diff --git a/commands-v2/armbot/constants.py b/commands-v2/armbot/constants.py new file mode 100644 index 0000000..357acfb --- /dev/null +++ b/commands-v2/armbot/constants.py @@ -0,0 +1,61 @@ +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +""" +The constants module is a convenience place for teams to hold robot-wide +numerical or boolean constants. Don't use this for any other purpose! +""" + +import math + + +class DriveConstants: + # The PWM IDs for the drivetrain motor controllers. + kLeftMotor1Port = 0 + kLeftMotor2Port = 1 + kRightMotor1Port = 2 + kRightMotor2Port = 3 + + # Encoders and their respective motor controllers. + kLeftEncoderPorts = (0, 1) + kRightEncoderPorts = (2, 3) + kLeftEncoderReversed = False + kRightEncoderReversed = True + + # Encoder counts per revolution/rotation. + kEncoderCPR = 1024 + kWheelDiameterInches = 6 + + # Assumes the encoders are directly mounted on the wheel shafts + kEncoderDistancePerPulse = (kWheelDiameterInches * math.pi) / kEncoderCPR + + +class ArmConstants: + # NOTE: Please do NOT use these values on your robot. + kMotorPort = 4 + kP = 1 + kSVolts = 1 + kGVolts = 1 + kVVoltSecondPerRad = 0.5 + kAVoltSecondSquaredPerRad = 0.1 + + kMaxVelocityRadPerSecond = 3 + kMaxAccelerationRadPerSecSquared = 10 + + kEncoderPorts = (4, 5) + kEncoderPPR = 256 + kEncoderDistancePerPulse = 2.0 * math.pi / kEncoderPPR + + # The offset of the arm from the horizontal in its neutral position, + # measured from the horizontal + kArmOffsetRads = 0.5 + + +class AutoConstants: + kAutoTimeoutSeconds = 12 + kAutoShootTimeSeconds = 7 + + +class OIConstants: + kDriverControllerPort = 0 diff --git a/commands-v2/armbot/robot.py b/commands-v2/armbot/robot.py new file mode 100644 index 0000000..e782f47 --- /dev/null +++ b/commands-v2/armbot/robot.py @@ -0,0 +1,83 @@ +#!usr/bin/env python3 + +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +import wpilib +import commands2 +import typing + +from robotcontainer import RobotContainer + + +class MyRobot(commands2.TimedCommandRobot): + """ + Our default robot class, pass it to wpilib.run + Command v2 robots are encouraged to inherit from TimedCommandRobot, which + has an implementation of robotPeriodic which runs the scheduler for you + """ + + autonomousCommand: typing.Optional[commands2.Command] = None + + def robotInit(self) -> None: + """ + This function is run when the robot is first started up and should be used for any + initialization code. + """ + + # Instantiate our RobotContainer. This will perform all our button bindings, and put our + # autonomous chooser on the dashboard. + self.container = RobotContainer() + + def robotPeriodic(self) -> None: + """This function is called every 20 ms, no matter the mode. Use this for items like diagnostics + that you want ran during disabled, autonomous, teleoperated and test. + + This runs after the mode specific periodic functions, but before LiveWindow and + SmartDashboard integrated updating.""" + + # Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled + # commands, running already-scheduled commands, removing finished or interrupted commands, + # and running subsystem periodic() methods. This must be called from the robot's periodic + # block in order for anything in the Command-based framework to work. + commands2.CommandScheduler.getInstance().run() + + def disabledInit(self) -> None: + """This function is called once each time the robot enters Disabled mode.""" + self.container.disablePIDSubsystems() + + def disabledPeriodic(self) -> None: + """This function is called periodically when disabled""" + pass + + def autonomousInit(self) -> None: + """This autonomous runs the autonomous command selected by your RobotContainer class.""" + self.autonomousCommand = self.container.getAutonomousCommand() + + if self.autonomousCommand: + self.autonomousCommand.schedule() + + def autonomousPeriodic(self) -> None: + """This function is called periodically during autonomous""" + pass + + def teleopInit(self) -> None: + # This makes sure that the autonomous stops running when + # teleop starts running. If you want the autonomous to + # continue until interrupted by another command, remove + # this line or comment it out. + if self.autonomousCommand: + self.autonomousCommand.cancel() + + def teleopPeriodic(self) -> None: + """This function is called periodically during operator control""" + pass + + def testInit(self) -> None: + # Cancels all running commands at the start of test mode + commands2.CommandScheduler.getInstance().cancelAll() + + +if __name__ == "__main__": + wpilib.run(MyRobot) diff --git a/commands-v2/armbot/robotcontainer.py b/commands-v2/armbot/robotcontainer.py new file mode 100644 index 0000000..ba4213b --- /dev/null +++ b/commands-v2/armbot/robotcontainer.py @@ -0,0 +1,96 @@ +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +import commands2 +import commands2.button +import commands2.cmd + +import constants + +from subsystems.armsubsystem import ArmSubsystem +from subsystems.drivesubsystem import DriveSubsystem + + +class RobotContainer: + """ + This class is where the bulk of the robot should be declared. Since Command-based is a + "declarative" paradigm, very little robot logic should actually be handled in the :class:`.Robot` + periodic methods (other than the scheduler calls). Instead, the structure of the robot (including + subsystems, commands, and button mappings) should be declared here. + """ + + def __init__(self) -> None: + # The robot's subsystems + self.robot_drive = DriveSubsystem() + self.robot_arm = ArmSubsystem() + + # The driver's controller + self.driver_controller = commands2.button.CommandXboxController( + constants.OIConstants.kDriverControllerPort + ) + + # Configure the button bindings + self.configureButtonBindings() + + # Set the default drive command + # Set the default drive command to split-stick arcade drive + self.robot_drive.setDefaultCommand( + commands2.cmd.run( + # A split-stick arcade command, with forward/backward controlled by the left + # hand, and turning controlled by the right. + lambda: self.robot_drive.arcadeDrive( + -self.driver_controller.getLeftY(), + -self.driver_controller.getRightX(), + ), + [self.robot_drive], + ) + ) + + def configureButtonBindings(self) -> None: + """ + Use this method to define your button->command mappings. Buttons can be created by + instantiating a :GenericHID or one of its subclasses (Joystick or XboxController), + and then passing it to a JoystickButton. + """ + + # Move the arm to 2 radians above horizontal when the 'A' button is pressed. + self.driver_controller.A().onTrue( + commands2.cmd.run(self.moveArm(2), [self.robot_arm]) + ) + + # Move the arm to neutral position when the 'B' button is pressed + self.driver_controller.B().onTrue( + commands2.cmd.run( + self.moveArm(constants.ArmConstants.kArmOffsetRads), [self.robot_arm] + ) + ) + + # Disable the arm controller when Y is pressed + self.driver_controller.Y().onTrue( + commands2.cmd.runOnce(lambda: self.robot_arm.disable()) + ) + + # Drive at half speed when the bumper is held + self.driver_controller.rightTrigger().onTrue( + commands2.cmd.runOnce(lambda: self.robot_drive.setMaxOutput(0.5)) + ) + self.driver_controller.rightTrigger().onFalse( + commands2.cmd.runOnce(lambda: self.robot_drive.setMaxOutput(1.0)) + ) + + def disablePIDSubsystems(self) -> None: + """Disables all ProfiledPIDSubsystem and PIDSubsystem instances. + This should be called on robot disable to prevent integral windup.""" + self.robot_arm.disable() + + def getAutonomousCommand(self) -> commands2.Command: + """Use this to pass the autonomous command to the main {@link Robot} class. + + :returns: the command to run in autonomous + """ + return commands2.cmd.nothing() + + def moveArm(self, radians: int) -> None: + self.robot_arm.setGoal(radians) + self.robot_arm.enable() diff --git a/commands-v2/armbot/subsystems/armsubsystem.py b/commands-v2/armbot/subsystems/armsubsystem.py new file mode 100644 index 0000000..ec161bb --- /dev/null +++ b/commands-v2/armbot/subsystems/armsubsystem.py @@ -0,0 +1,60 @@ +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +import wpilib +import commands2 +import wpimath.controller +import wpimath.trajectory + +import constants + + +class ArmSubsystem(commands2.ProfiledPIDSubsystem): + """A robot arm subsystem that moves with a motion profile.""" + + # Create a new ArmSubsystem + def __init__(self) -> None: + super().__init__( + wpimath.controller.ProfiledPIDController( + constants.ArmConstants.kP, + 0, + 0, + wpimath.trajectory.TrapezoidProfile.Constraints( + constants.ArmConstants.kMaxVelocityRadPerSecond, + constants.ArmConstants.kMaxAccelerationRadPerSecSquared, + ), + ), + 0, + ) + + self.motor = wpilib.PWMSparkMax(constants.ArmConstants.kMotorPort) + self.encoder = wpilib.Encoder( + constants.ArmConstants.kEncoderPorts[0], + constants.ArmConstants.kEncoderPorts[1], + ) + self.feedforward = wpimath.controller.ArmFeedforward( + constants.ArmConstants.kSVolts, + constants.ArmConstants.kGVolts, + constants.ArmConstants.kVVoltSecondPerRad, + constants.ArmConstants.kAVoltSecondSquaredPerRad, + ) + + self.encoder.setDistancePerPulse( + constants.ArmConstants.kEncoderDistancePerPulse + ) + + # Start arm at rest in neutral position + self.setGoal(constants.ArmConstants.kArmOffsetRads) + + def _useOutput( + self, output: float, setpoint: wpimath.trajectory.TrapezoidProfile.State + ) -> None: + # Calculate the feedforward from the setpoint + feedforward = self.feedforward.calculate(setpoint.position, setpoint.velocity) + + # Add the feedforward to the PID output to get the motor output + self.motor.setVoltage(output + feedforward) + + def _getMeasurement(self) -> float: + return self.encoder.getDistance() + constants.ArmConstants.kArmOffsetRads diff --git a/commands-v2/armbot/subsystems/drivesubsystem.py b/commands-v2/armbot/subsystems/drivesubsystem.py new file mode 100644 index 0000000..9daf44f --- /dev/null +++ b/commands-v2/armbot/subsystems/drivesubsystem.py @@ -0,0 +1,101 @@ +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +import wpilib +import wpilib.drive +import commands2 + +import constants + + +class DriveSubsystem(commands2.SubsystemBase): + + # Creates a new DriveSubsystem + def __init__(self) -> None: + super().__init__() + + # The motors on the left side of the drive + self.left_motors = wpilib.MotorControllerGroup( + wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor1Port), + wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor2Port), + ) + + # The motors on the right side of the drive + self.right_motors = wpilib.MotorControllerGroup( + wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor1Port), + wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor2Port), + ) + + # The robot's drive + self.drive = wpilib.drive.DifferentialDrive(self.left_motors, self.right_motors) + + # The left-side drive encoder + self.left_encoder = wpilib.Encoder( + constants.DriveConstants.kLeftEncoderPorts[0], + constants.DriveConstants.kLeftEncoderPorts[1], + constants.DriveConstants.kLeftEncoderReversed, + ) + + # The right-side drive encoder + self.right_encoder = wpilib.Encoder( + constants.DriveConstants.kRightEncoderPorts[0], + constants.DriveConstants.kRightEncoderPorts[1], + constants.DriveConstants.kRightEncoderReversed, + ) + + # Sets the distance per pulse for the encoders + self.left_encoder.setDistancePerPulse( + constants.DriveConstants.kEncoderDistancePerPulse + ) + self.right_encoder.setDistancePerPulse( + constants.DriveConstants.kEncoderDistancePerPulse + ) + + # We need to invert one side of the drivetrain so that positive voltages + # result in both sides moving forward. Depending on how your robot's + # gearbox is constructed, you might have to invert the left side instead. + self.right_motors.setInverted(True) + + def arcadeDrive(self, fwd: float, rot: float) -> None: + """Drives the robot using arcade controls. + + :param fwd: the commanded forward movement + :param rot: the commanded rotation + """ + self.drive.arcadeDrive(fwd, rot) + + def resetEncoders(self) -> None: + """Resets the drive encoders to currently read a position of 0.""" + self.left_encoder.reset() + self.right_encoder.reset() + + def getAverageEncoderDistance(self) -> float: + """Gets the average distance of the two encoders. + + :returns: the average of the two encoder readings + """ + return ( + self.left_encoder.getDistance() + self.right_encoder.getDistance() + ) / 2.0 + + def getLeftEncoder(self) -> wpilib.Encoder: + """Gets the left drive encoder. + + :returns: the left drive encoder + """ + return self.left_encoder + + def getRightEncoder(self) -> wpilib.Encoder: + """Gets the right drive encoder. + + :returns: the right drive encoder + """ + return self.right_encoder + + def setMaxOutput(self, max_output: float) -> None: + """Sets the max output of the drive. Useful for scaling the drive to drive more slowly. + + :param maxOutput: the maximum output to which the drive will be constrained + """ + self.drive.setMaxOutput(max_output) diff --git a/run_tests.sh b/run_tests.sh index 50b78bc..b311a55 100755 --- a/run_tests.sh +++ b/run_tests.sh @@ -7,6 +7,7 @@ BASE_TESTS=" addressableled arcade-drive arm-simulation + commands-v2/armbot commands-v2/armbotoffboard commands-v2/drive-distance-offboard commands-v2/frisbee-bot