diff --git a/commands/absoluterelativedrive.py b/commands/absoluterelativedrive.py index c23a512..78ec5bc 100644 --- a/commands/absoluterelativedrive.py +++ b/commands/absoluterelativedrive.py @@ -48,8 +48,8 @@ def rotation(self) -> float: def execute(self) -> None: self.drive.arcadeDriveWithFactors( - self.forward(), - self.sideways(), + -self.forward(), + -self.sideways(), self.rotation(), DriveSubsystem.CoordinateMode.FieldRelative, ) diff --git a/commands/fieldrelativedrive.py b/commands/fieldrelativedrive.py index 019cb55..16d43e3 100644 --- a/commands/fieldrelativedrive.py +++ b/commands/fieldrelativedrive.py @@ -24,8 +24,8 @@ def __init__( def execute(self) -> None: self.drive.arcadeDriveWithFactors( - self.forward(), - self.sideways(), + -self.forward(), + -self.sideways(), self.rotation(), DriveSubsystem.CoordinateMode.FieldRelative, ) diff --git a/controlInterface.json b/controlInterface.json index 1b214d9..b62273d 100644 --- a/controlInterface.json +++ b/controlInterface.json @@ -14,7 +14,7 @@ "rotationX": [ 1, { - "Axis": 0 + "Axis": 5 } ], "rotationY": [ diff --git a/networktables.json b/networktables.json new file mode 100644 index 0000000..cb9ee20 --- /dev/null +++ b/networktables.json @@ -0,0 +1,210 @@ +[ + { + "name": "/Preferences/forwardsBackwards controller", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/forwardsBackwards axis", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/leftRight controller", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/leftRight axis", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/rotationX controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/rotationX axis", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/rotationY controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/rotationY axis", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/fillCannon controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/fillCannon button", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/launchCannon controller", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/launchCannon button", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/closeValves controller", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/closeValves button", + "type": "int", + "value": 2, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/resetSwerveControl controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/resetSwerveControl button", + "type": "int", + "value": 10, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/returnPositionInput controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/returnPositionInput button", + "type": "int", + "value": 4, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/returnModeControl controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/returnModeControl button", + "type": "int", + "value": 5, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/pulseTheLights controller", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/pulseTheLights button", + "type": "int", + "value": 3, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/hornControl controller", + "type": "int", + "value": 1, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/hornControl button", + "type": "int", + "value": 2, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/lightControl controller", + "type": "int", + "value": 0, + "properties": { + "persistent": true + } + }, + { + "name": "/Preferences/lightControl button", + "type": "int", + "value": 4, + "properties": { + "persistent": true + } + } +] diff --git a/networktables.json.bck b/networktables.json.bck new file mode 100644 index 0000000..fe51488 --- /dev/null +++ b/networktables.json.bck @@ -0,0 +1 @@ +[] diff --git a/operatorinterface.py b/operatorinterface.py index 8539101..97554c3 100644 --- a/operatorinterface.py +++ b/operatorinterface.py @@ -103,11 +103,11 @@ def __init__(self) -> None: for control in controlScheme: binding = controlScheme[control] - self.prefs.initInt(control + " controller", binding[0]) + self.prefs.setInt(control + " controller", binding[0]) if "Button" in binding[1].keys(): - self.prefs.initInt(control + " button", binding[1]["Button"]) + self.prefs.setInt(control + " button", binding[1]["Button"]) elif "Axis" in binding[1].keys(): - self.prefs.initInt(control + " axis", binding[1]["Axis"]) + self.prefs.setInt(control + " axis", binding[1]["Axis"]) for num in controllerNumbers: controller = Joystick(num) diff --git a/robotcontainer.py b/robotcontainer.py index ef0ff79..db19eb0 100644 --- a/robotcontainer.py +++ b/robotcontainer.py @@ -87,12 +87,11 @@ def __init__(self) -> None: self.configureButtonBindings() self.drive.setDefaultCommand( - AbsoluteRelativeDrive( + FieldRelativeDrive( self.drive, self.operatorInterface.chassisControls.forwardsBackwards, self.operatorInterface.chassisControls.sideToSide, self.operatorInterface.chassisControls.rotationX, - self.operatorInterface.chassisControls.rotationY, ) ) diff --git a/subsystems/cannonsubsystem.py b/subsystems/cannonsubsystem.py index 2c7be51..39d5d22 100644 --- a/subsystems/cannonsubsystem.py +++ b/subsystems/cannonsubsystem.py @@ -26,10 +26,6 @@ class State(Enum): Filling = auto() Launching = auto() - def periodic(self) -> None: - SmartDashboard.putNumber(constants.kCannonStateKey, self.state.value) - SmartDashboard.putNumber(constants.kPressureKey, self.getPressure()) - def __init__(self) -> None: SubsystemBase.__init__(self) self.launchSolonoid = WPI_TalonSRX(constants.kCannonLaunchVictorDeviceID) @@ -50,6 +46,8 @@ def __init__(self) -> None: def periodic(self) -> None: self.compresser.set(Relay.Value.kOn) + SmartDashboard.putNumber(constants.kCannonStateKey, self.state.value) + SmartDashboard.putNumber(constants.kPressureKey, self.getPressure()) def getPressure(self) -> float: return map_range(