001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj.drive; 006 007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; 008 009import edu.wpi.first.hal.FRCNetComm.tInstances; 010import edu.wpi.first.hal.FRCNetComm.tResourceType; 011import edu.wpi.first.hal.HAL; 012import edu.wpi.first.math.MathUtil; 013import edu.wpi.first.math.geometry.Rotation2d; 014import edu.wpi.first.math.geometry.Translation2d; 015import edu.wpi.first.util.sendable.Sendable; 016import edu.wpi.first.util.sendable.SendableBuilder; 017import edu.wpi.first.util.sendable.SendableRegistry; 018import edu.wpi.first.wpilibj.motorcontrol.MotorController; 019import java.util.function.DoubleConsumer; 020 021/** 022 * A class for driving Mecanum drive platforms. 023 * 024 * <p>Mecanum drives are rectangular with one wheel on each corner. Each wheel has rollers toed in 025 * 45 degrees toward the front or back. When looking at the wheels from the top, the roller axles 026 * should form an X across the robot. Each drive() function provides different inverse kinematic 027 * relations for a Mecanum drive robot. 028 * 029 * <p>Drive base diagram: 030 * 031 * <pre> 032 * \\_______/ 033 * \\ | | / 034 * | | 035 * /_|___|_\\ 036 * / \\ 037 * </pre> 038 * 039 * <p>Each drive() function provides different inverse kinematic relations for a Mecanum drive 040 * robot. 041 * 042 * <p>This library uses the NWU axes convention (North-West-Up as external reference in the world 043 * frame). The positive X axis points ahead, the positive Y axis points to the left, and the 044 * positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation 045 * around the Z axis is positive. 046 * 047 * <p>Inputs smaller then {@value edu.wpi.first.wpilibj.drive.RobotDriveBase#kDefaultDeadband} will 048 * be set to 0, and larger values will be scaled so that the full range is still used. This deadband 049 * value can be changed with {@link #setDeadband}. 050 * 051 * <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The driveCartesian or 052 * drivePolar methods should be called periodically to avoid Motor Safety timeouts. 053 */ 054public class MecanumDrive extends RobotDriveBase implements Sendable, AutoCloseable { 055 private static int instances; 056 057 private final DoubleConsumer m_frontLeftMotor; 058 private final DoubleConsumer m_rearLeftMotor; 059 private final DoubleConsumer m_frontRightMotor; 060 private final DoubleConsumer m_rearRightMotor; 061 062 // Used for Sendable property getters 063 private double m_frontLeftOutput; 064 private double m_rearLeftOutput; 065 private double m_frontRightOutput; 066 private double m_rearRightOutput; 067 068 private boolean m_reported; 069 070 /** 071 * Wheel speeds for a mecanum drive. 072 * 073 * <p>Uses normalized voltage [-1.0..1.0]. 074 */ 075 @SuppressWarnings("MemberName") 076 public static class WheelSpeeds { 077 /** Front-left wheel speed. */ 078 public double frontLeft; 079 080 /** Front-right wheel speed. */ 081 public double frontRight; 082 083 /** Rear-left wheel speed. */ 084 public double rearLeft; 085 086 /** Rear-right wheel speed. */ 087 public double rearRight; 088 089 /** Constructs a WheelSpeeds with zeroes for all four speeds. */ 090 public WheelSpeeds() {} 091 092 /** 093 * Constructs a WheelSpeeds. 094 * 095 * @param frontLeft The front left speed [-1.0..1.0]. 096 * @param frontRight The front right speed [-1.0..1.0]. 097 * @param rearLeft The rear left speed [-1.0..1.0]. 098 * @param rearRight The rear right speed [-1.0..1.0]. 099 */ 100 public WheelSpeeds(double frontLeft, double frontRight, double rearLeft, double rearRight) { 101 this.frontLeft = frontLeft; 102 this.frontRight = frontRight; 103 this.rearLeft = rearLeft; 104 this.rearRight = rearRight; 105 } 106 } 107 108 /** 109 * Construct a MecanumDrive. 110 * 111 * <p>If a motor needs to be inverted, do so before passing it in. 112 * 113 * @param frontLeftMotor The motor on the front-left corner. 114 * @param rearLeftMotor The motor on the rear-left corner. 115 * @param frontRightMotor The motor on the front-right corner. 116 * @param rearRightMotor The motor on the rear-right corner. 117 */ 118 @SuppressWarnings({"removal", "this-escape"}) 119 public MecanumDrive( 120 MotorController frontLeftMotor, 121 MotorController rearLeftMotor, 122 MotorController frontRightMotor, 123 MotorController rearRightMotor) { 124 this( 125 (double output) -> frontLeftMotor.set(output), 126 (double output) -> rearLeftMotor.set(output), 127 (double output) -> frontRightMotor.set(output), 128 (double output) -> rearRightMotor.set(output)); 129 SendableRegistry.addChild(this, frontLeftMotor); 130 SendableRegistry.addChild(this, rearLeftMotor); 131 SendableRegistry.addChild(this, frontRightMotor); 132 SendableRegistry.addChild(this, rearRightMotor); 133 } 134 135 /** 136 * Construct a MecanumDrive. 137 * 138 * <p>If a motor needs to be inverted, do so before passing it in. 139 * 140 * @param frontLeftMotor The setter for the motor on the front-left corner. 141 * @param rearLeftMotor The setter for the motor on the rear-left corner. 142 * @param frontRightMotor The setter for the motor on the front-right corner. 143 * @param rearRightMotor The setter for the motor on the rear-right corner. 144 */ 145 @SuppressWarnings("this-escape") 146 public MecanumDrive( 147 DoubleConsumer frontLeftMotor, 148 DoubleConsumer rearLeftMotor, 149 DoubleConsumer frontRightMotor, 150 DoubleConsumer rearRightMotor) { 151 requireNonNullParam(frontLeftMotor, "frontLeftMotor", "MecanumDrive"); 152 requireNonNullParam(rearLeftMotor, "rearLeftMotor", "MecanumDrive"); 153 requireNonNullParam(frontRightMotor, "frontRightMotor", "MecanumDrive"); 154 requireNonNullParam(rearRightMotor, "rearRightMotor", "MecanumDrive"); 155 156 m_frontLeftMotor = frontLeftMotor; 157 m_rearLeftMotor = rearLeftMotor; 158 m_frontRightMotor = frontRightMotor; 159 m_rearRightMotor = rearRightMotor; 160 instances++; 161 SendableRegistry.addLW(this, "MecanumDrive", instances); 162 } 163 164 @Override 165 public void close() { 166 SendableRegistry.remove(this); 167 } 168 169 /** 170 * Drive method for Mecanum platform. 171 * 172 * <p>Angles are measured counterclockwise from the positive X axis. The robot's speed is 173 * independent of its angle or rotation rate. 174 * 175 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive. 176 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive. 177 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is 178 * positive. 179 */ 180 public void driveCartesian(double xSpeed, double ySpeed, double zRotation) { 181 driveCartesian(xSpeed, ySpeed, zRotation, Rotation2d.kZero); 182 } 183 184 /** 185 * Drive method for Mecanum platform. 186 * 187 * <p>Angles are measured counterclockwise from the positive X axis. The robot's speed is 188 * independent of its angle or rotation rate. 189 * 190 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive. 191 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive. 192 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is 193 * positive. 194 * @param gyroAngle The gyro heading around the Z axis. Use this to implement field-oriented 195 * controls. 196 */ 197 public void driveCartesian(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle) { 198 if (!m_reported) { 199 HAL.report( 200 tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumCartesian, 4); 201 m_reported = true; 202 } 203 204 xSpeed = MathUtil.applyDeadband(xSpeed, m_deadband); 205 ySpeed = MathUtil.applyDeadband(ySpeed, m_deadband); 206 207 var speeds = driveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle); 208 209 m_frontLeftOutput = speeds.frontLeft * m_maxOutput; 210 m_rearLeftOutput = speeds.rearLeft * m_maxOutput; 211 m_frontRightOutput = speeds.frontRight * m_maxOutput; 212 m_rearRightOutput = speeds.rearRight * m_maxOutput; 213 214 m_frontLeftMotor.accept(m_frontLeftOutput); 215 m_frontRightMotor.accept(m_frontRightOutput); 216 m_rearLeftMotor.accept(m_rearLeftOutput); 217 m_rearRightMotor.accept(m_rearRightOutput); 218 219 feed(); 220 } 221 222 /** 223 * Drive method for Mecanum platform. 224 * 225 * <p>Angles are measured counterclockwise from straight ahead. The speed at which the robot 226 * drives (translation) is independent of its angle or rotation rate. 227 * 228 * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is positive. 229 * @param angle The gyro heading around the Z axis at which the robot drives. 230 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is 231 * positive. 232 */ 233 public void drivePolar(double magnitude, Rotation2d angle, double zRotation) { 234 if (!m_reported) { 235 HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumPolar, 4); 236 m_reported = true; 237 } 238 239 driveCartesian( 240 magnitude * angle.getCos(), magnitude * angle.getSin(), zRotation, Rotation2d.kZero); 241 } 242 243 /** 244 * Cartesian inverse kinematics for Mecanum platform. 245 * 246 * <p>Angles are measured counterclockwise from the positive X axis. The robot's speed is 247 * independent of its angle or rotation rate. 248 * 249 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive. 250 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive. 251 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is 252 * positive. 253 * @return Wheel speeds [-1.0..1.0]. 254 */ 255 public static WheelSpeeds driveCartesianIK(double xSpeed, double ySpeed, double zRotation) { 256 return driveCartesianIK(xSpeed, ySpeed, zRotation, Rotation2d.kZero); 257 } 258 259 /** 260 * Cartesian inverse kinematics for Mecanum platform. 261 * 262 * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent of 263 * its angle or rotation rate. 264 * 265 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive. 266 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is positive. 267 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is 268 * positive. 269 * @param gyroAngle The gyro heading around the Z axis. Use this to implement field-oriented 270 * controls. 271 * @return Wheel speeds [-1.0..1.0]. 272 */ 273 public static WheelSpeeds driveCartesianIK( 274 double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle) { 275 xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0); 276 ySpeed = MathUtil.clamp(ySpeed, -1.0, 1.0); 277 278 // Compensate for gyro angle. 279 var input = new Translation2d(xSpeed, ySpeed).rotateBy(gyroAngle.unaryMinus()); 280 281 double[] wheelSpeeds = new double[4]; 282 wheelSpeeds[MotorType.kFrontLeft.value] = input.getX() + input.getY() + zRotation; 283 wheelSpeeds[MotorType.kFrontRight.value] = input.getX() - input.getY() - zRotation; 284 wheelSpeeds[MotorType.kRearLeft.value] = input.getX() - input.getY() + zRotation; 285 wheelSpeeds[MotorType.kRearRight.value] = input.getX() + input.getY() - zRotation; 286 287 normalize(wheelSpeeds); 288 289 return new WheelSpeeds( 290 wheelSpeeds[MotorType.kFrontLeft.value], 291 wheelSpeeds[MotorType.kFrontRight.value], 292 wheelSpeeds[MotorType.kRearLeft.value], 293 wheelSpeeds[MotorType.kRearRight.value]); 294 } 295 296 @Override 297 public void stopMotor() { 298 m_frontLeftOutput = 0.0; 299 m_frontRightOutput = 0.0; 300 m_rearLeftOutput = 0.0; 301 m_rearRightOutput = 0.0; 302 303 m_frontLeftMotor.accept(0.0); 304 m_frontRightMotor.accept(0.0); 305 m_rearLeftMotor.accept(0.0); 306 m_rearRightMotor.accept(0.0); 307 308 feed(); 309 } 310 311 @Override 312 public String getDescription() { 313 return "MecanumDrive"; 314 } 315 316 @Override 317 public void initSendable(SendableBuilder builder) { 318 builder.setSmartDashboardType("MecanumDrive"); 319 builder.setActuator(true); 320 builder.setSafeState(this::stopMotor); 321 builder.addDoubleProperty("Front Left Motor Speed", () -> m_frontLeftOutput, m_frontLeftMotor); 322 builder.addDoubleProperty( 323 "Front Right Motor Speed", () -> m_frontRightOutput, m_frontRightMotor); 324 builder.addDoubleProperty("Rear Left Motor Speed", () -> m_rearLeftOutput, m_rearLeftMotor); 325 builder.addDoubleProperty("Rear Right Motor Speed", () -> m_rearRightOutput, m_rearRightMotor); 326 } 327}