changement

This commit is contained in:
Antoine PerreaultE 2023-11-30 20:33:43 -05:00
parent 6d5e3f26ae
commit c26a26c577
7 changed files with 10 additions and 9 deletions

View File

@ -1,5 +1,5 @@
{ {
"angleJoystickRadiusDeadband": 0.5, "angleJoystickRadiusDeadband": 0.6,
"heading": { "heading": {
"p": 0.4, "p": 0.4,
"i": 0, "i": 0,

View File

@ -21,6 +21,6 @@
}, },
"inverted": { "inverted": {
"drive": false, "drive": false,
"angle": false "angle": true
} }
} }

View File

@ -21,6 +21,6 @@
}, },
"inverted": { "inverted": {
"drive": false, "drive": false,
"angle": false "angle": true
} }
} }

View File

@ -16,11 +16,11 @@
}, },
"encoder": { "encoder": {
"type": "cancoder", "type": "cancoder",
"id": 5, "id": 4,
"canbus": null "canbus": null
}, },
"inverted": { "inverted": {
"drive": false, "drive": false,
"angle": false "angle": true
} }
} }

View File

@ -16,11 +16,11 @@
}, },
"encoder": { "encoder": {
"type": "cancoder", "type": "cancoder",
"id": 4, "id": 5,
"canbus": null "canbus": null
}, },
"inverted": { "inverted": {
"drive": false, "drive": false,
"angle": false "angle": true
} }
} }

View File

@ -7,7 +7,7 @@
"iz": 0 "iz": 0
}, },
"angle": { "angle": {
"p": 0.0020645, "p": 0.005,
"i": 0, "i": 0,
"d": 0, "d": 0,
"f": 0, "f": 0,

View File

@ -3,6 +3,7 @@
// the WPILib BSD license file in the root directory of this project. // the WPILib BSD license file in the root directory of this project.
package frc.robot; package frc.robot;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
@ -51,7 +52,7 @@ public class RobotContainer {
configureBindings(); configureBindings();
drive.setDefaultCommand(new RunCommand(()->{ 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)); },drive));
} }