|
| 1 | +#!/usr/bin/env python3 |
| 2 | +""" |
| 3 | + This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation vectors |
| 4 | + in relation to the starting orientation of the robot (field-oriented controls). |
| 5 | +""" |
| 6 | + |
| 7 | +import wpilib |
| 8 | +import wpilib.drive |
| 9 | + |
| 10 | + |
| 11 | +class MyRobot(wpilib.TimedRobot): |
| 12 | + |
| 13 | + # gyro calibration constant, may need to be adjusted; |
| 14 | + # gyro value of 360 is set to correspond to one full revolution |
| 15 | + VOLTS_PER_DEGREE_PER_SECOND = 0.0128 |
| 16 | + |
| 17 | + FRONT_LEFT_CHANNEL = 0 |
| 18 | + REAR_LEFT_CHANNEL = 1 |
| 19 | + FRONT_RIGHT_CHANNEL = 2 |
| 20 | + REAR_RIGHT_CHANNEL = 3 |
| 21 | + GYRO_PORT = 0 |
| 22 | + JOYSTICK_PORT = 0 |
| 23 | + |
| 24 | + def robotInit(self): |
| 25 | + """Robot initialization function""" |
| 26 | + |
| 27 | + self.gyro = wpilib.AnalogGyro(self.GYRO_PORT) |
| 28 | + self.joystick = wpilib.Joystick(self.JOYSTICK_PORT) |
| 29 | + |
| 30 | + frontLeft = wpilib.PWMSparkMax(self.FRONT_LEFT_CHANNEL) |
| 31 | + rearLeft = wpilib.PWMSparkMax(self.REAR_LEFT_CHANNEL) |
| 32 | + frontRight = wpilib.PWMSparkMax(self.FRONT_RIGHT_CHANNEL) |
| 33 | + rearRight = wpilib.PWMSparkMax(self.REAR_RIGHT_CHANNEL) |
| 34 | + |
| 35 | + frontRight.setInverted(True) |
| 36 | + rearRight.setInverted(True) |
| 37 | + |
| 38 | + self.robotDrive = wpilib.drive.MecanumDrive( |
| 39 | + frontLeft, rearLeft, frontRight, rearRight |
| 40 | + ) |
| 41 | + |
| 42 | + self.gyro.setSensitivity(self.VOLTS_PER_DEGREE_PER_SECOND) |
| 43 | + |
| 44 | + def teleopPeriodic(self): |
| 45 | + self.robotDrive.driveCartesian( |
| 46 | + -self.joystick.getY(), -self.joystick.getX(), -self.joystick.getZ(), |
| 47 | + self.gyro.getRotation2d() |
| 48 | + ) |
| 49 | + |
| 50 | + |
| 51 | +if __name__ == "__main__": |
| 52 | + wpilib.run(MyRobot) |
0 commit comments