MecanumDrive unintended behavior


^ The above is an image that displays the intended/actual behavior found in my team’s Mecanum code.
Our Team’s Forward/Backwards and Left/Right strafing works great. However, when trying to turn using wpilibj’s MecanumDrive, the wheels spin incorrectly and the robot basically sputters in place.

package frc.robot;
//Blah Blah imports, you (or your IDE) know what's here

public class Robot extends TimedRobot
{
    private SparkMaxMotor leftRear; // SparkMaxMotor is just a wrapper around CANSparkMax, yes I know about the deprecation
    private SparkMaxMotor rightRear;
    private SparkMaxMotor leftFront;
    private SparkMaxMotor rightFront;
    private final XboxController controller = new XboxController(0);
    private MecanumDrive drive; // wpilib mecanumdrive

    @Override
    public void robotInit()
    { // motor = new SparkMaxMotor(id, MotorType)
        leftRear=new SparkMaxMotor(0, CANSparkMaxLowLevel.MotorType.kBrushless);
        rightRear=new SparkMaxMotor(1, CANSparkMaxLowLevel.MotorType.kBrushless);
        leftFront=new SparkMaxMotor(2, CANSparkMaxLowLevel.MotorType.kBrushless);
        rightFront=new SparkMaxMotor(3, CANSparkMaxLowLevel.MotorType.kBrushless);
        drive = new MecanumDrive(leftFront, leftRear, rightFront, rightRear);
    }
    
    
    @Override
    public void teleopPeriodic()
    {
        double y = controller.getLeftY();
        double x = controller.getLeftX();
        double turn = controller.getRightX();
        drive.driveCartesian(y, x, turn);
    }
    public void periodic() {
        leftRear.periodic();;
        rightRear.periodic();
        leftFront.periodic();
        rightFront.periodic();
    }
}
  • Kaiden McMartin, 5183

Likely two motors that are diagonal from each other are swapped. Notice how diagonal motors have the same rotation direction in forward and strafe mode, but not when rotating.

Double check CAN IDs

I’m no longer with the robot until tomorrow so I cannot confirm the exact IDs, but all CAN IDs for the MAXs were double checked multiple times by blinking, but I will run down the blinks again tomorrow first thing.

Be sure to test with your robot on blocks so you don’t burn out your motors :wink:

Yep, already had our setup for that going today :smile:

This code probably isn’t driving the robot the way you think it should.

  • Robot forward is positive X
  • Robot left is positive Y
  • Robot rotation is counter-clockwise positive

Joysticks, on the other hand, are:

  • backwards is positive Y
  • right is positive X

Joystick values are rotation around the axis:

So, you need to invert the values from the joystick. I also recommend matching the variable names (you have x named y, and y named x)

double x = -controller.getLeftY();
double y = -controller.getLeftX();
double turn = -controller.getRightX();
drive.driveCartesian(x, y, turn);

Building in the problem above, you probably have your motors inverted incorrectly. With your code, when you push forward on the controller, the robot should move backwards. When you press to the right, the robot should move left.

The fact that the robot appears to moving the right way is probably an indication that your motors are not inverted correctly. Positive output should make the motors drive forward. Incorrect inversion would appear to work for forward and backward, but would not work for rotation.

I’m using an Xbox Controller, not a large joystick. I’m aware of the left/right being backwards. Although front/back is not (and is driving as expected front and back).

I’ve looked at the inversion states of the motors, and they are as expected to have the chassis move in the 4 directions correctly (front wheels inverted, rear wheels normal).

As of right now:

Positive input from left stick Y - > X input for Cartesian - > forward movement, and vice versa
Positive input from left stick X - > Y input for Cartesian - > leftwards movement (can use - for expected drive behavior.
Positive input from right stick X - > turn input for Cartesian - > The diagrammed unintended behavior

I have triple checked the CAN ids and sparks on the bot.
For clarity,
CanID 1 front left
2 back left
3 back right
4 front right

Swapping front left and back right in the code appears to produce a fix. The motors are in a different order than the Mecanum Drive constructor asks for.

I’ll take the fix either way, however, this is odd behavior from MecanumDrive

The axes are the same on an XBox controller as they are on a large joystick.

This is unusual, but it depends on your robot build. Usually the right side is inverted, and the left side is not.
Are you 100% sure that positive output on the motor results in forward motion of the wheel?

This is wrong, unless you want to push the controller stick toward you to drive the robot forward. Positive input from the left Y is pulling the stick toward you. Pushing it away from you is negative.

I think you’re saying you have to invert the input from the left stick, that would be correct. Pushing the left stick to the right will result in postive X input, so it needs to be inverted.

Positive input from the right stick is pushing the stick to the right. It needs to be inverted because robot rotation is CCW (left) positive.

This is because you’re telling the MecanumDrive class you want to move in a different direction than you intend. It’s up to you if you want to leave your workaround and move forward, but I highly recommend getting it fixed properly. If you want to implement odometry, pose estimation, or path planning for autonomous, you’ll need to keep implementing workarounds throughout the code if you don’t use the correct coordinate system.

It seems like you don’t believe I am correct, so I’ll include some references. You can also look in Driver Station while you move the sticks around, and confirm the behavior with your robot’s motors.

The drive classes use the NWU axes convention… The positive X axis points ahead, the positive Y axis points left, and the positive Z axis points up…

Joysticks follow NED (North-East-Down) convention, where the positive X axis points ahead, the positive Y axis points right, and the positive Z axis points down. However, it’s important to note that axes values are rotations around the respective axes, not translations. When viewed with each axis pointing toward you, CCW is a positive value and CW is a negative value. Pushing forward on the joystick is a CW rotation around the Y axis, so you get a negative value. Pushing to the right is a CCW rotation around the X axis, so you get a positive value.

m_robotDrive.driveCartesian(-m_stick.getY(), -m_stick.getX(), -m_stick.getZ());

Important

Forward on joysticks is the negative direction. Teams often negate the values when reading joystick axes to account for this.

2 Likes

I think I’m having a Mandela Effect moment about the Y controller axis. Every memory I have has it being positive :smile: but yeah it is how you say. This goes into non-Mecanum drive too. I just checked our old code and we’ve never negated our left-stick-Y input for DifferentialDrive.arcadeDrive either (with the same documentation showing the negation for that too).
This is with right side inverted on these old bots too.
There is something fishy with our configurations

I will run some more testing on it tomorrow with this knowledge

We also ran our differential drives backwards for our first two rookie years without realizing it. Until you get to path following or holonomic drive, it’s pretty easy to just work around it and make it work.

Here’s a page that I put together on this exact topic that I’m hoping to get merged to the WPILib docs. If you get a chance, look it over and let me know if you have any feedback.

This topic was automatically closed 365 days after the last reply. New replies are no longer allowed.