Using Limits to Control Range of Motion

In the previous sections you worked on some of the building blocks for restricting an arms range of motion. From those sections you should have the foundation you need to perform basic arm control. However, there are some other creative ways you can use encoder positions and limits to expand the control you have over your arm.

This section will cover two additional types of control. The first type of control we will explore is the idea of soft limits. In the Adding a Limit Switch section we discuss the concept of physical limits of a mechanism however, there may be times you need to limit the range of motion of an arm without installing a physical limit. To do this position based code can be used to create a range for the arm.

Once you have a basic idea of how to create soft limits, we will explore how to use a limit switch (like a touch sensor) to reset the range of motion. This type of control reduces the risk of getting stuck outside of your intended range of motion, which can affect the expected behavior of your robot.

To set the soft limits we will use some of the basic logic we established in previous sections, with some edited changes. Start with a Basic Op Mode and add the constant variables from the Calculating Target Position section to the op mode.

@TeleOp

public class Basic extends LinearOpMode {
    private DcMotor  arm;

    static final double     COUNTS_PER_MOTOR_REV    = 288; 
    static final double     GEAR_REDUCTION    = 2.7778;   
    static final double     COUNTS_PER_GEAR_REV    = COUNTS_PER_MOTOR_REV * GEAR_REDUCTION;
    static final double     COUNTS_PER_DEGREE    = COUNTS_PER_GEAR_REV/360;
    
    @Override
    public void runOpMode() {
        arm = hardwareMap.get(DcMotor.class, "arm");
        
        
        waitForStart();
    
        while (opModeIsActive()) {
            telemetry.addData("Status", "Running");
            telemetry.update();

        }
    }
}

Next we need to create our upper and lower limits. Create two new integer variables one called minPosition and one called maxPosition. Add both of these to the in the initialization section of the op mode above the waitForStart(); command.

public void runOpMode() {
        arm = hardwareMap.get(DcMotor.class, "arm");
        
        int minPostion;
        int maxPosition;
        waitForStart();
    

For now we want the minPosition set as our starting position and the maxPosition set to our 90 degree position. Set minPositionequal to 0 and set maxPositionequal toCOUNTS_PER_DEGREE times 45 .

Remember you need to make a data type conversion!

int minPostion = 0;
int maxPosition = (int)(COUNTS_PER_DEGREE *45);

An if/else if statement needs to be added to control the arm, for this we can use the same basic logic we use in the Estimating the Position of the Arm section.

while(opModeIsActive()){
     if(gamepad1.dpad_up){
            arm.setPower(0.5);         
            }
     else if (gamepad1.dpad_down){
            arm.setPower(-0.5); 
            }   
     else { 
            arm.setPower(0); 
            }   
     } 

To set the limit we need to edit our if/else ifstatement so that the limits are built in. If DpadUpis selected and the position of the arm is less than the maxPosition then the arm will move to the maxPosition. If DpadDown is selected and the position of the is greater that the minPosition then the arm will move towards the minPosition.

while (opModeIsActive()) {
    if (gamepad1.dpad_up && arm.getCurrentPosition() < maxPosition) {
            arm.setPower(0.5);
            } 
    else if (gamepad1.dpad_down && arm.getCurrentPosition() > minPosition) {
            arm.setPower(-0.5);
            } 
    else {
            arm.setPower(0);
            }
    }

The current code configuration will stop the motor at any point that the conditions to power the motor are not met. Depending to factors like the weight of the mechanism and any load that it is bearing, when the motor stops the arm may drop below the maxPosition. Take time to test out the code and confirm that it behaves in the way you expect it to.

Overriding Limits

One of the benefits of having a soft limit is being able to exceed that limit. Since encoders zero tick position is determined by the position of the arm when the Control Hub powers on; if attention is not payed to what position the arm is on power up the range of motion of the arm is affected. For instance, if we have to reset the Control Hub while the arm is in the 90 degree position, the 90 degree position is equal to 0 encoder ticks. One way around this is to create an override for the range of motion.

There are a few different ways an override of sorts can be created, in our case we are going to use the a button and touch sensor to help reset our range.

Start by editing the if/else if statement to add another else if condition. Use the line gamepad1.a as the condition. Add a the line arm.setPower(-0.5); as the action item.

while (opModeIsActive()) {
    if (gamepad1.dpad_up && arm.getCurrentPosition() < maxPosition) {
            arm.setPower(0.5);
            } 
    else if (gamepad1.dpad_down && arm.getCurrentPosition() > minPosition) {
            arm.setPower(-0.5);
            } 
    else if(gamepad1.a){
            arm.setPower(-0.5);
    else {
            arm.setPower(0);
            }
    }

Now that we have this change in place, when the a button is pressed the arm will move toward the starting position. When the arm reaches and presses the touch sensor we want toSTOP_AND_RESET_ENCODER .

We can create another if statement that focuses on performing this stop and reset when the Touch Sensor is pressed.

if (touch.isPressed()) {
          arm.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
        }

So, if the Touch Sensor returns true (or is pressed) the motor run mode STOP_AND_RESET_ENCODERwill be activated causing the motor encoder to reset to 0 ticks.

Now that this code is done, try testing it!

@TeleOp

public class HelloRobot_ArmControl extends LinearOpMode {
    private DcMotor arm;
    private Servo claw;
    private DcMotor leftmotor;
    private DcMotor rightmotor;
    private TouchSensor touch;
    
    static final double     COUNTS_PER_MOTOR_REV    = 288; 
    static final double     GEAR_REDUCTION    = 2.7778;   
    static final double     COUNTS_PER_GEAR_REV    = COUNTS_PER_MOTOR_REV * GEAR_REDUCTION;
    static final double     COUNTS_PER_DEGREE    = COUNTS_PER_GEAR_REV/360;

    

    @Override
    public void runOpMode() {
        arm = hardwareMap.get(DcMotor.class, "arm");
        claw = hardwareMap.get(Servo.class, "claw");
        leftmotor = hardwareMap.get(DcMotor.class, "leftmotor");
        rightmotor = hardwareMap.get(DcMotor.class, "rightmotor");
        touch = hardwareMap.get(TouchSensor.class, "touch");
        
        int minPostion = 0;
        int maxPosition = (int)(COUNTS_PER_DEGREE *45);
        
        waitForStart();
            
        // run until the end of the match (driver presses STOP)
        while (opModeIsActive()) {
            if (gamepad1.dpad_up && arm.getCurrentPosition() < maxPosition) {
                arm.setPower(0.5);
                    } 
            else if (gamepad1.dpad_down && arm.getCurrentPosition() > minPosition) {
                arm.setPower(-0.5);
                    } 
            else if (gamepad1.a) {
                arm.setPower(-0.5);
                    } 
            else {
                arm.setPower(0);
                }
            if (touch.isPressed()) {
              arm.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
                    }
        telemetry.addData("Arm Test", arm.getCurrentPosition());
        telemetry.update(); 
        }
    }
}

Last updated