Changer id swerve
This commit is contained in:
parent
1dc4b31f4f
commit
633ebb0ac9
@ -88,5 +88,10 @@
|
||||
"buttonCount": 0,
|
||||
"povCount": 0
|
||||
}
|
||||
],
|
||||
"robotJoysticks": [
|
||||
{
|
||||
"guid": "030000006d04000015c2000000000000"
|
||||
}
|
||||
]
|
||||
}
|
||||
|
11
simgui.json
11
simgui.json
@ -1,7 +1,16 @@
|
||||
{
|
||||
"NTProvider": {
|
||||
"types": {
|
||||
"/FMSInfo": "FMSInfo"
|
||||
"/FMSInfo": "FMSInfo",
|
||||
"/SmartDashboard/Field": "Field2d",
|
||||
"/SmartDashboard/navX-Sensor[1]": "Gyro"
|
||||
},
|
||||
"windows": {
|
||||
"/SmartDashboard/Field": {
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -11,12 +11,12 @@
|
||||
},
|
||||
"angle": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 1,
|
||||
"canbus": null
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 0,
|
||||
"id": 2,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
|
@ -6,17 +6,17 @@
|
||||
"absoluteEncoderOffset": 0,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 3,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 4,
|
||||
"canbus": null
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 0,
|
||||
"id": 5,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
|
@ -6,17 +6,17 @@
|
||||
"absoluteEncoderOffset": 0,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 6,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 7,
|
||||
"canbus": null
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 0,
|
||||
"id": 8,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
|
@ -6,17 +6,17 @@
|
||||
"absoluteEncoderOffset": 0,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 9,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "sparkmax",
|
||||
"id": 0,
|
||||
"id": 10,
|
||||
"canbus": null
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 0,
|
||||
"id": 11,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
|
@ -22,7 +22,7 @@ public class RobotContainer {
|
||||
// drive.drive(manette.getLeftX(), manette.getLeftY(), manette.getRightX());
|
||||
//},drive));
|
||||
drive.setDefaultCommand(new RunCommand(()->{
|
||||
drive.drive(joystick1.getX(), -joystick1.getY(), joystick1.getZ());
|
||||
drive.drive(joystick1.getX(), -joystick1.getY(), -joystick1.getZ());
|
||||
},drive));
|
||||
}
|
||||
|
||||
|
@ -18,7 +18,7 @@ public class Drive extends SubsystemBase {
|
||||
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
||||
|
||||
public void drive(double x, double y, double zRotation){
|
||||
swerveDrive.drive(new Translation2d(x, y), zRotation, true, true);
|
||||
swerveDrive.drive(new Translation2d(x, y), zRotation, true, false);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user