diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BasicOmniOpMode_Linear.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BasicOmniOpMode_Linear.java
index f323723..835606a 100644
--- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BasicOmniOpMode_Linear.java
+++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BasicOmniOpMode_Linear.java
@@ -29,17 +29,30 @@
package org.firstinspires.ftc.teamcode;
+import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_ENCODER;
+import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_ENCODER_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_LEFT_MOTOR;
+import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_LEFT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_RIGHT_MOTOR;
+import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_RIGHT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_LEFT_MOTOR;
+import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_LEFT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_RIGHT_MOTOR;
+import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_RIGHT_MOTOR_DIRECTION;
+import static org.firstinspires.ftc.teamcode.PedroConstants.LEFT_ENCODER;
+import static org.firstinspires.ftc.teamcode.PedroConstants.LEFT_ENCODER_DIRECTION;
+import static org.firstinspires.ftc.teamcode.PedroConstants.RIGHT_ENCODER;
+import static org.firstinspires.ftc.teamcode.PedroConstants.RIGHT_ENCODER_DIRECTION;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
+import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.util.ElapsedTime;
+import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder;
+
/*
* This file contains an example of a Linear "OpMode".
* An OpMode is a 'program' that runs in either the autonomous or the teleop period of an FTC match.
@@ -77,6 +90,9 @@ public class BasicOmniOpMode_Linear extends LinearOpMode {
private DcMotor leftBackDrive = null;
private DcMotor rightFrontDrive = null;
private DcMotor rightBackDrive = null;
+ private Encoder leftEncoder;
+ private Encoder rightEncoder;
+ private Encoder strafeEncoder;
@Override
public void runOpMode() {
@@ -88,6 +104,16 @@ public class BasicOmniOpMode_Linear extends LinearOpMode {
rightFrontDrive = hardwareMap.get(DcMotor.class, FRONT_RIGHT_MOTOR);
rightBackDrive = hardwareMap.get(DcMotor.class, BACK_RIGHT_MOTOR);
+ // TODO: replace these with your encoder ports
+ leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, LEFT_ENCODER));
+ rightEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, RIGHT_ENCODER));
+ strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, BACK_ENCODER));
+
+ // TODO: reverse any encoders necessary
+ leftEncoder.setDirection(LEFT_ENCODER_DIRECTION);
+ rightEncoder.setDirection(RIGHT_ENCODER_DIRECTION);
+ strafeEncoder.setDirection(BACK_ENCODER_DIRECTION);
+
// ########################################################################################
// !!! IMPORTANT Drive Information. Test your motor directions. !!!!!
// ########################################################################################
@@ -98,13 +124,16 @@ public class BasicOmniOpMode_Linear extends LinearOpMode {
// 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.REVERSE);
- rightBackDrive.setDirection(DcMotor.Direction.REVERSE);
+ leftFrontDrive.setDirection(FRONT_LEFT_MOTOR_DIRECTION);
+ leftBackDrive.setDirection(BACK_LEFT_MOTOR_DIRECTION);
+ rightFrontDrive.setDirection(FRONT_RIGHT_MOTOR_DIRECTION);
+ rightBackDrive.setDirection(BACK_RIGHT_MOTOR_DIRECTION);
// Wait for the game to start (driver presses START)
telemetry.addData("Status", "Initialized");
+ telemetry.addData("Left Encoder Value", leftEncoder.getDeltaPosition());
+ telemetry.addData("Right Encoder Value", rightEncoder.getDeltaPosition());
+ telemetry.addData("Strafe Encoder Value", strafeEncoder.getDeltaPosition());
telemetry.update();
waitForStart();
@@ -166,6 +195,9 @@ public class BasicOmniOpMode_Linear extends LinearOpMode {
telemetry.addData("Status", "Run Time: " + runtime.toString());
telemetry.addData("Front left/Right", "%4.2f, %4.2f", leftFrontPower, rightFrontPower);
telemetry.addData("Back left/Right", "%4.2f, %4.2f", leftBackPower, rightBackPower);
+ telemetry.addData("Left Encoder Value", leftEncoder.getDeltaPosition());
+ telemetry.addData("Right Encoder Value", rightEncoder.getDeltaPosition());
+ telemetry.addData("Strafe Encoder Value", strafeEncoder.getDeltaPosition());
telemetry.update();
}
}}
diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java
index d0846bd..4e98812 100644
--- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java
+++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java
@@ -22,8 +22,8 @@ public class PedroConstants {
// Robot motor direction
public static final Direction FRONT_LEFT_MOTOR_DIRECTION = Direction.REVERSE;
public static final Direction BACK_LEFT_MOTOR_DIRECTION = Direction.REVERSE;
- public static final Direction FRONT_RIGHT_MOTOR_DIRECTION = Direction.REVERSE;
- public static final Direction BACK_RIGHT_MOTOR_DIRECTION = Direction.REVERSE;
+ public static final Direction FRONT_RIGHT_MOTOR_DIRECTION = Direction.FORWARD;
+ public static final Direction BACK_RIGHT_MOTOR_DIRECTION = Direction.FORWARD;
// Robot IMU configuration
public static final String IMU = "imu";
@@ -42,7 +42,7 @@ public class PedroConstants {
// Robot encoder direction
public static final double LEFT_ENCODER_DIRECTION = Encoder.FORWARD;
public static final double RIGHT_ENCODER_DIRECTION = Encoder.FORWARD;
- public static final double BACK_ENCODER_DIRECTION = Encoder.REVERSE;
+ public static final double BACK_ENCODER_DIRECTION = Encoder.FORWARD;
/*
Pedro's parameters
diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorIMUOrthogonal.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorIMUOrthogonal.java
new file mode 100644
index 0000000..d9640b3
--- /dev/null
+++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorIMUOrthogonal.java
@@ -0,0 +1,171 @@
+/* Copyright (c) 2022 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.
+ */
+
+package org.firstinspires.ftc.teamcode;
+
+import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_ENCODER;
+import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_ENCODER_DIRECTION;
+import static org.firstinspires.ftc.teamcode.PedroConstants.IMU_LOGO_FACING_DIRECTION;
+import static org.firstinspires.ftc.teamcode.PedroConstants.IMU_USB_FACING_DIRECTION;
+import static org.firstinspires.ftc.teamcode.PedroConstants.LEFT_ENCODER;
+import static org.firstinspires.ftc.teamcode.PedroConstants.LEFT_ENCODER_DIRECTION;
+import static org.firstinspires.ftc.teamcode.PedroConstants.RIGHT_ENCODER;
+import static org.firstinspires.ftc.teamcode.PedroConstants.RIGHT_ENCODER_DIRECTION;
+
+import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
+import com.qualcomm.robotcore.eventloop.opmode.Disabled;
+import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
+import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
+import com.qualcomm.robotcore.hardware.DcMotorEx;
+import com.qualcomm.robotcore.hardware.IMU;
+
+import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
+import org.firstinspires.ftc.robotcore.external.navigation.AngularVelocity;
+import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
+import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder;
+
+/*
+ * This OpMode shows how to use the new universal IMU interface. This
+ * interface may be used with the BNO055 IMU or the BHI260 IMU. It assumes that an IMU is configured
+ * on the robot with the name "imu".
+ *
+ * The sample will display the current Yaw, Pitch and Roll of the robot.
+ * With the correct orientation parameters selected, pitch/roll/yaw should act as follows:
+ * Pitch value should INCREASE as the robot is tipped UP at the front. (Rotation about X)
+ * Roll value should INCREASE as the robot is tipped UP at the left side. (Rotation about Y)
+ * Yaw value should INCREASE as the robot is rotated Counter Clockwise. (Rotation about Z)
+ *
+ * The yaw can be reset (to zero) by pressing the Y button on the gamepad (Triangle on a PS4 controller)
+ *
+ * This specific sample assumes that the Hub is mounted on one of the three orthogonal planes
+ * (X/Y, X/Z or Y/Z) and that the Hub has only been rotated in a range of 90 degree increments.
+ *
+ * Note: if your Hub is mounted on a surface angled at some non-90 Degree multiple (like 30) look at
+ * the alternative SensorIMUNonOrthogonal sample in this folder.
+ *
+ * This "Orthogonal" requirement means that:
+ *
+ * 1) The Logo printed on the top of the Hub can ONLY be pointing in one of six directions:
+ * FORWARD, BACKWARD, UP, DOWN, LEFT and RIGHT.
+ *
+ * 2) The USB ports can only be pointing in one of the same six directions:
+ * FORWARD, BACKWARD, UP, DOWN, LEFT and RIGHT.
+ *
+ * So, To fully define how your Hub is mounted to the robot, you must simply specify:
+ * logoFacingDirection
+ * usbFacingDirection
+ *
+ * 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.
+ *
+ * Finally, choose the two correct parameters to define how your Hub is mounted and edit this OpMode
+ * to use those parameters.
+ */
+@TeleOp(name = "Sensor: IMU Orthogonal", group = "Sensor")
+@Disabled // Comment this out to add to the OpMode list
+public class SensorIMUOrthogonal extends LinearOpMode {
+ // The IMU sensor object
+ IMU imu;
+ private Encoder leftEncoder;
+ private Encoder rightEncoder;
+ private Encoder strafeEncoder;
+
+ //----------------------------------------------------------------------------------------------
+ // Main logic
+ //----------------------------------------------------------------------------------------------
+
+ @Override
+ public void runOpMode() throws InterruptedException {
+
+ // Retrieve and initialize the IMU.
+ // This sample expects the IMU to be in a REV Hub and named "imu".
+ imu = hardwareMap.get(IMU.class, PedroConstants.IMU);
+
+ // TODO: replace these with your encoder ports
+ leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, LEFT_ENCODER));
+ rightEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, RIGHT_ENCODER));
+ strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, BACK_ENCODER));
+
+ // TODO: reverse any encoders necessary
+ leftEncoder.setDirection(LEFT_ENCODER_DIRECTION);
+ rightEncoder.setDirection(RIGHT_ENCODER_DIRECTION);
+ strafeEncoder.setDirection(BACK_ENCODER_DIRECTION);
+
+ /* Define how the hub is mounted on the robot to get the correct Yaw, Pitch and Roll values.
+ *
+ * Two input parameters are required to fully specify the Orientation.
+ * The first parameter specifies the direction the printed logo on the Hub is pointing.
+ * The second parameter specifies the direction the USB connector on the Hub is pointing.
+ * All directions are relative to the robot, and left/right is as-viewed from behind the robot.
+ *
+ * If you are using a REV 9-Axis IMU, you can use the Rev9AxisImuOrientationOnRobot class instead of the
+ * RevHubOrientationOnRobot class, which has an I2cPortFacingDirection instead of a UsbFacingDirection.
+ */
+
+ /* The next two lines define Hub orientation.
+ * The Default Orientation (shown) is when a hub is mounted horizontally with the printed logo pointing UP and the USB port pointing FORWARD.
+ *
+ * To Do: EDIT these two lines to match YOUR mounting configuration.
+ */
+ RevHubOrientationOnRobot.LogoFacingDirection logoDirection = IMU_LOGO_FACING_DIRECTION;
+ RevHubOrientationOnRobot.UsbFacingDirection usbDirection = IMU_USB_FACING_DIRECTION;
+
+ RevHubOrientationOnRobot orientationOnRobot = new RevHubOrientationOnRobot(logoDirection, usbDirection);
+
+ // Now initialize the IMU with this mounting orientation
+ // Note: if you choose two conflicting directions, this initialization will cause a code exception.
+ imu.initialize(new IMU.Parameters(orientationOnRobot));
+
+ // Loop and update the dashboard
+ while (!isStopRequested()) {
+
+ telemetry.addData("Hub orientation", "Logo=%s USB=%s\n ", logoDirection, usbDirection);
+
+ // Check to see if heading reset is requested
+ if (gamepad1.y) {
+ telemetry.addData("Yaw", "Resetting\n");
+ imu.resetYaw();
+ } else {
+ telemetry.addData("Yaw", "Press Y (triangle) on Gamepad to reset\n");
+ }
+
+ // Retrieve Rotational Angles and Velocities
+ YawPitchRollAngles orientation = imu.getRobotYawPitchRollAngles();
+ AngularVelocity angularVelocity = imu.getRobotAngularVelocity(AngleUnit.DEGREES);
+
+ telemetry.addData("Yaw (Z)", "%.2f Deg. (Heading)", orientation.getYaw(AngleUnit.DEGREES));
+ telemetry.addData("Pitch (X)", "%.2f Deg.", orientation.getPitch(AngleUnit.DEGREES));
+ telemetry.addData("Roll (Y)", "%.2f Deg.\n", orientation.getRoll(AngleUnit.DEGREES));
+ telemetry.addData("Yaw (Z) velocity", "%.2f Deg/Sec", angularVelocity.zRotationRate);
+ telemetry.addData("Pitch (X) velocity", "%.2f Deg/Sec", angularVelocity.xRotationRate);
+ telemetry.addData("Roll (Y) velocity", "%.2f Deg/Sec", angularVelocity.yRotationRate);
+ telemetry.update();
+ }
+ }
+}
diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md
index bd22f46..c7fa481 100644
--- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md
+++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md
@@ -71,7 +71,8 @@ measurements will be in centimeters.
of how fast your robot will coast to a stop. Honestly, this is up to you. I personally used 4, but
what works best for you is most important. Higher numbers will cause a faster brake, but increase
oscillations at the end. Lower numbers will do the opposite. This can be found on line `107` in
- `FollowerConstants`, named `zeroPowerAccelerationMultiplier`. The drive PID is much, much more sensitive than the others. For reference,
+ `FollowerConstants`, named `zeroPowerAccelerationMultiplier`. The drive PID is much, much more
+* sensitive than the others. For reference,
my P values were in the hundredths and thousandths place values, and my D values were in the hundred
thousandths and millionths place values. To tune this, enable `useDrive`, `useHeading`, and
`useTranslational` in the `Follower` dropdown in FTC Dashboard. Next, run `StraightBackAndForth`
diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java
index ad74928..3576f9d 100644
--- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java
+++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java
@@ -70,7 +70,7 @@ public class PoseUpdater {
*/
public PoseUpdater(HardwareMap hardwareMap) {
// TODO: replace the second argument with your preferred localizer
- this(hardwareMap, new DriveEncoderLocalizer(hardwareMap));
+ this(hardwareMap, new ThreeWheelLocalizer(hardwareMap));
}
/**
diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java
index b1d5c54..9f850c6 100644
--- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java
+++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java
@@ -57,9 +57,12 @@ public class ThreeWheelLocalizer extends Localizer {
private Pose rightEncoderPose;
private Pose strafeEncoderPose;
private double totalHeading;
- public static double FORWARD_TICKS_TO_INCHES = 0.00052189;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963;
- public static double STRAFE_TICKS_TO_INCHES = 0.00052189;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659;
- public static double TURN_TICKS_TO_RADIANS = 0.00053717;//8192 * 1.37795 * 2 * Math.PI * 0.5;
+// public static double FORWARD_TICKS_TO_INCHES = 0.00052189;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963;
+ public static double FORWARD_TICKS_TO_INCHES = 0.0029;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963;
+// public static double STRAFE_TICKS_TO_INCHES = 0.00052189;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659;
+ public static double STRAFE_TICKS_TO_INCHES = 0.0029;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659;
+// public static double TURN_TICKS_TO_RADIANS = 0.00053717;//8192 * 1.37795 * 2 * Math.PI * 0.5;
+ public static double TURN_TICKS_TO_RADIANS = 0.003;//8192 * 1.37795 * 2 * Math.PI * 0.5;
/**
* This creates a new ThreeWheelLocalizer from a HardwareMap, with a starting Pose at (0,0)
@@ -80,9 +83,9 @@ public class ThreeWheelLocalizer extends Localizer {
*/
public ThreeWheelLocalizer(HardwareMap map, Pose setStartPose) {
// TODO: replace these with your encoder positions
- leftEncoderPose = new Pose(-18.5/25.4 - 0.1, 164.4/25.4, 0);
- rightEncoderPose = new Pose(-18.4/25.4 - 0.1, -159.6/25.4, 0);
- strafeEncoderPose = new Pose(0*(-107.9/25.4+8)+-107.9/25.4+0.25, -1.1/25.4-0.23, Math.toRadians(90));
+ leftEncoderPose = new Pose(0, 6.19375, 0);
+ rightEncoderPose = new Pose(0, -6.19375, 0);
+ strafeEncoderPose = new Pose(-7, 0, Math.toRadians(90));
hardwareMap = map;
@@ -92,9 +95,9 @@ public class ThreeWheelLocalizer extends Localizer {
strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, BACK_ENCODER));
// TODO: reverse any encoders necessary
- //leftEncoder.setDirection(Encoder.REVERSE);
- // rightEncoder.setDirection(Encoder.REVERSE);
- //strafeEncoder.setDirection(Encoder.FORWARD);
+ leftEncoder.setDirection(LEFT_ENCODER_DIRECTION);
+ rightEncoder.setDirection(RIGHT_ENCODER_DIRECTION);
+ strafeEncoder.setDirection(BACK_ENCODER_DIRECTION);
setStartPose(setStartPose);
timer = new NanoTimer();