Skip to content

Commit fe758ed

Browse files
committed
FtcRobotController v7.2
1 parent e945da2 commit fe758ed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

44 files changed

+619
-1479
lines changed

Diff for: FtcRobotController/build.gradle

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ android {
2020
sourceCompatibility JavaVersion.VERSION_1_7
2121
targetCompatibility JavaVersion.VERSION_1_7
2222
}
23+
namespace = 'com.qualcomm.ftcrobotcontroller'
2324
}
2425

2526
apply from: '../build.dependencies.gradle'

Diff for: FtcRobotController/src/main/AndroidManifest.xml

+2-3
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,8 @@
11
<?xml version="1.0" encoding="utf-8"?>
22
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
33
xmlns:tools="http://schemas.android.com/tools"
4-
package="com.qualcomm.ftcrobotcontroller"
5-
android:versionCode="44"
6-
android:versionName="7.1">
4+
android:versionCode="45"
5+
android:versionName="7.2">
76

87
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
98

Diff for: FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOmniOpMode_Linear.java

+13-4
Original file line numberDiff line numberDiff line change
@@ -46,15 +46,17 @@
4646
* Both of these drives are illustrated at https://gm0.org/en/latest/docs/robot-design/drivetrains/holonomic.html
4747
* Note that a Mecanum drive must display an X roller-pattern when viewed from above.
4848
*
49+
* Also note that it is critical to set the correct rotation direction for each motor. See details below.
50+
*
4951
* Holonomic drives provide the ability for the robot to move in three axes (directions) simultaneously.
5052
* Each motion axis is controlled by one Joystick axis.
5153
*
52-
* 1) Axial: Driving forward and backwards Left-joystick Forward/Backwards
54+
* 1) Axial: Driving forward and backward Left-joystick Forward/Backward
5355
* 2) Lateral: Strafing right and left Left-joystick Right and Left
5456
* 3) Yaw: Rotating Clockwise and counter clockwise Right-joystick Right and Left
5557
*
5658
* This code is written assuming that the right-side motors need to be reversed for the robot to drive forward.
57-
* When you first test your robot, if it moves backwards when you push the left stick forward, then you must flip
59+
* When you first test your robot, if it moves backward when you push the left stick forward, then you must flip
5860
* the direction of all 4 motors (see code below).
5961
*
6062
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
@@ -82,9 +84,16 @@ public void runOpMode() {
8284
rightFrontDrive = hardwareMap.get(DcMotor.class, "right_front_drive");
8385
rightBackDrive = hardwareMap.get(DcMotor.class, "right_back_drive");
8486

87+
// ########################################################################################
88+
// !!! IMPORTANT Drive Information. Test your motor directions. !!!!!
89+
// ########################################################################################
8590
// Most robots need the motors on one side to be reversed to drive forward.
86-
// When you first test your robot, push the left joystick forward
87-
// and flip the direction ( FORWARD <-> REVERSE ) of any wheel that runs backwards
91+
// The motor reversals shown here are for a "direct drive" robot (the wheels turn the same direction as the motor shaft)
92+
// If your robot has additional gear reductions or uses a right-angled drive, it's important to ensure
93+
// that your motors are turning in the correct direction. So, start out with the reversals here, BUT
94+
// when you first test your robot, push the left joystick forward and observe the direction the wheels turn.
95+
// Reverse the direction (flip FORWARD <-> REVERSE ) of any wheel that runs backward
96+
// Keep testing until ALL the wheels move the robot forward when you push the left joystick forward.
8897
leftFrontDrive.setDirection(DcMotor.Direction.REVERSE);
8998
leftBackDrive.setDirection(DcMotor.Direction.REVERSE);
9099
rightFrontDrive.setDirection(DcMotor.Direction.FORWARD);

Diff for: FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Iterative.java

+7-6
Original file line numberDiff line numberDiff line change
@@ -40,13 +40,13 @@
4040
* This file contains an example of an iterative (Non-Linear) "OpMode".
4141
* An OpMode is a 'program' that runs in either the autonomous or the teleop period of an FTC match.
4242
* The names of OpModes appear on the menu of the FTC Driver Station.
43-
* When an selection is made from the menu, the corresponding OpMode
43+
* When a selection is made from the menu, the corresponding OpMode
4444
* class is instantiated on the Robot Controller and executed.
4545
*
4646
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
4747
* It includes all the skeletal structure that all iterative OpModes contain.
4848
*
49-
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
49+
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
5050
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
5151
*/
5252

@@ -72,10 +72,11 @@ public void init() {
7272
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
7373
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
7474

75-
// Most robots need the motor on one side to be reversed to drive forward
76-
// Reverse the motor that runs backwards when connected directly to the battery
77-
leftDrive.setDirection(DcMotor.Direction.FORWARD);
78-
rightDrive.setDirection(DcMotor.Direction.REVERSE);
75+
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
76+
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
77+
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
78+
leftDrive.setDirection(DcMotor.Direction.REVERSE);
79+
rightDrive.setDirection(DcMotor.Direction.FORWARD);
7980

8081
// Tell the driver that initialization is complete.
8182
telemetry.addData("Status", "Initialized");

Diff for: FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Linear.java

+7-6
Original file line numberDiff line numberDiff line change
@@ -40,13 +40,13 @@
4040
/**
4141
* This file contains an minimal example of a Linear "OpMode". An OpMode is a 'program' that runs in either
4242
* the autonomous or the teleop period of an FTC match. The names of OpModes appear on the menu
43-
* of the FTC Driver Station. When an selection is made from the menu, the corresponding OpMode
43+
* of the FTC Driver Station. When a selection is made from the menu, the corresponding OpMode
4444
* class is instantiated on the Robot Controller and executed.
4545
*
4646
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
4747
* It includes all the skeletal structure that all linear OpModes contain.
4848
*
49-
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
49+
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
5050
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
5151
*/
5252

@@ -70,10 +70,11 @@ public void runOpMode() {
7070
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
7171
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
7272

73-
// Most robots need the motor on one side to be reversed to drive forward
74-
// Reverse the motor that runs backwards when connected directly to the battery
75-
leftDrive.setDirection(DcMotor.Direction.FORWARD);
76-
rightDrive.setDirection(DcMotor.Direction.REVERSE);
73+
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
74+
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
75+
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
76+
leftDrive.setDirection(DcMotor.Direction.REVERSE);
77+
rightDrive.setDirection(DcMotor.Direction.FORWARD);
7778

7879
// Wait for the game to start (driver presses PLAY)
7980
waitForStart();

Diff for: FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptCompassCalibration.java

+16-12
Original file line numberDiff line numberDiff line change
@@ -33,13 +33,11 @@
3333
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
3434
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
3535
import com.qualcomm.robotcore.hardware.CompassSensor;
36+
import com.qualcomm.robotcore.hardware.DcMotor;
3637
import com.qualcomm.robotcore.util.ElapsedTime;
3738

3839
/**
3940
* This file illustrates the concept of calibrating a MR Compass
40-
* It uses the common Pushbot hardware class to define the drive on the robot.
41-
* The code is structured as a LinearOpMode
42-
*
4341
* This code assumes there is a compass configured with the name "compass"
4442
*
4543
* This code will put the compass into calibration mode, wait three seconds and then attempt
@@ -57,7 +55,8 @@
5755
public class ConceptCompassCalibration extends LinearOpMode {
5856

5957
/* Declare OpMode members. */
60-
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
58+
public DcMotor leftDrive = null;
59+
public DcMotor rightDrive = null;
6160
private ElapsedTime runtime = new ElapsedTime();
6261
CompassSensor compass;
6362

@@ -68,10 +67,15 @@ public class ConceptCompassCalibration extends LinearOpMode {
6867
@Override
6968
public void runOpMode() {
7069

71-
/* Initialize the drive system variables.
72-
* The init() method of the hardware class does all the work here
73-
*/
74-
robot.init(hardwareMap);
70+
// Initialize the drive system variables.
71+
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
72+
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
73+
74+
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
75+
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
76+
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
77+
leftDrive.setDirection(DcMotor.Direction.REVERSE);
78+
rightDrive.setDirection(DcMotor.Direction.FORWARD);
7579

7680
// get a reference to our Compass Sensor object.
7781
compass = hardwareMap.get(CompassSensor.class, "compass");
@@ -93,8 +97,8 @@ public void runOpMode() {
9397
// Start the robot rotating clockwise
9498
telemetry.addData("Compass", "Calibration mode. Turning the robot...");
9599
telemetry.update();
96-
robot.leftDrive.setPower(MOTOR_POWER);
97-
robot.rightDrive.setPower(-MOTOR_POWER);
100+
leftDrive.setPower(MOTOR_POWER);
101+
rightDrive.setPower(-MOTOR_POWER);
98102

99103
// run until time expires OR the driver presses STOP;
100104
runtime.reset();
@@ -103,8 +107,8 @@ public void runOpMode() {
103107
}
104108

105109
// Stop all motors and turn off claibration
106-
robot.leftDrive.setPower(0);
107-
robot.rightDrive.setPower(0);
110+
leftDrive.setPower(0);
111+
rightDrive.setPower(0);
108112
compass.setMode(CompassSensor.CompassMode.MEASUREMENT_MODE);
109113
telemetry.addData("Compass", "Returning to measurement mode");
110114
telemetry.update();

Diff for: FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptDIMAsIndicator.java

-103
This file was deleted.

0 commit comments

Comments
 (0)