001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ 003/* Open Source Software - may be modified and shared by FRC teams. The code */ 004/* must be accompanied by the FIRST BSD license file in the root directory of */ 005/* the project. */ 006/*----------------------------------------------------------------------------*/ 007 008package edu.wpi.first.wpilibj.drive; 009 010import edu.wpi.first.wpilibj.SpeedController; 011import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances; 012import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType; 013import edu.wpi.first.wpilibj.hal.HAL; 014import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; 015 016/** 017 * A class for driving Mecanum drive platforms. 018 * 019 * <p>Mecanum drives are rectangular with one wheel on each corner. Each wheel has rollers toed in 020 * 45 degrees toward the front or back. When looking at the wheels from the top, the roller axles 021 * should form an X across the robot. Each drive() function provides different inverse kinematic 022 * relations for a Mecanum drive robot. 023 * 024 * <p>Drive base diagram: 025 * <pre> 026 * \\_______/ 027 * \\ | | / 028 * | | 029 * /_|___|_\\ 030 * / \\ 031 * </pre> 032 * 033 * <p>Each drive() function provides different inverse kinematic relations for a Mecanum drive 034 * robot. Motor outputs for the right side are negated, so motor direction inversion by the user is 035 * usually unnecessary. 036 * 037 * <p>This library uses the NED axes convention (North-East-Down as external reference in the world 038 * frame): http://www.nuclearprojects.com/ins/images/axis_big.png. 039 * 040 * <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis 041 * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is 042 * positive. 043 * 044 * <p>Inputs smaller then {@value edu.wpi.first.wpilibj.drive.RobotDriveBase#kDefaultDeadband} will 045 * be set to 0, and larger values will be scaled so that the full range is still used. This 046 * deadband value can be changed with {@link #setDeadband}. 047 * 048 * <p>RobotDrive porting guide: 049 * <br>In MecanumDrive, the right side speed controllers are automatically inverted, while in 050 * RobotDrive, no speed controllers are automatically inverted. 051 * <br>{@link #driveCartesian(double, double, double, double)} is equivalent to 052 * {@link edu.wpi.first.wpilibj.RobotDrive#mecanumDrive_Cartesian(double, double, double, double)} 053 * if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted compared to 054 * RobotDrive (eg driveCartesian(xSpeed, -ySpeed, zRotation, -gyroAngle). 055 * <br>{@link #drivePolar(double, double, double)} is equivalent to 056 * {@link edu.wpi.first.wpilibj.RobotDrive#mecanumDrive_Polar(double, double, double)} if a 057 * deadband of 0 is used. 058 */ 059public class MecanumDrive extends RobotDriveBase { 060 private static int instances = 0; 061 062 private SpeedController m_frontLeftMotor; 063 private SpeedController m_rearLeftMotor; 064 private SpeedController m_frontRightMotor; 065 private SpeedController m_rearRightMotor; 066 067 private boolean m_reported = false; 068 069 /** 070 * Construct a MecanumDrive. 071 * 072 * <p>If a motor needs to be inverted, do so before passing it in. 073 */ 074 public MecanumDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor, 075 SpeedController frontRightMotor, SpeedController rearRightMotor) { 076 m_frontLeftMotor = frontLeftMotor; 077 m_rearLeftMotor = rearLeftMotor; 078 m_frontRightMotor = frontRightMotor; 079 m_rearRightMotor = rearRightMotor; 080 addChild(m_frontLeftMotor); 081 addChild(m_rearLeftMotor); 082 addChild(m_frontRightMotor); 083 addChild(m_rearRightMotor); 084 instances++; 085 setName("MecanumDrive", instances); 086 } 087 088 /** 089 * Drive method for Mecanum platform. 090 * 091 * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent 092 * from its angle or rotation rate. 093 * 094 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is positive. 095 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive. 096 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is 097 * positive. 098 */ 099 @SuppressWarnings("ParameterName") 100 public void driveCartesian(double ySpeed, double xSpeed, double zRotation) { 101 driveCartesian(ySpeed, xSpeed, zRotation, 0.0); 102 } 103 104 /** 105 * Drive method for Mecanum platform. 106 * 107 * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent 108 * from its angle or rotation rate. 109 * 110 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is positive. 111 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is positive. 112 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is 113 * positive. 114 * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use 115 * this to implement field-oriented controls. 116 */ 117 @SuppressWarnings("ParameterName") 118 public void driveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle) { 119 if (!m_reported) { 120 HAL.report(tResourceType.kResourceType_RobotDrive, 4, 121 tInstances.kRobotDrive_MecanumCartesian); 122 m_reported = true; 123 } 124 125 ySpeed = limit(ySpeed); 126 ySpeed = applyDeadband(ySpeed, m_deadband); 127 128 xSpeed = limit(xSpeed); 129 xSpeed = applyDeadband(xSpeed, m_deadband); 130 131 // Compensate for gyro angle. 132 Vector2d input = new Vector2d(ySpeed, xSpeed); 133 input.rotate(-gyroAngle); 134 135 double[] wheelSpeeds = new double[4]; 136 wheelSpeeds[MotorType.kFrontLeft.value] = input.x + input.y + zRotation; 137 wheelSpeeds[MotorType.kFrontRight.value] = input.x - input.y + zRotation; 138 wheelSpeeds[MotorType.kRearLeft.value] = -input.x + input.y + zRotation; 139 wheelSpeeds[MotorType.kRearRight.value] = -input.x - input.y + zRotation; 140 141 normalize(wheelSpeeds); 142 143 m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft.value] * m_maxOutput); 144 m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight.value] * m_maxOutput); 145 m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput); 146 m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput); 147 148 m_safetyHelper.feed(); 149 } 150 151 /** 152 * Drive method for Mecanum platform. 153 * 154 * <p>Angles are measured counter-clockwise from straight ahead. The speed at which the robot 155 * drives (translation) is independent from its angle or rotation rate. 156 * 157 * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is positive. 158 * @param angle The angle around the Z axis at which the robot drives in degrees [-180..180]. 159 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is 160 * positive. 161 */ 162 @SuppressWarnings("ParameterName") 163 public void drivePolar(double magnitude, double angle, double zRotation) { 164 if (!m_reported) { 165 HAL.report(tResourceType.kResourceType_RobotDrive, 4, tInstances.kRobotDrive_MecanumPolar); 166 m_reported = true; 167 } 168 169 driveCartesian(magnitude * Math.sin(angle * (Math.PI / 180.0)), 170 magnitude * Math.cos(angle * (Math.PI / 180.0)), zRotation, 0.0); 171 } 172 173 @Override 174 public void stopMotor() { 175 m_frontLeftMotor.stopMotor(); 176 m_frontRightMotor.stopMotor(); 177 m_rearLeftMotor.stopMotor(); 178 m_rearRightMotor.stopMotor(); 179 m_safetyHelper.feed(); 180 } 181 182 @Override 183 public String getDescription() { 184 return "MecanumDrive"; 185 } 186 187 @Override 188 public void initSendable(SendableBuilder builder) { 189 builder.setSmartDashboardType("MecanumDrive"); 190 builder.addDoubleProperty("Front Left Motor Speed", m_frontLeftMotor::get, 191 m_frontLeftMotor::set); 192 builder.addDoubleProperty("Front Right Motor Speed", m_frontRightMotor::get, 193 m_frontRightMotor::set); 194 builder.addDoubleProperty("Rear Left Motor Speed", m_rearLeftMotor::get, 195 m_rearLeftMotor::set); 196 builder.addDoubleProperty("Rear Right Motor Speed", m_rearRightMotor::get, 197 m_rearRightMotor::set); 198 } 199}