changement
This commit is contained in:
parent
6d5e3f26ae
commit
c26a26c577
@ -1,5 +1,5 @@
|
||||
{
|
||||
"angleJoystickRadiusDeadband": 0.5,
|
||||
"angleJoystickRadiusDeadband": 0.6,
|
||||
"heading": {
|
||||
"p": 0.4,
|
||||
"i": 0,
|
||||
|
@ -21,6 +21,6 @@
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -21,6 +21,6 @@
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -16,11 +16,11 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 5,
|
||||
"id": 4,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -16,11 +16,11 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 4,
|
||||
"id": 5,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -7,7 +7,7 @@
|
||||
"iz": 0
|
||||
},
|
||||
"angle": {
|
||||
"p": 0.0020645,
|
||||
"p": 0.005,
|
||||
"i": 0,
|
||||
"d": 0,
|
||||
"f": 0,
|
||||
|
@ -3,6 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
@ -51,7 +52,7 @@ public class RobotContainer {
|
||||
|
||||
configureBindings();
|
||||
drive.setDefaultCommand(new RunCommand(()->{
|
||||
drive.drive(-joystick1.getY(), -joystick1.getX(), -joystick1.getZ());
|
||||
drive.drive(-joystick1.getY(), -joystick1.getX(), MathUtil.applyDeadband(-joystick1.getZ(), 0.2));
|
||||
},drive));
|
||||
}
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user