2023 Drive base
 
Loading...
Searching...
No Matches
frc.robot.subsystems.MecaDrive Class Reference
Inheritance diagram for frc.robot.subsystems.MecaDrive:
frc.robot.subsystems.DriveBase

Public Member Functions

 MecaDrive (int frontLeftMotorPort, int frontRightMotorPort, int rearLeftMotorPort, int rearRightMotorPort, IMU imu)
 
void drive (double speedX, double speedY, double rotateSpeed)
 
void printControlsOfCurrentMode ()
 Prints the controls of the current driving mode.
 
void cycleMotor ()
 Cycle between each motor during debug mode.
 
void printActiveMotorDebugMode ()
 prints the number of the currently activated motors during debug mode
 
void periodic ()
 
void updateOdometry ()
 
Pose2d getPose ()
 Returns the currently-estimated pose of the robot.
 
double getOdomX ()
 
double getOdomY ()
 
double getOdomHeading ()
 
void resetOdometry (Pose2d pose)
 Resets the odometry to the specified pose.
 
- Public Member Functions inherited from frc.robot.subsystems.DriveBase
void drive (double leftAnalogX, double leftAnalogY, double rightAnalogX, double rightAnalogY)
 Drive the robot with controller input.
 
void drive (double leftAnalogX, double leftAnalogY, double rightAnalogX)
 
abstract void printControlsOfCurrentMode ()
 Prints the controls of the current driving mode.
 
void increaseSpeedBracket ()
 The speed bracket controls the multiplier for al the speeds So when you change it, lets say, to 1/2 speed, all movement will be at 1/2 speed.
 
void decreaseSpeedBracket ()
 
void turnOnDefaultMode ()
 
void turnOnDebugMode ()
 
void turnOnStopMode ()
 should be overridden for actual functionality because depends on drive base specifc speeds (for tank drive, there is a left and right speed, whereas for mecanum there are 4)
 
void turnONPIDTuningMode ()
 
abstract void cycleMotor ()
 Needs to be implemented in sub classes becuase there might be different numbers of motors.
 
void AButtonPressed ()
 
void BButtonPressed ()
 
void XButtonPressed ()
 
void YButtonPressed ()
 
void leftBumperPressed ()
 
void rightBumperPressed ()
 
Mode getCurrentMode ()
 
void setCurrentMode (Mode currentMode)
 
int getDebugEnabledMotor ()
 
void setDebugEnabledMotor (int debugEnabledMotor)
 
Trajectory getCurrentTrajectory ()
 
void setCurrentTrajectory (Trajectory currentTrajectory)
 
TrajectoryConfig getTrajectoryConfig ()
 
RamseteController getChassisController ()
 
double getCurrentTrajectoryTime ()
 
void resetCurrentTrajectoryTime ()
 
void incrementCurrentTrajectoryTime ()
 

Private Member Functions

double slowDown (double inputVelocity)
 This will return a value lower than the input, and it is used to slow down the motors during stop mode.
 
double convertPosition (double rawPosition)
 Converts raw position units to meters.
 
double convertVelocity (double rawVelocity)
 Converts raw sensor velocity to meters/second.
 

Additional Inherited Members

- Protected Attributes inherited from frc.robot.subsystems.DriveBase
TrajectoryConfig trajectoryConfig
 

Detailed Description

Definition at line 19 of file MecaDrive.java.

Constructor & Destructor Documentation

◆ MecaDrive()

frc.robot.subsystems.MecaDrive.MecaDrive ( int  frontLeftMotorPort,
int  frontRightMotorPort,
int  rearLeftMotorPort,
int  rearRightMotorPort,
IMU  imu 
)

Definition at line 40 of file MecaDrive.java.

41 {
42
43 frontLeftMotor = new WPI_TalonFX(frontLeftMotorPort);
44 frontRightMotor = new WPI_TalonFX(frontRightMotorPort);
45 rearLeftMotor = new WPI_TalonFX(rearLeftMotorPort);
46 rearRightMotor = new WPI_TalonFX(rearRightMotorPort);
47
48 // invert motors to make forward the right direction
49 frontRightMotor.setInverted(true);
50 rearRightMotor.setInverted(true);
51
52 // zero encoders
53 frontLeftMotor.setSelectedSensorPosition(0);
54 frontRightMotor.setSelectedSensorPosition(0);
55 rearLeftMotor.setSelectedSensorPosition(0);
56 rearRightMotor.setSelectedSensorPosition(0);
57
58 mDrive = new MecanumDrive(frontLeftMotor, rearLeftMotor, frontRightMotor, rearRightMotor);
59
60 this.imu = imu;
61
62 // Odometry: !!secondary constructor takes initialPose argument
63 mOdom = new MecanumDriveOdometry(Constants.MECANUM_KINEMATICS, new Rotation2d(Math.toRadians(imu.getAngle())), getWheelPositions());
64
65 // see declaration in DriveBase
66 // set up the config for autonomous trajectories
67 // see another team's implementation https://github.com/FRC5254/FRC-5254-2020/blob/master/src/main/java/frc/robot/commands/auto/Path.java
68 // relevant info! https://www.chiefdelphi.com/t/poll-why-didnt-you-use-the-wpilib-trajectory-generator-this-year/384611/37
69 trajectoryConfig = new TrajectoryConfig(Constants.maxVelocityMetersPerSecond, Constants.maxAccelerationMetersPerSecond);
70 trajectoryConfig.setKinematics(Constants.MECANUM_KINEMATICS);
71 trajectoryConfig.addConstraint( // this may be unnessesary, hmm unsure
72 new MecanumDriveKinematicsConstraint(Constants.MECANUM_KINEMATICS, Constants.maxVelocityMetersPerSecond));
73 }
TrajectoryConfig trajectoryConfig
Definition: DriveBase.java:35

References frc.robot.Constants.maxAccelerationMetersPerSecond, frc.robot.Constants.maxVelocityMetersPerSecond, frc.robot.Constants.MECANUM_KINEMATICS, and frc.robot.subsystems.DriveBase.trajectoryConfig.

Member Function Documentation

◆ convertPosition()

double frc.robot.subsystems.MecaDrive.convertPosition ( double  rawPosition)
private

Converts raw position units to meters.

Parameters
rawPositionthe position from an encoder in raw sensor units
Returns
the position in meters

Definition at line 203 of file MecaDrive.java.

203 {
204 // raw units are "clicks," so divide by "clicks" per rotation to get rotations
205 // also account for gear ratio because the encoders measure motor output, not actual wheel
206 double position = rawPosition / (Constants.TALON_FX_CPR * Constants.FALCON_GEARBOX_RATIO);
207 // multiply by circumference to get linear distance
208 position *= Math.PI * Constants.MECANUM_WHEEL_DIAMETER;
209 return position;
210 }

References frc.robot.Constants.FALCON_GEARBOX_RATIO, and frc.robot.Constants.MECANUM_WHEEL_DIAMETER.

◆ convertVelocity()

double frc.robot.subsystems.MecaDrive.convertVelocity ( double  rawVelocity)
private

Converts raw sensor velocity to meters/second.

Parameters
rawVelocitythe velocity from an encoder in raw sensor units
Returns
velocity in m/s

Definition at line 232 of file MecaDrive.java.

232 {
233 // convert to rotations per second because raw units are "clicks" per 100ms
234 // also account for gear ratio because the encoders measure motor output, not actual wheel
235 double velocity = rawVelocity / (Constants.TALON_FX_CPR * Constants.FALCON_GEARBOX_RATIO) * 10;
236 // multiply by circumference to get linear velocity
237 velocity *= Math.PI * Constants.MECANUM_WHEEL_DIAMETER;
238 return velocity;
239 }

References frc.robot.Constants.FALCON_GEARBOX_RATIO, and frc.robot.Constants.MECANUM_WHEEL_DIAMETER.

◆ cycleMotor()

void frc.robot.subsystems.MecaDrive.cycleMotor ( )

Cycle between each motor during debug mode.

Reimplemented from frc.robot.subsystems.DriveBase.

Definition at line 170 of file MecaDrive.java.

170 {
171 if (currentMode == Mode.DEBUG_MODE) {
172 debugEnabledMotor++;
173 debugEnabledMotor %= 4;
174 System.out.println("Current Motor: " + debugEnabledMotor);
175 }
176 }

Referenced by frc.robot.Robot.checkForButtonPresses().

◆ drive()

void frc.robot.subsystems.MecaDrive.drive ( double  speedX,
double  speedY,
double  rotateSpeed 
)

Reimplemented from frc.robot.subsystems.DriveBase.

Definition at line 76 of file MecaDrive.java.

76 {
77 speedX *= speedMultiplier;
78 speedY *= speedMultiplier;
79 rotateSpeed *= speedMultiplier;
80 // these speeds are linearized from 1 to -1
81
82 switch (currentMode){
83 case STOP_MODE:
84 // STOP!!!!! set motors to 0
85 // slower stop
86 speedX = slowDown(speedX);
87 speedY = slowDown(speedY);
88 rotateSpeed = slowDown(rotateSpeed);
89 break;
90
91 // TODO: figure out how to implement a debug mode
92 // case DEBUG_MODE:
93 // // Debug mode (toggle wheels with left stick button)
94
95 // switch (debugEnabledMotor){
96 // case 0:
97 // frontLeftMotor.set(ControlMode.PercentOutput, combinedSpeeds[0]);
98 // break;
99 // case 1:
100 // frontRightMotor.set(ControlMode.PercentOutput, combinedSpeeds[1]);
101 // break;
102 // case 2:
103 // rearLeftMotor.set(ControlMode.PercentOutput, combinedSpeeds[2]);
104 // break;
105 // case 3:
106 // rearRightMotor.set(ControlMode.PercentOutput, combinedSpeeds[3]);
107 // break;
108 // }
109
110 // break;
111 case PID_TUNING_MODE:
112 // nothing yet
113 break;
114 default:
115 break;
116 }
117
118 // method defines Y as left/right and X as forward/backward - contrary to docs, right and forward are positive
119 // https://docs.wpilib.org/en/stable/docs/software/pathplanning/trajectory-tutorial/creating-drive-subsystem.html
120 mDrive.driveCartesian(speedY, speedX, rotateSpeed);
121 }
double slowDown(double inputVelocity)
This will return a value lower than the input, and it is used to slow down the motors during stop mod...
Definition: MecaDrive.java:130

References frc.robot.subsystems.MecaDrive.slowDown().

Referenced by frc.robot.subsystems.Autonomous.applyChassisSpeeds(), frc.robot.Robot.autonomousPeriodic(), and frc.robot.Robot.drive().

◆ getOdomHeading()

double frc.robot.subsystems.MecaDrive.getOdomHeading ( )

Definition at line 270 of file MecaDrive.java.

270 {
271 return mOdom.getPoseMeters().getRotation().getDegrees();
272 }

Referenced by frc.robot.subsystems.BetterShuffleboard.pushOdom().

◆ getOdomX()

double frc.robot.subsystems.MecaDrive.getOdomX ( )

Definition at line 262 of file MecaDrive.java.

262 {
263 return mOdom.getPoseMeters().getTranslation().getX();
264 }

Referenced by frc.robot.subsystems.BetterShuffleboard.pushOdom().

◆ getOdomY()

double frc.robot.subsystems.MecaDrive.getOdomY ( )

Definition at line 266 of file MecaDrive.java.

266 {
267 return mOdom.getPoseMeters().getTranslation().getY();
268 }

Referenced by frc.robot.subsystems.BetterShuffleboard.pushOdom().

◆ getPose()

Pose2d frc.robot.subsystems.MecaDrive.getPose ( )

Returns the currently-estimated pose of the robot.

Returns
The pose.

Definition at line 258 of file MecaDrive.java.

258 {
259 return mOdom.getPoseMeters();
260 }

Referenced by frc.robot.Robot.autonomousCheckForButtonPresses(), frc.robot.subsystems.Autonomous.getChassisSpeeds(), and frc.robot.subsystems.Autonomous.updateTrajectory().

◆ periodic()

void frc.robot.subsystems.MecaDrive.periodic ( )

Definition at line 190 of file MecaDrive.java.

190 {
191 // Update the odometry in the periodic block
192 }

◆ printActiveMotorDebugMode()

void frc.robot.subsystems.MecaDrive.printActiveMotorDebugMode ( )

prints the number of the currently activated motors during debug mode

Definition at line 181 of file MecaDrive.java.

181 {
182 if (currentMode == Mode.DEBUG_MODE) {
183 System.out.println("Current Motor: " + debugEnabledMotor);
184 }
185 }

Referenced by frc.robot.Robot.checkForButtonPresses().

◆ printControlsOfCurrentMode()

void frc.robot.subsystems.MecaDrive.printControlsOfCurrentMode ( )

Prints the controls of the current driving mode.

Reimplemented from frc.robot.subsystems.DriveBase.

Definition at line 142 of file MecaDrive.java.

142 {
143 System.out.println("Controls:");
144 switch(currentMode) {
145 case DEFAULT_MODE:
146 System.out.println("Left Bracket: Decrease speed multiplier");
147 System.out.println("Right Bracket: Increase speed multiplier");
148 break;
149 case DEBUG_MODE:
150 System.out.println("A: Cycle active motor");
151 System.out.println("B: Print current active motor");
152 System.out.println("Left Bracket: Decrease speed multiplier");
153 System.out.println("Right Bracket: Increase speed multiplier");
154 break;
155 case STOP_MODE:
156 System.out.println("Left Bracket: Decrease speed multiplier");
157 System.out.println("Right Bracket: Increase speed multiplier");
158 break;
159 case PID_TUNING_MODE:
160 System.out.println("Left Bracket: Decrease speed multiplier");
161 System.out.println("Right Bracket: Increase speed multiplier");
162 break;
163 }
164 }

◆ resetOdometry()

void frc.robot.subsystems.MecaDrive.resetOdometry ( Pose2d  pose)

Resets the odometry to the specified pose.

Parameters
poseThe pose to which to set the odometry.

Definition at line 283 of file MecaDrive.java.

283 {
284 //resetEncoders();
285 mOdom.resetPosition(
286 new Rotation2d(Math.toRadians(imu.getAngle())), getWheelPositions(), pose);
287 }

◆ slowDown()

double frc.robot.subsystems.MecaDrive.slowDown ( double  inputVelocity)
private

This will return a value lower than the input, and it is used to slow down the motors during stop mode.

Parameters
inputVelocitybetween -1 and 1 (double)
Returns
the new value (lower)

Definition at line 130 of file MecaDrive.java.

130 {
131 // velocity needs to be reduced
132 double newVelocity = inputVelocity / Constants.SLOW_DOWN_FACTOR;
133
134 // input has reached cutoff, now returning 0 speed
135 if (Math.abs(inputVelocity) < Constants.SLOW_DOWN_CUTOFF){
136 newVelocity = 0;
137 }
138
139 return newVelocity;
140 }

References frc.robot.Constants.SLOW_DOWN_CUTOFF, and frc.robot.Constants.SLOW_DOWN_FACTOR.

Referenced by frc.robot.subsystems.MecaDrive.drive().

◆ updateOdometry()

void frc.robot.subsystems.MecaDrive.updateOdometry ( )

Definition at line 194 of file MecaDrive.java.

194 {
195 mOdom.update(new Rotation2d(Math.toRadians(imu.getHeading())), getWheelPositions());
196 }
double getHeading()
Definition: IMU.java:18

References frc.robot.subsystems.IMU.getHeading().

Referenced by frc.robot.Robot.robotPeriodic().


The documentation for this class was generated from the following file: