Before getting started with programming we needed to create a configuration file. Below is an overview of how the robot is configured for the teleop code to function as expected:
Port Type
Port Number
Device Type
Name
Configuration file download
To put this configuration file on your robot, drag this file into the "FIRST" folder of your Control Hub's file system.
Joysticks and Triggers input floating point data to your code allowing you to adjust the speed of a motor based on the pressure applied to the trigger or position of the joystick.
Buttons, Bumpers, and D-Pad provide boolean data to your code and are ideal for triggering an action such as rotating a motor to a set position.
What drivetrain are you using and what driving style do you want to use?
We decided our robot for CENTERSTAGE would be driven with Split Arcade Drive for advantages in precision while driving.
Which input makes the most sense?
There are multiple buttons in play for this year's Starter Bot. Both bumpers control the gripper's ability to pick up Pixels. The wrist servo is bound to the "A/Cross" and "B/Circle" buttons for rotating between the intake and home position. Lastly, this year's arm is controlled by the triggers.
Not all gamepads have buttons labeled the same way. Check the manufacturer's documentation for accurate button mapping.
This section makes the assumption that you have learned some of the FTC programming basics by going through the Hello Robot guide. If you have not gone through this guide please walk through it before proceeding.
In Hello Robot- Basics of Programming Drivetrains we covered how to program arcade drive with one joystick. For this example, we will be programming arcade drive using two joysticks. This type of drive is called "split arcade". In split arcade drive, the left joystick will control forward and reverse motion of the robot, and the right joystick will control turning. This is similar to how some RC cars are driven and video games are played.
Let's break down the Blocks Code for CENTERSTAGE!
Establishing Variables:
This year's Starter Bot makes use of a lot of variables.
This code runs AFTER the initialization is activated, but BEFORE the play button is clicked.
This section allows the encoder on the arm Core Hex Motors to be reset to zero on start up and establishes their default behavior. Additionally, this sets two of the motors to run in reverse, one on the drivetrain and one of the arm motors.
This code will run ONCE after the play button is activated.
This section acts as an additional check for resetting the arm's power and position as well as setting the Core Hex Motors to "RUN_TO_POSITION" mode as default when the play button is clicked.
Split Arcade Drive:
The following sections all run REPEATEDLY in the "while loop" once the play button is activated.
Let's begin with programming our Split Arcade Drive. This code will take input from the right and left joysticks to determine the robot's movement. The left joystick controls forward and back, while the right stick controls left and right turning movement.
Manual Arm Movement:
The triggers on the controller determine the direction of the arm's rotation. The arm's power is determined by how far down both triggers are pressed. Additionally, the if/then statement switches the arm between manual drive and being ready to run the preset positions.
Arm and Wrist Preset Positions:
There are three preset positions for the arm and wrist on the Starter Bot- intake, home, and scoring.
Re-zero Encoder:
When you re-zero the encoder the arm and wrist should be in the HOME position.
Watchdog to Shutdown Motor in Home Position:
This check prevents the Core Hex Motors from continuing to run while in home position to prevent potential overheating.
Let's take a closer look at all the parts of this if/then statement:
This if/then statement will only run if all the following are met:
The arm is not currently moving in manual mode from the triggers being pressed
The motors are actively on
The left Core Hex Motor's current and target position are less than or equal to the threshold (currently set to five)
Home position's value is set to 0 while Intake is set to 10
Gripper Controls:
When either or both of the bumpers on the controller are held down the gripper will open fully. When released it will return to the closed position to secure the fingers around the pixel.
Programming Teleop - OnBot Java
This section makes the assumption that you have learned some of the FTC programming basics by going through the Hello Robot guide. If you have not gone through this guide please walk through it before proceeding.
In Hello Robot- Basics of Programming Drivetrainswe covered how to program arcade drive with one joystick. For this example, we will be programming arcade drive using two joysticks. This type of drive is called "split arcade". In split arcade drive, the left joystick will control forward and reverse motion of the robot, and the right joystick will control turning. This is similar to how some RC cars are driven and video games are played.
Full Robot Code
To use this code with your Starter Bot, copy and paste it into a new OnBot Java OP Mode!
/* Copyright (c) 2017 FIRST. All rights reserved. * * Redistribution and use in source and binary forms, with or without modification, * are permitted (subject to the limitations in the disclaimer below) provided that * the following conditions are met: * * Redistributions of source code must retain the above copyright notice, this list * of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright notice, this * list of conditions and the following disclaimer in the documentation and/or * other materials provided with the distribution. * * Neither the name of FIRST nor the names of its contributors may be used to endorse or * promote products derived from this software without specific prior written permission. * * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */packageorg.firstinspires.ftc.teamcode;importcom.qualcomm.robotcore.eventloop.opmode.Disabled;importcom.qualcomm.robotcore.hardware.Servo;importcom.qualcomm.robotcore.eventloop.opmode.OpMode;importcom.qualcomm.robotcore.eventloop.opmode.TeleOp;importcom.qualcomm.robotcore.hardware.DcMotor;importcom.qualcomm.robotcore.util.ElapsedTime;importcom.qualcomm.robotcore.util.Range;@TeleOp(name="Starter Bot 2024", group="Iterative Opmode")publicclassStarterBot2024TeleopextendsOpMode{// Declare OpMode members.privateElapsedTime runtime =newElapsedTime();privateDcMotor leftDrive =null;privateDcMotor rightDrive =null;privateDcMotor armLeft =null;privateDcMotor armRight =null;privateServo gripper =null;privateServo wrist =null;privateboolean manualMode =false;privatedouble armSetpoint =0.0;privatefinaldouble armManualDeadband =0.03;privatefinaldouble gripperClosedPosition =1.0;privatefinaldouble gripperOpenPosition =0.5;privatefinaldouble wristUpPosition =1.0;privatefinaldouble wristDownPosition =0.0;privatefinalint armHomePosition =0;privatefinalint armIntakePosition =10;privatefinalint armScorePosition =600;privatefinalint armShutdownThreshold =5;/* * Code to run ONCE when the driver hits INIT */ @Overridepublicvoidinit() {telemetry.addData("Status","Initialized"); leftDrive =hardwareMap.get(DcMotor.class,"leftDrive"); rightDrive =hardwareMap.get(DcMotor.class,"rightDrive"); armLeft =hardwareMap.get(DcMotor.class,"armLeft"); armRight =hardwareMap.get(DcMotor.class,"armRight"); gripper =hardwareMap.get(Servo.class,"gripper"); wrist =hardwareMap.get(Servo.class,"wrist");leftDrive.setDirection(DcMotor.Direction.FORWARD);rightDrive.setDirection(DcMotor.Direction.REVERSE);leftDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);rightDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);armLeft.setDirection(DcMotor.Direction.FORWARD);armRight.setDirection(DcMotor.Direction.REVERSE);armLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);armRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);armLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);armRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);armLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);armRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);armLeft.setPower(0.0);armRight.setPower(0.0);telemetry.addData("Status","Initialized"); }/* * Code to run REPEATEDLY after the driver hits INIT, but before they hit PLAY */ @Overridepublicvoidinit_loop() { }/* * Code to run ONCE when the driver hits PLAY */ @Overridepublicvoidstart() {runtime.reset();armLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);armRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);armLeft.setTargetPosition(armHomePosition);armRight.setTargetPosition(armHomePosition);armLeft.setPower(1.0);armRight.setPower(1.0);armLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);armRight.setMode(DcMotor.RunMode.RUN_TO_POSITION); }/* * Code to run REPEATEDLY after the driver hits PLAY but before they hit STOP */ @Overridepublicvoidloop() {double leftPower;double rightPower;double manualArmPower;//DRIVEdouble drive =-gamepad1.left_stick_y;double turn =gamepad1.right_stick_x; leftPower =Range.clip(drive + turn,-1.0,1.0) ; rightPower =Range.clip(drive - turn,-1.0,1.0) ;leftDrive.setPower(leftPower);rightDrive.setPower(rightPower);//ARM & WRIST manualArmPower =gamepad1.right_trigger-gamepad1.left_trigger;if (Math.abs(manualArmPower) > armManualDeadband) {if (!manualMode) {armLeft.setPower(0.0);armRight.setPower(0.0);armLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);armRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); manualMode =true; }armLeft.setPower(manualArmPower);armRight.setPower(manualArmPower); }else {if (manualMode) {armLeft.setTargetPosition(armLeft.getCurrentPosition());armRight.setTargetPosition(armRight.getCurrentPosition());armLeft.setPower(1.0);armRight.setPower(1.0);armLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);armRight.setMode(DcMotor.RunMode.RUN_TO_POSITION); manualMode =false; }//preset buttonsif (gamepad1.a) {armLeft.setTargetPosition(armHomePosition);armRight.setTargetPosition(armHomePosition);armLeft.setPower(1.0);armRight.setPower(1.0);armLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);armRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);wrist.setPosition(wristUpPosition); }elseif (gamepad1.b) {armLeft.setTargetPosition(armIntakePosition);armRight.setTargetPosition(armIntakePosition);armLeft.setPower(1.0);armRight.setPower(1.0);armLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);armRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);wrist.setPosition(wristDownPosition); }elseif (gamepad1.y) {armLeft.setTargetPosition(armScorePosition);armRight.setTargetPosition(armScorePosition);armLeft.setPower(1.0);armRight.setPower(1.0);armLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);armRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);wrist.setPosition(wristUpPosition); } }//Re-zero encoder buttonif (gamepad1.start) {armLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);armRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);armLeft.setPower(0.0);armRight.setPower(0.0); manualMode =false; }//Watchdog to shut down motor once the arm reaches the home positionif (!manualMode &&armLeft.getMode() ==DcMotor.RunMode.RUN_TO_POSITION&&armLeft.getTargetPosition() <= armShutdownThreshold &&armLeft.getCurrentPosition() <= armShutdownThreshold ) {armLeft.setPower(0.0);armRight.setPower(0.0);armLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);armRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); }//GRIPPERif (gamepad1.left_bumper||gamepad1.right_bumper) {gripper.setPosition(gripperOpenPosition); }else {gripper.setPosition(gripperClosedPosition); }telemetry.addData("Status","Run Time: "+runtime.toString());telemetry.addData("Gamepad","drive (%.2f), turn (%.2f)", drive, turn);telemetry.addData("Motors","left (%.2f), right (%.2f)", leftPower, rightPower);telemetry.addData("Manual Power", manualArmPower);telemetry.addData("Arm Pos:","left = "+ ((Integer)armLeft.getCurrentPosition()).toString() +", right = "+ ((Integer)armRight.getCurrentPosition()).