Driving a robot using Mecanum drive

Mecanum drive is a method of driving using specially designed wheels that allow the robot to drive in any direction without changing the orientation of the robot. A robot with a conventional drivetrain (all wheels pointing in the same direction) must turn in the direction it needs to drive. A mecanum robot can move in any direction without first turning and is called a holonomic drive.

Conventions and Defaults

For information on conventions and defaults of the MecanumDrive class, see the WPILib Drive classes: Conventions and Defaults article.

Mecanum wheels

Mecanum wheels

The wheels shown in this robot have rollers that cause the forces from driving to be applied at a 45 degree angle rather than straight forward as in the case of a conventional drive. You might guess that varying the speed of the wheels results in travel in any direction. You can look up how mecanum wheels work on various web sites on the internet.

Controlling Mecanum: Cartesian vs Polar

The MecanumDrive class contains two ways of controlling the drivetrain:

  • Cartesian: This method takes X, Y, and Rotation parameters and is commonly used when mapping joysticks to mecanum drive movement. The resulting robot translation is a combination of the desired X and Y movement.
  • Polar: This method takes Magnitude, Angle, and Rotation parameters and is commonly used when controlling the robot autonomously. The angle should be specified in degrees around the Z-axis (between -180 and 180).

Code for teleop driving with mecanum wheels

Here's a sample program that shows the minimum code to drive using a single joystick and mecanum wheels. The joystick XY position represents a robot-relative direction vector that the robot should follow. The twist (Z) axis on the joystick represents the rate of rotation for the robot while it's driving.

C++
#include "WPILib.h"
/**
 * Simplest program to drive a robot with mecanum drive using a single Logitech
 * Extreme 3D Pro joystick and 4 drive motors connected as follows:
 *     - PWM 0 - Connected to front left drive motor
 *     - PWM 1 - Connected to rear left drive motor
 *     - PWM 2 - Connected to front right drive motor
 *     - PWM 3 - Connected to rear right drive motor
 */
class MecanumDefaultCode : public frc::TimedRobot
{
	
	frc::Spark m_frontLeft{0};		
	frc::Spark m_rearLeft{1}; 
	frc::Spark m_frontRight{2};
	frc::Spark m_rearRight{3};
	frc::MecanumDrive m_drive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};
	frc::Joystick m_driveStick{1};

	/**
	 * Gets called once for each new packet from the DS.
	 */
	void TeleopPeriodic override (void)
	{
		m_robotDrive.MecanumDrive_Cartesian(m_driveStick.GetX(), m_driveStick.GetY(), m_driveStick.GetZ());
	}

};
START_ROBOT_CLASS(MecanumDefaultCode);
Java
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.TimedRobot;

/*
 * Simplest program to drive a robot with mecanum drive using a single Logitech
 * Extreme 3D Pro joystick and 4 drive motors connected as follows:
 *     - PWM 0 - Connected to front left drive motor
 *     - PWM 1 - Connected to rear left drive motor
 *     - PWM 2 - Connected to front right drive motor
 *     - PWM 3 - Connected to rear right drive motor
 */

public class MecanumDefaultCode extends TimedRobot {
     //Create a robot drive object using PWMs 0, 1, 2 and 3
     Spark m_frontLeft = new Spark(1);	
		Spark m_rearLeft = new Spark(2);
		Spark m_frontRight = new Spark(3);	
		Spark m_rearRight = new Spark(4);
     //Define joystick being used at USB port 1 on the Driver Station
     Joystick m_driveStick = new Joystick(1);

     public void teleopPeriodic() 
		{
          m_robotDrive.mecanumDrive_Cartesian(m_driveStick.getX(), m_driveStick.getY(), m_driveStick.getZ());
     }
}


Updating the program for field-oriented driving

There is also an optional 4th parameter to the MecanumDrive_Cartesian() method that is the angle returned from a Gyro sensor. This will adjust the X/Y values supplied, in this case, from the joystick to be relative to the field rather than relative to the robot. This is particularly useful with mecanum drive since, for the purposes of steering, the robot really has no front, back or sides. It can go in any direction. Adding the angle in degrees from a gyro object will cause the robot to move away from the drivers when the joystick is pushed forwards, and towards the drivers when it is pulled towards them - regardless of what direction the robot is facing!

The use of field-oriented driving makes often makes the robot much easier to drive, especially compared to a "robot-oriented" drive system where the controls are reversed when the robot is facing the drivers.

Just remember to get the gyro angle each time MecanumDrive_Cartesian() is called.

C++
m_robotDrive.MecanumDrive_Cartesian(m_driveStick.GetX(), m_driveStick.GetY(), m_driveStick.GetZ(), m_gyro.GetAngle());
Java
m_robotDrive.mecanumDrive_Cartesian(m_driveStick.getX(), m_driveStick.getY(), m_driveStick.getZ(), m_gyro.getAngle());

0 Report Errors

Use this form to report any errors with the documentation. For help with WPILib, please use the FIRST Forums at http://forums.usfirst.org For reporting WPILib bugs, please submit an issue on GitHub at https://github.com/wpilibsuite/allwpilib/issues/new

Ignore