Setting Velocity

Velocity is a closed loop control within the SDK that uses the encoder counts to determine the approximate power/speed the motors need to go in order to meet the set velocity. When working with encoder setting a velocity is recommended over setting a power level, as it offers a higher level of control.

To set a velocity, its important to understand the maximum velocity in RPM your motor is capable of. For the Class Bot V2 the motors are capable of a maximum RPM of 300. With a drivetrain, you are likely to get better control by setting velocity lower than the maximum. In this case, lets set the velocity to 175 RPM

Recall that setVelocity is measure in ticks per second.

Create a new double variable called TPS. Add TPS the to the op mode under where rightTarget is defined.

public void runOpMode() {
        leftmotor = hardwareMap.get(DcMotor.class, "leftmotor");
        rightmotor = hardwareMap.get(DcMotor.class, "rightmotor");
        
        rightmotor.setDirection(DcMotor.Direction.REVERSE);
        
        leftmotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
        rightmotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
        
        int leftTarget = (int)(610 * COUNTS_PER_MM);
        int rightTarget = (int)(610 * COUNTS_PER_MM);
        double TPS;
        
        waitForStart();

Since RPM is the amount of revolutions per minute a conversion needs to be made from RPM to ticks per second. To do this divide the RPM by 60, to get the amount of rotations per second. Rotations per second can the be multiplied by COUNTS_PER_WHEEL_REV, to get the amount of ticks per second.

double TPS = (175/60) * COUNTS_PER_WHEEL_REV

Exchange the setPower();functions for setVelocity();. AddTPS as the parameter for setVelocity();.

waitForStart();

leftmotor.setTargetPosition(leftTarget);
rightmotor.setTargetPosition(rightTarget);

leftmotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightmotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);

leftmotor.setVelocity(TPS);
rightmotor.setVelocity(TPS);

while (opModeIsActive() && (leftmotor.isBusy() && rightmotor.isBusy())){
        
        }

Try to build the code. Do you get errors?

With the current state of the code you are likely to get errors similar to the ones pictured below:

This is because the setVelocity();function is a function of theDcMotorEx Interface. The DcMotorEx Interface is an extension of the DcMotor Interface, that provides enhanced motor functionality, such as access to closed loop control functions. To use setVelocity(); the motor variables need to be changed to DcMotorEx . To do this both the private variable creation of the motors, and the hardware mapping need to be changed to DcMotorEx.

public class HelloRobot_EncoderAuton extends LinearOpMode {
    private DcMotorEx leftmotor;
    private DcMotorEx rightmotor;
public void runOpMode() {
        leftmotor = hardwareMap.get(DcMotorEx.class, "leftmotor");
        rightmotor = hardwareMap.get(DcMotorEx.class, "rightmotor");

Since DcMotorEx is an extension of DcMotor, DcMotor specific functions can be used by variables defined as DcMotorEx.

Once you have made these changes the basic, drive two feet code is done! The code below is the finalized version of the code. In this the other hardware components and telemetry have been added.

@Autonomous

public class HelloRobot_EncoderAuton extends LinearOpMode {
    private DcMotorEx leftmotor;
    private DcMotorEx rightmotor;
    private DcMotor arm;
    private Servo claw;
    private TouchSensor touch;
    
    static final double     COUNTS_PER_MOTOR_REV    = 28.0; 
    static final double     DRIVE_GEAR_REDUCTION    = 30.24;   
    static final double     WHEEL_CIRCUMFERENCE_MM  = 90.0 * 3.14;
    
    static final double     COUNTS_PER_WHEEL_REV    = COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION;
    static final double     COUNTS_PER_MM           = COUNTS_PER_WHEEL_REV / WHEEL_CIRCUMFERENCE_MM;
    
    @Override
    public void runOpMode() {
        leftmotor = hardwareMap.get(DcMotorEx.class, "leftmotor");
        rightmotor = hardwareMap.get(DcMotorEx.class, "rightmotor");
        arm = hardwareMap.get(DcMotor.class, "arm");
        claw = hardwareMap.get(Servo.class, "claw");
        touch = hardwareMap.get(TouchSensor.class, "touch");
        
        rightmotor.setDirection(DcMotor.Direction.REVERSE);

        leftmotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
        rightmotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
        
        
        int leftTarget = (int)(610 * COUNTS_PER_MM);
        int rightTarget = (int)(610 * COUNTS_PER_MM);
        double TPS = (175/ 60) * COUNTS_PER_WHEEL_REV;
        
        waitForStart();
        
        
        leftmotor.setTargetPosition(leftTarget);
        rightmotor.setTargetPosition(rightTarget);
        
        leftmotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
        rightmotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
        
        leftmotor.setVelocity(TPS);
        rightmotor.setVelocity(TPS);
        
        while (opModeIsActive() && (leftmotor.isBusy() && rightmotor.isBusy())) {
            telemetry.addData("left", leftmotor.getCurrentPosition());
            telemetry.addData("right", rightmotor.getCurrentPosition());
            telemetry.update();
        }
    }
}

Last updated