Skip to content

Commit

Permalink
Merge pull request FIRST-Tech-Challenge#324 from FIRST-Tech-Challenge…
Browse files Browse the repository at this point in the history
…/20220723-130006-release-candidate

FtcRobotController v7.2
  • Loading branch information
CalKestis authored Jul 25, 2022
2 parents e945da2 + fe758ed commit aba72e5
Show file tree
Hide file tree
Showing 44 changed files with 619 additions and 1,479 deletions.
1 change: 1 addition & 0 deletions FtcRobotController/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ android {
sourceCompatibility JavaVersion.VERSION_1_7
targetCompatibility JavaVersion.VERSION_1_7
}
namespace = 'com.qualcomm.ftcrobotcontroller'
}

apply from: '../build.dependencies.gradle'
5 changes: 2 additions & 3 deletions FtcRobotController/src/main/AndroidManifest.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
<?xml version="1.0" encoding="utf-8"?>
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:tools="http://schemas.android.com/tools"
package="com.qualcomm.ftcrobotcontroller"
android:versionCode="44"
android:versionName="7.1">
android:versionCode="45"
android:versionName="7.2">

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

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

// ########################################################################################
// !!! IMPORTANT Drive Information. Test your motor directions. !!!!!
// ########################################################################################
// Most robots need the motors on one side to be reversed to drive forward.
// When you first test your robot, push the left joystick forward
// and flip the direction ( FORWARD <-> REVERSE ) of any wheel that runs backwards
// The motor reversals shown here are for a "direct drive" robot (the wheels turn the same direction as the motor shaft)
// If your robot has additional gear reductions or uses a right-angled drive, it's important to ensure
// that your motors are turning in the correct direction. So, start out with the reversals here, BUT
// when you first test your robot, push the left joystick forward and observe the direction the wheels turn.
// Reverse the direction (flip FORWARD <-> REVERSE ) of any wheel that runs backward
// Keep testing until ALL the wheels move the robot forward when you push the left joystick forward.
leftFrontDrive.setDirection(DcMotor.Direction.REVERSE);
leftBackDrive.setDirection(DcMotor.Direction.REVERSE);
rightFrontDrive.setDirection(DcMotor.Direction.FORWARD);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,13 @@
* This file contains an example of an iterative (Non-Linear) "OpMode".
* An OpMode is a 'program' that runs in either the autonomous or the teleop period of an FTC match.
* The names of OpModes appear on the menu of the FTC Driver Station.
* When an selection is made from the menu, the corresponding OpMode
* When a selection is made from the menu, the corresponding OpMode
* class is instantiated on the Robot Controller and executed.
*
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
* It includes all the skeletal structure that all iterative OpModes contain.
*
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
*/

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

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

// Tell the driver that initialization is complete.
telemetry.addData("Status", "Initialized");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,13 @@
/**
* This file contains an minimal example of a Linear "OpMode". An OpMode is a 'program' that runs in either
* the autonomous or the teleop period of an FTC match. The names of OpModes appear on the menu
* of the FTC Driver Station. When an selection is made from the menu, the corresponding OpMode
* of the FTC Driver Station. When a selection is made from the menu, the corresponding OpMode
* class is instantiated on the Robot Controller and executed.
*
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
* It includes all the skeletal structure that all linear OpModes contain.
*
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
*/

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

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

// Wait for the game to start (driver presses PLAY)
waitForStart();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,11 @@
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.CompassSensor;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;

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

/* Declare OpMode members. */
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
public DcMotor leftDrive = null;
public DcMotor rightDrive = null;
private ElapsedTime runtime = new ElapsedTime();
CompassSensor compass;

Expand All @@ -68,10 +67,15 @@ public class ConceptCompassCalibration extends LinearOpMode {
@Override
public void runOpMode() {

/* Initialize the drive system variables.
* The init() method of the hardware class does all the work here
*/
robot.init(hardwareMap);
// Initialize the drive system variables.
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");

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

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

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

// Stop all motors and turn off claibration
robot.leftDrive.setPower(0);
robot.rightDrive.setPower(0);
leftDrive.setPower(0);
rightDrive.setPower(0);
compass.setMode(CompassSensor.CompassMode.MEASUREMENT_MODE);
telemetry.addData("Compass", "Returning to measurement mode");
telemetry.update();
Expand Down

This file was deleted.

Loading

0 comments on commit aba72e5

Please sign in to comment.