Wheel Encoders

So far we have been controlling the motors by setting their power. Unfortunately, this is not ideal because the power only indirectly controls the speed, which is what we are really interested in. As we have already seen, our robot does not exactly drive straight when we apply the same power to both wheels. This is because differences in the motors and the way they are mounted cause them to run at slightly different speeds when the same power is applied.

What we need is some way to tell how far the wheels have turned and how fast. Each of the wheels on this robot have an encoder which will do just that. We will use the encoder to control the distance the robot moves as well as it’s speed.

For our first exercise, we are going to create a new command, similar to our DriveForTimeCommand, that will drive the robot forward a fixed distance, rather than a fixed time.

The encoders that we are using are handled by the Encoder class. We will need to create a separate instance of this class for the left and right motors. The DriveSubsystem will eventually need the encoders so we will be adding these to that class. Consulting the Encoder class, we see that the constructor take a encoder type and two integer parameters which specifies the Arduino pins to which they are connected. For this robot the encoder type is Analog, left encoder is connected to pins 0 and 1, while the right encoder is connected to pins 2 and 3. Open the DriveSubsystem.java file and add the following at top of the class.

public class DriveSubsystem extends SubsystemBase {
  private static final int k_rightMotorPWMPin = 5;
  private static final int k_rightMotorDirPin = 4;
  private static final int k_leftMotorPWMPin = 6;
  private static final int k_leftMotorDirPin = 7;
  private static final int k_leftEncoderPin1 = 0;
  private static final int k_leftEncoderPin2 = 1;
  private static final int k_rightEncoderPin1 = 2;
  private static final int k_rightEncoderPin2 = 3;

  private PWMMotor m_rightMotor = new PWMMotor(k_rightMotorPWMPin, k_rightMotorDirPin);
  private PWMMotor m_leftMotor = new PWMMotor(k_leftMotorPWMPin, k_leftMotorDirPin);
  private Encoder m_rightEncoder = new Encoder(robotCore.Encoder.EncoderType.Analog, k_rightEncoderPin1, k_rightEncoderPin2);
  private Encoder m_leftEncoder = new Encoder(robotCore.Encoder.EncoderType.Analog, k_leftEncoderPin1, k_leftEncoderPin2);

When you import the Encoder class be sure to select the one from RobotCore. Also note that once again we are declaring constants for the encoder pins rather than simply using the numbers directly in the call to the constructor.

Now the way these encoders are wired we will discover that for the right encoder when the wheel moves in the forward direction, the encoder will count up. However the left encoder will count down when the wheel moves forward. Hence we want to reverse the direction of the left encoder. We do this by adding the following to the DriveSubsystem constructor:

  public DriveSubsystem() {
    Logger.Log("DriveSubsystem", 3, "DriveSubsystem()");

    m_leftEncoder.setInverted(true);
  }

The call to setInverted(true) tells the encoder to reverse it’s direction.

Now we are going to need access to these encoders from our Command classes, so we will also create functions to retrieve the left and right encoders:

  public Encoder getLeftEncoder() {
    return (m_leftEncoder.Clone());
  }

  public Encoder getRightEncoder() {
    return (m_rightEncoder.Clone());
  }

Note that we are actually returning a copy of the Encoder rather than the one saved by the DriveSubsystem. This is so that the user of the copy is free to reset() the Encoder without affecting others who may be using the Encoder.

Now it is time to create our new command which we will call DriveForDistanceCommand. Go ahead and create a new class under the commands folder. This time instead of using the ExampleCommand as our starting point, copy the contents of DriveForTimeCommand.java file into your newly created DriveForDistanceCommand.java file. Then rename the file and replace all instances of DriveForTimeCommand with DriveForDistanceCommand.

Since we will not be using a Timer for this class, remove all references to the Timer. This will involve removing the time parameter from the constructor and having isFinished() function return false.

This will give us a better starting point. Your new file should look like:

/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
/* Open Source Software - may be modified and shared by FRC teams. The code   */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project.                                                               */
/*----------------------------------------------------------------------------*/

package robot.commands;

import edu.wpi.first.wpilibj2.command.CommandBase;
import robot.subsystems.DriveSubsystem;
import robotCore.Logger;

/**
 * An example command that uses an example subsystem.
 */
public class DriveForDistanceCommand extends CommandBase {
  private final DriveSubsystem m_subsystem;
  private double m_power;

  /**
   * Creates a new DriveForDistanceCommand.
   *
   * @param subsystem The subsystem used by this command.
   */
  public DriveForDistanceCommand(DriveSubsystem subsystem, double power) {
    Logger.Log("DriveForDistanceCommand", 3, "DriveForDistanceCommand()");

    m_subsystem = subsystem;
    m_power = power;
    // Use addRequirements() here to declare subsystem dependencies.
    addRequirements(m_subsystem);
  }

  // Called when the command is initially scheduled.
  @Override
  public void initialize() {
    Logger.Log("DriveForDistanceCommand", 2, "initialize()");

    m_subsystem.setPower(m_power, m_power);
  }

  // Called every time the scheduler runs while the command is scheduled.
  @Override
  public void execute() {
    Logger.Log("DriveForDistanceCommand", -1, "execute()");
  }

  // Called once the command ends or is interrupted.
  @Override
  public void end(boolean interrupted) {
    Logger.Log("DriveForDistanceCommand", 2, String.format("end(%b)", interrupted));

    m_subsystem.setPower(0, 0);
  }

  // Returns true when the command should end.
  @Override
  public boolean isFinished() {
    Logger.Log("DriveForDistanceCommand", -1, "isFinished()");

    return (false);
  }
}

Next we want to change our constructor to take a distance instead of a time. We also need to get the encoders from the DriveSubsystem. To measure the distance we can use either of the encoders but for this command we will use the left encoder.

public class DriveForDistanceCommand extends CommandBase {
  private final DriveSubsystem m_subsystem;
  private double m_power;
  private double m_distance;
  private Encoder m_leftEncoder;

  /**
   * Creates a new DriveForDistanceCommand.
   *
   * @param subsystem The subsystem used by this command.
   */
  public DriveForDistanceCommand(DriveSubsystem subsystem, double power, double distance) {
    Logger.Log("DriveForDistanceCommand", 3, "DriveForDistanceCommand()");

    m_subsystem = subsystem;
    m_power = power;
    m_distance = distance;
    m_leftEncoder = subsystem.getLeftEncoder();
    
    // Use addRequirements() here to declare subsystem dependencies.
    addRequirements(m_subsystem);
  }

Again, when you import the declaration for Encoder be sure to choose the one from robotCore.

In the initialize() function we need to reset the Encoder so that it counts from zero each time we run this command. Remember that the encoder we receive from the DriveSubsystem is our own copy so resetting it will not affect the DriveSubsystem or any other commands with use the encoders.

  public void initialize() {
    Logger.Log("DriveForDistanceCommand", 2, "initialize()");

    m_leftEncoder.reset();

    m_subsystem.setPower(m_power, m_power);
  }

The last thing we need to do is change the isFinished() function to return true when the distance is greater than or equal to the target distance:

  public boolean isFinished() {
    Logger.Log("DriveForDistanceCommand", -1, "isFinished()");

    return (m_leftEncoder.get() >= m_distance);
  }

Your DriveForDistanceCommand.java file should now look like:

/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
/* Open Source Software - may be modified and shared by FRC teams. The code   */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project.                                                               */
/*----------------------------------------------------------------------------*/

package robot.commands;

import edu.wpi.first.wpilibj2.command.CommandBase;
import robot.subsystems.DriveSubsystem;
import robotCore.Encoder;
import robotCore.Logger;

/**
 * An example command that uses an example subsystem.
 */
public class DriveForDistanceCommand extends CommandBase {
  private final DriveSubsystem m_subsystem;
  private double m_power;
  private double m_distance;
  private Encoder m_leftEncoder;

  /**
   * Creates a new DriveForDistanceCommand.
   *
   * @param subsystem The subsystem used by this command.
   */
  public DriveForDistanceCommand(DriveSubsystem subsystem, double power, double distance) {
    Logger.Log("DriveForDistanceCommand", 3, "DriveForDistanceCommand()");

    m_subsystem = subsystem;
    m_power = power;
    m_distance = distance;
    m_leftEncoder = subsystem.getLeftEncoder();

    // Use addRequirements() here to declare subsystem dependencies.
    addRequirements(m_subsystem);
  }

  // Called when the command is initially scheduled.
  @Override
  public void initialize() {
    Logger.Log("DriveForDistanceCommand", 2, "initialize()");

    m_leftEncoder.reset();

    m_subsystem.setPower(m_power, m_power);
  }

  // Called every time the scheduler runs while the command is scheduled.
  @Override
  public void execute() {
    Logger.Log("DriveForDistanceCommand", -1, "execute()");
  }

  // Called once the command ends or is interrupted.
  @Override
  public void end(boolean interrupted) {
    Logger.Log("DriveForDistanceCommand", 2, String.format("end(%b)", interrupted));

    m_subsystem.setPower(0, 0);
  }

  // Returns true when the command should end.
  @Override
  public boolean isFinished() {
    Logger.Log("DriveForDistanceCommand", -1, "isFinished()");

    return (m_leftEncoder.get() >= m_distance);
  }
}

Now we will configure the RobotContainer class to tie this new command to button 2 on the joystick. In RobotContainer.java we first add a declaration for m_button2:

public class RobotContainer {
  // The robot's subsystems and commands are defined here...
  @SuppressWarnings("unused")
  private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
  private final DriveSubsystem m_driveSubsystem = new DriveSubsystem();
  private final Joystick m_joystick = new Joystick(0);
  private final JoystickButton m_button1 = new JoystickButton(m_joystick, 1);
  private final JoystickButton m_button2 = new JoystickButton(m_joystick, 2);

Then we connect it so when this button is pressed we will run the DriveForDistanceCommand:

  private void configureButtonBindings() {
    m_button1.whenPressed(new DriveForTimeCommand(m_driveSubsystem, 0.75, 3.0));
    m_button2.whenPressed(new DriveForDistanceCommand(m_driveSubsystem, 0.75, 4000));

Note that the distance that we are passing in are in somewhat arbitrary units. The Encoder will count about 1000 for each complete rotation of the wheel so the actual distance traveled will be dependent on the size of the wheel. We have chosen 4000 here just to test this command. Later we will perform a conversion which will allow us to use real world units such as inches.

Your RobotContainer.java file should now look like:

/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
/* Open Source Software - may be modified and shared by FRC teams. The code   */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project.                                                               */
/*----------------------------------------------------------------------------*/

package robot;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import robot.commands.ArcadeDriveCommand;
import robot.commands.DriveForDistanceCommand;
import robot.commands.DriveForTimeCommand;
import robot.commands.ExampleCommand;
import robot.subsystems.DriveSubsystem;
import robot.subsystems.ExampleSubsystem;
import robotCore.Joystick;

/**
 * This class is where the bulk of the robot should be declared. Since
 * Command-based is a "declarative" paradigm, very little robot logic should
 * actually be handled in the {@link Robot} periodic methods (other than the
 * scheduler calls). Instead, the structure of the robot (including subsystems,
 * commands, and button mappings) should be declared here.
 */
public class RobotContainer {
  // The robot's subsystems and commands are defined here...
  @SuppressWarnings("unused")
  private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
  private final DriveSubsystem m_driveSubsystem = new DriveSubsystem();
  private final Joystick m_joystick = new Joystick(0);
  private final JoystickButton m_button1 = new JoystickButton(m_joystick, 1);
  private final JoystickButton m_button2 = new JoystickButton(m_joystick, 2);

  private final ExampleCommand m_autoCommand = null; // new ExampleCommand(m_exampleSubsystem);

  /**
   * The container for the robot. Contains subsystems, OI devices, and commands.
   */
  public RobotContainer() {
    m_driveSubsystem.setDefaultCommand(new ArcadeDriveCommand(m_driveSubsystem, m_joystick));

    // Configure the button bindings
    configureButtonBindings();
  }

  /**
   * Use this method to define your button->command mappings. Buttons can be
   * created by instantiating a {@link GenericHID} or one of its subclasses
   * ({@link edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then
   * passing it to a {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}.
   */
  private void configureButtonBindings() {
    m_button1.whenPressed(new DriveForTimeCommand(m_driveSubsystem, 0.75, 3.0));
    m_button2.whenPressed(new DriveForDistanceCommand(m_driveSubsystem, 0.75, 4000));
  }

  /**
   * Use this to pass the autonomous command to the main {@link Robot} class.
   *
   * @return the command to run in autonomous
   */
  public Command getAutonomousCommand() {
    // An ExampleCommand will run in autonomous
    return m_autoCommand;
  }
}

Now run your program and click the B2 button. You should find that your robot will drive a short distance and then stop. Also note that since we are now using distance rather than time, we can change the speed and the robot should still move the same distance. Try it out and see.

Next: Speed Control