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 deleted file mode 100644 index e33996f..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BasicOmniOpMode_Linear.java +++ /dev/null @@ -1,210 +0,0 @@ -/* Copyright (c) 2021 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.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 org.firstinspires.ftc.teamcode.PedroConstants.*; -import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder; - -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; - -/* - * 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. - * The names of OpModes appear on the menu of the FTC Driver Station. - * When a selection is made from the menu, the corresponding OpMode is executed. - * - * This particular OpMode illustrates driving a 4-motor Omni-Directional (or Holonomic) robot. - * This code will work with either a Mecanum-Drive or an X-Drive train. - * 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 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 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. - * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list - */ - -@TeleOp(name="Basic: Omni Linear OpMode", group="Linear OpMode") -public class BasicOmniOpMode_Linear extends LinearOpMode { - - // Declare OpMode members for each of the 4 motors. - private ElapsedTime runtime = new ElapsedTime(); - private DcMotor leftFrontDrive = null; - 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() { - - // Initialize the hardware variables. Note that the strings used here must correspond - // to the names assigned during the robot configuration step on the DS or RC devices. - leftFrontDrive = hardwareMap.get(DcMotor.class, FRONT_LEFT_MOTOR); - leftBackDrive = hardwareMap.get(DcMotor.class, BACK_LEFT_MOTOR); - rightFrontDrive = hardwareMap.get(DcMotor.class, FRONT_RIGHT_MOTOR); - rightBackDrive = hardwareMap.get(DcMotor.class, BACK_RIGHT_MOTOR); - - // ######################################################################################## - // !!! IMPORTANT Drive Information. Test your motor directions. !!!!! - // ######################################################################################## - // Most robots need the motors on one side to be reversed to drive forward. - // 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(FRONT_LEFT_MOTOR_DIRECTION); - leftBackDrive.setDirection(BACK_LEFT_MOTOR_DIRECTION); - rightFrontDrive.setDirection(FRONT_RIGHT_MOTOR_DIRECTION); - rightBackDrive.setDirection(BACK_RIGHT_MOTOR_DIRECTION); - - // 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); - - leftEncoder.reset(); - rightEncoder.reset(); - strafeEncoder.reset(); - - // Wait for the game to start (driver presses START) - telemetry.addData("Status", "Initialized"); - telemetry.update(); - - waitForStart(); - runtime.reset(); - - // run until the end of the match (driver presses STOP) - while (opModeIsActive()) { - double max; - - // POV Mode uses left joystick to go forward & strafe, and right joystick to rotate. - double axial = -gamepad1.left_stick_y; // Note: pushing stick forward gives negative value - double lateral = gamepad1.left_stick_x; - double yaw = gamepad1.right_stick_x; - - // Combine the joystick requests for each axis-motion to determine each wheel's power. - // Set up a variable for each drive wheel to save the power level for telemetry. - double leftFrontPower = axial + lateral + yaw; - double rightFrontPower = axial - lateral - yaw; - double leftBackPower = axial - lateral + yaw; - double rightBackPower = axial + lateral - yaw; - - // Normalize the values so no wheel power exceeds 100% - // This ensures that the robot maintains the desired motion. - max = Math.max(Math.abs(leftFrontPower), Math.abs(rightFrontPower)); - max = Math.max(max, Math.abs(leftBackPower)); - max = Math.max(max, Math.abs(rightBackPower)); - - if (max > 1.0) { - leftFrontPower /= max; - rightFrontPower /= max; - leftBackPower /= max; - rightBackPower /= max; - } - - // This is test code: - // - // Uncomment the following code to test your motor directions. - // Each button should make the corresponding motor run FORWARD. - // 1) First get all the motors to take to correct positions on the robot - // by adjusting your Robot Configuration if necessary. - // 2) Then make sure they run in the correct direction by modifying the - // the setDirection() calls above. - // Once the correct motors move in the correct direction re-comment this code. - - - // leftFrontPower = gamepad1.x ? 1.0 : 0.0; // X gamepad - // leftBackPower = gamepad1.a ? 1.0 : 0.0; // A gamepad - // rightFrontPower = gamepad1.y ? 1.0 : 0.0; // Y gamepad - // rightBackPower = gamepad1.b ? 1.0 : 0.0; // B gamepad - - - // Send calculated power to wheels - leftFrontDrive.setPower(leftFrontPower); - rightFrontDrive.setPower(rightFrontPower); - leftBackDrive.setPower(leftBackPower); - rightBackDrive.setPower(rightBackPower); - - leftEncoder.update(); - rightEncoder.update(); - strafeEncoder.update(); - - // Show the elapsed game time and wheel power. - 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("Encoder Left", leftEncoder.getDeltaPosition()); - telemetry.addData("Encoder Right", rightEncoder.getDeltaPosition()); - telemetry.addData("Encoder Back (Right is +)", 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 6ed40c0..88bfac0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java @@ -40,7 +40,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; // Arm config public static final String SLIDE_MOTOR = "SlideMotor"; @@ -53,24 +53,24 @@ public class PedroConstants { */ // The weight of the robot in Kilograms - public static final double ROBOT_WEIGHT_IN_KG = 10.5; + public static final double ROBOT_WEIGHT_IN_KG = 9; // Maximum velocity of the robot going forward - public static final double ROBOT_SPEED_FORWARD = 79.0257; + public static final double ROBOT_SPEED_FORWARD = 51.5; // Maximum velocity of the robot going right - public static final double ROBOT_SPEED_LATERAL = 12.3941; + public static final double ROBOT_SPEED_LATERAL = 28.7; // Rate of deceleration when power is cut-off when the robot is moving forward - public static final double FORWARD_ZERO_POWER_ACCEL = -50.7945; + public static final double FORWARD_ZERO_POWER_ACCEL = -59.8; // Rate of deceleration when power is cut-off when the robot is moving to the right - public static final double LATERAL_ZERO_POWER_ACCEL = -92.733; + public static final double LATERAL_ZERO_POWER_ACCEL = -99.7; // Determines how fast your robot will decelerate as a factor of how fast your robot will coast to a stop - public static final double ZERO_POWER_ACCEL_MULT = 2.5; + public static final double ZERO_POWER_ACCEL_MULT = 3.5; /* Centripetal force correction - increase if robot is correcting into the path - decrease if robot is correcting away from the path */ - public static final double CENTRIPETAL_SCALING = 0.0005; + public static final double CENTRIPETAL_SCALING = 0.0004; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/BlueBasketAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/BlueBasketAuto.java index c596660..9a7e7a3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/BlueBasketAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/BlueBasketAuto.java @@ -35,7 +35,7 @@ public class BlueBasketAuto extends OpMode { private PathChain path; - private final Pose startPose = new Pose(11.25, 95.75); + private final Pose startPose = new Pose(11.25, 95.75, 0); /** * This initializes the Follower and creates the PathChain for the "circle". Additionally, this @@ -140,7 +140,7 @@ public class BlueBasketAuto extends OpMode { ) ) .setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(270)).build(); - follower.followPath(path); + follower.followPath(path, true); telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); telemetryA.update(); @@ -154,7 +154,7 @@ public class BlueBasketAuto extends OpMode { public void loop() { follower.update(); if (follower.atParametricEnd()) { - follower.followPath(path); + follower.followPath(path, true); } follower.telemetryDebug(telemetryA); } 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 6bd60f7..ce2a8f2 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 @@ -69,7 +69,7 @@ public class PoseUpdater { */ public PoseUpdater(HardwareMap hardwareMap) { // TODO: replace the second argument with your preferred localizer - this(hardwareMap, new ThreeWheelIMULocalizer(hardwareMap)); + this(hardwareMap, new ThreeWheelLocalizer(hardwareMap)); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java index ef92025..71145e2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java @@ -65,9 +65,9 @@ public class ThreeWheelIMULocalizer extends Localizer { private double previousIMUOrientation; private double deltaRadians; private double totalHeading; - public static double FORWARD_TICKS_TO_INCHES = 0.004;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963; - public static double STRAFE_TICKS_TO_INCHES = -0.0036;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659; - public static double TURN_TICKS_TO_RADIANS = 0.0043;//8192 * 1.37795 * 2 * Math.PI * 0.5; + 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.0029;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659; + public static double TURN_TICKS_TO_RADIANS = 0.0022;//8192 * 1.37795 * 2 * Math.PI * 0.5; public static boolean useIMU = true; @@ -96,9 +96,9 @@ public class ThreeWheelIMULocalizer extends Localizer { imu.initialize(new IMU.Parameters(new RevHubOrientationOnRobot(IMU_LOGO_FACING_DIRECTION, IMU_USB_FACING_DIRECTION))); // TODO: replace these with your encoder positions - leftEncoderPose = new Pose(-7.625, 6.19375, 0); - rightEncoderPose = new Pose(-7.625, -6.19375, 0); - strafeEncoderPose = new Pose(7, 1, 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)); // TODO: replace these with your encoder ports leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, LEFT_ENCODER)); 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..c554097 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,9 @@ 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.0029;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963; + 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.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 +80,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; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java index 45423bc..d0ab034 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java @@ -40,9 +40,9 @@ public class FollowerConstants { // Translational PIDF coefficients (don't use integral) public static CustomPIDFCoefficients translationalPIDFCoefficients = new CustomPIDFCoefficients( - 0.05, - 0, + 0.1, 0, + 0.01, 0); // Translational Integral @@ -58,9 +58,9 @@ public class FollowerConstants { // Heading error PIDF coefficients public static CustomPIDFCoefficients headingPIDFCoefficients = new CustomPIDFCoefficients( - 1, + 2, 0, - 0.1, + 0.025, 0); // Feed forward constant added on to the heading PIDF @@ -69,10 +69,10 @@ public class FollowerConstants { // Drive PIDF coefficients public static CustomFilteredPIDFCoefficients drivePIDFCoefficients = new CustomFilteredPIDFCoefficients( - 0.00475, + 0.006, 0, - 0.00004125, - 0.0, + 0.00001, + 0.8, 0); // Feed forward constant added on to the drive PIDF @@ -81,7 +81,7 @@ public class FollowerConstants { // Kalman filter parameters for the drive error Kalman filter public static KalmanFilterParameters driveKalmanFilterParameters = new KalmanFilterParameters( 6, - 1); + 3); // Mass of robot in kilograms diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java index e97f78a..5f25325 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java @@ -93,11 +93,13 @@ public class ForwardVelocityTuner extends OpMode { } telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); - telemetryA.addLine("The robot will run at 1 power until it reaches " + DISTANCE + " inches forward."); - telemetryA.addLine("Make sure you have enough room, since the robot has inertia after cutting power."); - telemetryA.addLine("After running the distance, the robot will cut power from the drivetrain and display the forward velocity."); - telemetryA.addLine("Press CROSS or A on game pad 1 to stop."); - telemetryA.update(); +// telemetryA.addLine("The robot will run at 1 power until it reaches " + DISTANCE + " inches forward."); +// telemetryA.addLine("Make sure you have enough room, since the robot has inertia after cutting power."); +// telemetryA.addLine("After running the distance, the robot will cut power from the drivetrain and display the forward velocity."); +// telemetryA.addLine("Press CROSS or A on game pad 1 to stop."); +// +// +// telemetryA.update(); } @@ -138,6 +140,13 @@ public class ForwardVelocityTuner extends OpMode { velocities.add(currentVelocity); velocities.remove(0); } + telemetryA.addData("x", poseUpdater.getPose().getX()); + telemetryA.addData("y", poseUpdater.getPose().getY()); + telemetryA.addData("heading", poseUpdater.getPose().getHeading()); + telemetryA.addData("velo mag", poseUpdater.getVelocity().getMagnitude()); + telemetryA.addData("velo ", poseUpdater.getVelocity().getTheta()); + telemetryA.update(); + } else { double average = 0; for (Double velocity : velocities) { @@ -146,7 +155,12 @@ public class ForwardVelocityTuner extends OpMode { average /= (double) velocities.size(); telemetryA.addData("forward velocity:", average); - telemetryA.update(); +// telemetryA.addData("x", poseUpdater.getPose().getX()); +// telemetryA.addData("y", poseUpdater.getPose().getY()); +// telemetryA.addData("heading", poseUpdater.getPose().getHeading()); +// telemetryA.addData("velo mag", poseUpdater.getVelocity().getMagnitude()); +// telemetryA.addData("velo ", poseUpdater.getVelocity().getTheta()); +// telemetryA.update(); } } }