27 Commits

Author SHA1 Message Date
c9ffd4f061 Added driver hub config naming 2024-12-17 21:35:16 -08:00
021dfa7222 Added lift configurations 2024-12-17 21:34:49 -08:00
233b177cf6 Removing more files to keep things light for this branch 2024-12-17 21:32:10 -08:00
0ab402af0f Lightening the load and configured the robot with appropriate values (encoders/motors) 2024-12-17 19:07:34 -08:00
aa496b8237 Ollie's work committed 2024-12-08 12:48:30 -08:00
66f3339e26 Working Pre loaded auto! Can score 11 points consistently! 2024-11-14 17:10:46 -08:00
ad0a8d3374 Merge remote-tracking branch 'origin/branch-silver-14493' into branch-silver-14493 2024-11-14 16:23:46 -08:00
dc71eb4317 Feature where driver can override centricity (robot vs field). 2024-11-13 15:09:59 -08:00
94144780b8 Tentative fix for robot/runBlocking problem as per issue #2 2024-11-13 09:13:24 -08:00
a362d2e004 Massive upgrade and shift of files 2024-11-12 23:16:23 -08:00
2008c3cd88 Working somehitng i don't know 2024-11-12 16:55:35 -08:00
c5be3cd932 Silver Branch Code 2024-11-03 09:13:37 -08:00
7d83b9c254 Add sample cometbot package 2024-10-31 15:37:09 -07:00
5f50d053c5 Merge remote-tracking branch 'origin/branch-silver-14493' into branch-silver-14493
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java
2024-10-21 21:57:45 -07:00
0cfb57c643 Merge remote-tracking branch 'origin/branch-silver-14493' into branch-silver-14493 2024-10-17 11:07:25 -07:00
50db1f9175 Add new files (2nd try) 2024-10-17 11:07:10 -07:00
552bb3e25a Add new files 2024-10-17 11:06:13 -07:00
c1076a832c Rebased changes 2024-10-17 11:05:12 -07:00
7bf8b0c357 Add files 2024-10-17 11:04:02 -07:00
adfab3e8af Add sample code 2024-10-15 15:44:49 -07:00
0f7ea50907 Updated constants for silver and it, somehow, works 2024-10-15 15:43:53 -07:00
239f168540 Retuned to success, PIDF (P = .05) and translationalPIDFeedForward is back to 0 2024-10-15 13:59:02 -07:00
f2bcdcc55a Add constants 2024-10-01 17:05:54 -07:00
e08aac773d Static entries for arm servos 2024-10-01 15:45:02 -07:00
3950a83ac1 Added encoder naming and usage 2024-10-01 10:19:40 -07:00
552ff3f339 Updated to 10.1 2024-09-30 22:37:16 -07:00
4eef485dab Re-wired and reconfigured 2024-09-30 20:39:24 -07:00
18 changed files with 927 additions and 151 deletions

View File

@ -0,0 +1,24 @@
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.cometbots.CometBotAutoDevelopment;
@TeleOp(name = "CometBot Auto", group = "Development")
public class CometBotDevAuto extends OpMode {
public CometBotAutoDevelopment runMode;
@Override
public void init() {
this.runMode = new CometBotAutoDevelopment(hardwareMap, telemetry, gamepad1, gamepad2);
this.runMode.init();
}
@Override
public void loop() {
this.runMode.update();
telemetry.update();
}
}

View File

@ -1,92 +0,0 @@
/*
Copyright (c) 2024 Alan Smith
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 Alan Smith 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 FITNESSFOR 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;
/*
* This OpMode illustrates how to use the goBILDA Indicator Light
*
* To make this work, this Light uses a Servo motor and setPositions.
* Valid values are from .277 to .722.
*
* If it's less than .277 then no light
* If it's greater than .722 then white light
*
* Spec Sheet is here: https://cdn11.bigcommerce.com/s-x56mtydx1w/images/stencil/original/products/2275/13464/3118-0808-0002-Product-Insight-4__03940__01348.1728056113.png?c=1
*/
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.Servo;
@TeleOp(name = "Demo: goBILDA Indicator Light", group = "Concept")
public class DemoGoBildaIndicatorLight extends LinearOpMode {
Servo front_led;
private final double buffer = .277;
@Override
public void runOpMode() {
front_led = hardwareMap.get(Servo.class, "test_servo");
waitForStart();
while (opModeIsActive()) {
double left_x = Math.abs(gamepad1.left_stick_x) / 4;
double left_y = Math.abs(gamepad1.left_stick_y) / 4;
double right_x = Math.abs(gamepad1.right_stick_x) / 4;
double right_y = Math.abs(gamepad1.right_stick_y) / 4;
double total_position = Math.min(left_x + left_y + right_x + right_y + buffer, 1.0);
telemetry.addData("left_x", left_x);
telemetry.addData("left_y", left_y);
telemetry.addData("right_x", right_x);
telemetry.addData("right_y", right_y);
telemetry.addData("total (plus buffer)", total_position);
telemetry.update();
front_led.setPosition(total_position);
if (gamepad1.cross) {
front_led.setPosition(.611);
sleep(2000);
}
if (gamepad1.triangle) {
front_led.setPosition(.444);
sleep(2000);
}
if (gamepad1.square) {
front_led.setPosition(.7);
sleep(2000);
}
if (gamepad1.circle) {
front_led.setPosition(.3);
sleep(2000);
}
}
}
}

View File

@ -12,10 +12,10 @@ public class PedroConstants {
*/ */
// Robot motor configurations // Robot motor configurations
public static final String FRONT_LEFT_MOTOR = "Drive front lt"; public static final String FRONT_LEFT_MOTOR = "front-left";
public static final String BACK_LEFT_MOTOR = "Drive back lt"; public static final String BACK_LEFT_MOTOR = "back-left";
public static final String FRONT_RIGHT_MOTOR = "Drive front rt"; public static final String FRONT_RIGHT_MOTOR = "front-right";
public static final String BACK_RIGHT_MOTOR = "Drive back rt"; public static final String BACK_RIGHT_MOTOR = "back-right";
// Robot motor direction // Robot motor direction
public static final Direction FRONT_LEFT_MOTOR_DIRECTION = Direction.REVERSE; public static final Direction FRONT_LEFT_MOTOR_DIRECTION = Direction.REVERSE;
@ -23,48 +23,61 @@ public class PedroConstants {
public static final Direction FRONT_RIGHT_MOTOR_DIRECTION = Direction.FORWARD; public static final Direction FRONT_RIGHT_MOTOR_DIRECTION = Direction.FORWARD;
public static final Direction BACK_RIGHT_MOTOR_DIRECTION = Direction.FORWARD; public static final Direction BACK_RIGHT_MOTOR_DIRECTION = Direction.FORWARD;
/*
Motor Max Power
*/
public static final double MAX_POWER = .75;
// Robot IMU configuration // Robot IMU configuration
public static final String IMU = "imu"; public static final String IMU = "imu";
// Robot IMU placement // Robot IMU placement
public static final RevHubOrientationOnRobot.LogoFacingDirection IMU_LOGO_FACING_DIRECTION public static final RevHubOrientationOnRobot.LogoFacingDirection IMU_LOGO_FACING_DIRECTION
= RevHubOrientationOnRobot.LogoFacingDirection.DOWN; = RevHubOrientationOnRobot.LogoFacingDirection.LEFT;
public static final RevHubOrientationOnRobot.UsbFacingDirection IMU_USB_FACING_DIRECTION public static final RevHubOrientationOnRobot.UsbFacingDirection IMU_USB_FACING_DIRECTION
= RevHubOrientationOnRobot.UsbFacingDirection.LEFT; = RevHubOrientationOnRobot.UsbFacingDirection.UP;
// Robot encoders // Robot encoders
public static final String LEFT_ENCODER = "encoder left"; // NOTE: Encoders are plugged into the same ports as motors hence the weird names
public static final String RIGHT_ENCODER = "encoder right"; public static final String RIGHT_ENCODER = "front-left"; //2
public static final String BACK_ENCODER = "encoder back"; public static final String BACK_ENCODER = "front-right"; //1
public static final String LEFT_ENCODER = "back-right"; //0
// Robot encoder direction // Robot encoder direction
public static final double LEFT_ENCODER_DIRECTION = Encoder.FORWARD; public static final double LEFT_ENCODER_DIRECTION = Encoder.FORWARD;
public static final double RIGHT_ENCODER_DIRECTION = Encoder.FORWARD; public static final double RIGHT_ENCODER_DIRECTION = Encoder.REVERSE;
public static final double BACK_ENCODER_DIRECTION = Encoder.REVERSE; public static final double BACK_ENCODER_DIRECTION = Encoder.FORWARD;
// Arm config
public static final String LIFT_SLIDE_LEFT_MOTOR = "lift-slide-left";
public static final String LIFT_SLIDE_RIGHT_MOTOR = "lift-slide-right";
public static final String Claw_Servo = "ClawServo";
public static final String Wrist_Servo = "WristServo";
public static final String Arm_Servo = "ArmServo";
/* /*
Pedro's parameters Pedro's parameters
*/ */
// The weight of the robot in Kilograms // 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 // Maximum velocity of the robot going forward
public static final double ROBOT_SPEED_FORWARD = 72.0693; public static final double ROBOT_SPEED_FORWARD = 51.5;
// Maximum velocity of the robot going right // Maximum velocity of the robot going right
public static final double ROBOT_SPEED_LATERAL = 24.1401; public static final double ROBOT_SPEED_LATERAL = 28.7;
// Rate of deceleration when power is cut-off when the robot is moving forward // Rate of deceleration when power is cut-off when the robot is moving forward
public static final double FORWARD_ZERO_POWER_ACCEL = -74.3779; 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 // Rate of deceleration when power is cut-off when the robot is moving to the right
public static final double LATERAL_ZERO_POWER_ACCEL = -111.8409; 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 // 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 = 4; public static final double ZERO_POWER_ACCEL_MULT = 3.5;
/* Centripetal force correction - increase if robot is correcting into the path /* Centripetal force correction - increase if robot is correcting into the path
- decrease if robot is correcting away from 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;
} }

View File

@ -0,0 +1,122 @@
package org.firstinspires.ftc.teamcode;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
@Autonomous(name = "Pre Loaded Blue Basket Auto", group = "Competition")
public class PreLoadedBlueBasketAuto extends OpMode {
private Telemetry telemetryA;
private Follower follower;
private PathChain path;
private final Pose startPose = new Pose(7.875, 89.357);
@Override
public void init() {
follower = new Follower(hardwareMap);
follower.setMaxPower(.45);
follower.setStartingPose(startPose);
path = follower.pathBuilder()
.addPath(
// Line 1
new BezierLine(
new Point(8.036, 89.196, Point.CARTESIAN),
new Point(10.125, 126.804, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 2
new BezierCurve(
new Point(10.125, 126.804, Point.CARTESIAN),
new Point(37.607, 90.000, Point.CARTESIAN),
new Point(62.357, 119.893, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 3
new BezierCurve(
new Point(62.357, 119.893, Point.CARTESIAN),
new Point(33.750, 112.500, Point.CARTESIAN),
new Point(15.107, 130.661, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 4
new BezierCurve(
new Point(15.107, 130.661, Point.CARTESIAN),
new Point(58.821, 103.018, Point.CARTESIAN),
new Point(59.625, 126.964, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 5
new BezierLine(
new Point(59.625, 126.964, Point.CARTESIAN),
new Point(15.107, 130.339, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 6
new BezierLine(
new Point(15.107, 130.339, Point.CARTESIAN),
new Point(59.625, 126.964, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 7
new BezierLine(
new Point(59.625, 126.964, Point.CARTESIAN),
new Point(57.857, 133.071, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 8
new BezierLine(
new Point(57.857, 133.071, Point.CARTESIAN),
new Point(18.964, 134.679, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 9
new BezierCurve(
new Point(18.964, 134.679, Point.CARTESIAN),
new Point(84.536, 131.786, Point.CARTESIAN),
new Point(80.036, 96.429, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(270)).build();
follower.followPath(path);
telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry());
telemetryA.update();
}
@Override
public void loop() {
follower.update();
follower.telemetryDebug(telemetryA);
}
}

View File

@ -0,0 +1,151 @@
package org.firstinspires.ftc.teamcode.cometbots;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
/**
* This is the Circle autonomous OpMode. It runs the robot in a PathChain that's actually not quite
* a circle, but some Bezier curves that have control points set essentially in a square. However,
* it turns enough to tune your centripetal force correction and some of your heading. Some lag in
* heading is to be expected.
*
* @author Anyi Lin - 10158 Scott's Bots
* @author Aaron Yang - 10158 Scott's Bots
* @author Harrison Womack - 10158 Scott's Bots
* @version 1.0, 3/12/2024
*/
@Config
@Autonomous(name = "BlueNonBasketAuto", group = "Autonomous Pathing Tuning")
public class BlueNonBasketAuto extends OpMode {
private Telemetry telemetryA;
private Follower follower;
private PathChain path;
private final Pose startPose = new Pose(10.929, 55.446, 0);
/**
* This initializes the Follower and creates the PathChain for the "circle". Additionally, this
* initializes the FTC Dashboard telemetry.
*/
@Override
public void init() {
follower = new Follower(hardwareMap);
follower.setMaxPower(.45);
follower.setStartingPose(startPose);
path = follower.pathBuilder()
.addPath(
// Line 1
new BezierCurve(
new Point(10.929, 55.446, Point.CARTESIAN),
new Point(42.429, 46.446, Point.CARTESIAN),
new Point(36.321, 38.089, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 2
new BezierLine(
new Point(36.321, 38.089, Point.CARTESIAN),
new Point(59.786, 36.643, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 3
new BezierLine(
new Point(59.786, 36.643, Point.CARTESIAN),
new Point(59.304, 24.750, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 4
new BezierLine(
new Point(59.304, 24.750, Point.CARTESIAN),
new Point(13.982, 23.946, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 5
new BezierLine(
new Point(13.982, 23.946, Point.CARTESIAN),
new Point(59.464, 24.429, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 6
new BezierLine(
new Point(59.464, 24.429, Point.CARTESIAN),
new Point(58.982, 15.268, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 7
new BezierLine(
new Point(58.982, 15.268, Point.CARTESIAN),
new Point(13.821, 14.464, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 8
new BezierLine(
new Point(13.821, 14.464, Point.CARTESIAN),
new Point(58.661, 13.500, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 9
new BezierLine(
new Point(58.661, 13.500, Point.CARTESIAN),
new Point(58.339, 8.679, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(
// Line 10
new BezierLine(
new Point(58.339, 8.679, Point.CARTESIAN),
new Point(14.625, 8.518, Point.CARTESIAN)
)
)
.setConstantHeadingInterpolation(Math.toRadians(0)).build();
follower.followPath(path, true);
telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry());
telemetryA.update();
}
/**
* This runs the OpMode, updating the Follower as well as printing out the debug statements to
* the Telemetry, as well as the FTC Dashboard.
*/
@Override
public void loop() {
follower.update();
if (follower.atParametricEnd()) {
follower.followPath(path, true);
}
follower.telemetryDebug(telemetryA);
}
}

View File

@ -0,0 +1,142 @@
package org.firstinspires.ftc.teamcode.cometbots;
import static org.firstinspires.ftc.teamcode.PedroConstants.MAX_POWER;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.SequentialAction;
import com.acmerobotics.roadrunner.SleepAction;
import com.acmerobotics.roadrunner.ftc.Actions;
import com.qualcomm.robotcore.hardware.Gamepad;
import com.qualcomm.robotcore.hardware.HardwareMap;
import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
import org.firstinspires.ftc.teamcode.states.FieldStates;
import org.firstinspires.ftc.teamcode.subsystem.MotorsSubsystem;
public class CometBotAutoDevelopment {
/*
Subsystems
*/
private MotorsSubsystem motors;
/*
Controllers
*/
public Gamepad GP1;
public Gamepad GP2;
public Gamepad currentGP1;
public Gamepad previousGP1;
public Gamepad currentGP2;
public Gamepad previousGP2;
private Telemetry telemetry;
public FieldStates fieldStates;
private boolean centricity = false;
private Follower follower;
private HardwareMap hardwareMap;
public CometBotAutoDevelopment(HardwareMap hardwareMap, Telemetry telemetry, Gamepad gp1, Gamepad gp2) {
this.motors = new MotorsSubsystem(hardwareMap, telemetry);
this.GP1 = gp1;
this.GP2 = gp2;
this.hardwareMap = hardwareMap;
this.telemetry = telemetry;
this.currentGP1 = new Gamepad();
this.currentGP2 = new Gamepad();
this.previousGP1 = new Gamepad();
this.previousGP2 = new Gamepad();
this.fieldStates = new FieldStates();
this.follower = new Follower(hardwareMap);
}
public class ZeroOutPower implements Action {
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
follower = new Follower(hardwareMap);
follower.setMaxPower(0);
System.out.println("Running ZeroOutPower");
return follower.isBusy();
}
}
public class ReturnToMaxPower implements Action {
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
follower = new Follower(hardwareMap);
follower.setMaxPower(MAX_POWER);
follower.startTeleopDrive();
System.out.println("Running ReturnToMaxPower");
return follower.isBusy();
}
}
public Action zeroOutPower() {
return new ZeroOutPower();
}
public Action returnToMaxPower() {
return new ReturnToMaxPower();
}
public void init() {
this.motors.init();
this.fieldStates.setFieldLocation(FieldStates.FieldLocation.TRAVELING);
follower.setMaxPower(MAX_POWER);
follower.startTeleopDrive();
}
public void update() {
this.previousGP1.copy(currentGP1);
this.currentGP1.copy(this.GP1);
this.previousGP2.copy(currentGP2);
this.currentGP2.copy(this.GP2);
this.toFixMotorBlockingIssueFirstMethod();
this.toFixMotorBlockingIssueSecondMethod();
this.changeCentricity();
follower.setTeleOpMovementVectors(-this.GP1.left_stick_y, -this.GP1.left_stick_x, -this.GP1.right_stick_x, centricity);
follower.update();
this.telemetry.addData("Field State", this.fieldStates.getFieldLocation());
}
public void changeCentricity() {
if (this.currentGP1.left_bumper && !this.previousGP1.left_bumper) {
this.centricity = !centricity;
this.follower.breakFollowing();
this.follower.startTeleopDrive();
}
}
public void toFixMotorBlockingIssueFirstMethod() {
if (this.currentGP1.cross && !this.previousGP1.cross) {
fieldStates.setFieldLocation(FieldStates.FieldLocation.BUCKET);
Actions.runBlocking(new SequentialAction(
this.zeroOutPower(),
new SleepAction(3),
this.returnToMaxPower()
));
fieldStates.setFieldLocation(FieldStates.FieldLocation.TRAVELING);
}
}
public void toFixMotorBlockingIssueSecondMethod() {
if (this.currentGP1.circle && !this.previousGP1.circle) {
this.follower.breakFollowing();
fieldStates.setFieldLocation(FieldStates.FieldLocation.BUCKET);
Actions.runBlocking(new SequentialAction(
new SleepAction(3)
));
fieldStates.setFieldLocation(FieldStates.FieldLocation.TRAVELING);
this.follower.startTeleopDrive();
}
}
}

View File

@ -0,0 +1,197 @@
/* 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.cometbots.projects;
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.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.
* 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 final ElapsedTime runtime = new ElapsedTime();
@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.
DcMotor leftFrontDrive = hardwareMap.get(DcMotor.class, FRONT_LEFT_MOTOR);
DcMotor leftBackDrive = hardwareMap.get(DcMotor.class, BACK_LEFT_MOTOR);
DcMotor rightFrontDrive = hardwareMap.get(DcMotor.class, FRONT_RIGHT_MOTOR);
DcMotor rightBackDrive = hardwareMap.get(DcMotor.class, BACK_RIGHT_MOTOR);
// TODO: replace these with your encoder ports
Encoder leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, LEFT_ENCODER));
Encoder rightEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, RIGHT_ENCODER));
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. !!!!!
// ########################################################################################
// 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);
// 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();
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);
// 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("Left Encoder Value", leftEncoder.getDeltaPosition());
telemetry.addData("Right Encoder Value", rightEncoder.getDeltaPosition());
telemetry.addData("Strafe Encoder Value", strafeEncoder.getDeltaPosition());
telemetry.update();
}
}}

View File

@ -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 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 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 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 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 thousandths and millionths place values. To tune this, enable `useDrive`, `useHeading`, and
`useTranslational` in the `Follower` dropdown in FTC Dashboard. Next, run `StraightBackAndForth` `useTranslational` in the `Follower` dropdown in FTC Dashboard. Next, run `StraightBackAndForth`

View File

@ -69,7 +69,7 @@ public class PoseUpdater {
*/ */
public PoseUpdater(HardwareMap hardwareMap) { public PoseUpdater(HardwareMap hardwareMap) {
// TODO: replace the second argument with your preferred localizer // TODO: replace the second argument with your preferred localizer
this(hardwareMap, new ThreeWheelIMULocalizer(hardwareMap)); this(hardwareMap, new ThreeWheelLocalizer(hardwareMap));
} }
/** /**

View File

@ -65,9 +65,9 @@ public class ThreeWheelIMULocalizer extends Localizer {
private double previousIMUOrientation; private double previousIMUOrientation;
private double deltaRadians; private double deltaRadians;
private double totalHeading; private double totalHeading;
public static double FORWARD_TICKS_TO_INCHES = 0.004;//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.0036;//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.0043;//8192 * 1.37795 * 2 * Math.PI * 0.5; public static double TURN_TICKS_TO_RADIANS = 0.0022;//8192 * 1.37795 * 2 * Math.PI * 0.5;
public static boolean useIMU = true; 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))); imu.initialize(new IMU.Parameters(new RevHubOrientationOnRobot(IMU_LOGO_FACING_DIRECTION, IMU_USB_FACING_DIRECTION)));
// TODO: replace these with your encoder positions // TODO: replace these with your encoder positions
leftEncoderPose = new Pose(-7.625, 6.19375, 0); leftEncoderPose = new Pose(0, 6.19375, 0);
rightEncoderPose = new Pose(-7.625, -6.19375, 0); rightEncoderPose = new Pose(0, -6.19375, 0);
strafeEncoderPose = new Pose(7, 1, Math.toRadians(90)); strafeEncoderPose = new Pose(-7, 0, Math.toRadians(90));
// TODO: replace these with your encoder ports // TODO: replace these with your encoder ports
leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, LEFT_ENCODER)); leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, LEFT_ENCODER));

View File

@ -57,9 +57,9 @@ public class ThreeWheelLocalizer extends Localizer {
private Pose rightEncoderPose; private Pose rightEncoderPose;
private Pose strafeEncoderPose; private Pose strafeEncoderPose;
private double totalHeading; private double totalHeading;
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) * 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) { public ThreeWheelLocalizer(HardwareMap map, Pose setStartPose) {
// TODO: replace these with your encoder positions // TODO: replace these with your encoder positions
leftEncoderPose = new Pose(-18.5/25.4 - 0.1, 164.4/25.4, 0); leftEncoderPose = new Pose(0, 6.25, 0);
rightEncoderPose = new Pose(-18.4/25.4 - 0.1, -159.6/25.4, 0); rightEncoderPose = new Pose(0, -6.25, 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)); strafeEncoderPose = new Pose(-7, 0, Math.toRadians(90));
hardwareMap = map; hardwareMap = map;
@ -92,9 +92,9 @@ public class ThreeWheelLocalizer extends Localizer {
strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, BACK_ENCODER)); strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, BACK_ENCODER));
// TODO: reverse any encoders necessary // TODO: reverse any encoders necessary
//leftEncoder.setDirection(Encoder.REVERSE); leftEncoder.setDirection(LEFT_ENCODER_DIRECTION);
// rightEncoder.setDirection(Encoder.REVERSE); rightEncoder.setDirection(RIGHT_ENCODER_DIRECTION);
//strafeEncoder.setDirection(Encoder.FORWARD); strafeEncoder.setDirection(BACK_ENCODER_DIRECTION);
setStartPose(setStartPose); setStartPose(setStartPose);
timer = new NanoTimer(); timer = new NanoTimer();

View File

@ -1,5 +1,9 @@
package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning; package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning;
import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_LEFT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_RIGHT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_LEFT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_RIGHT_MOTOR_DIRECTION;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
@ -58,8 +62,10 @@ public class LocalizationTest extends OpMode {
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
leftFront.setDirection(DcMotorSimple.Direction.REVERSE); leftFront.setDirection(FRONT_LEFT_MOTOR_DIRECTION);
leftRear.setDirection(DcMotorSimple.Direction.REVERSE); leftRear.setDirection(BACK_LEFT_MOTOR_DIRECTION);
rightFront.setDirection(FRONT_RIGHT_MOTOR_DIRECTION);
rightRear.setDirection(BACK_RIGHT_MOTOR_DIRECTION);
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);

View File

@ -42,7 +42,7 @@ public class FollowerConstants {
public static CustomPIDFCoefficients translationalPIDFCoefficients = new CustomPIDFCoefficients( public static CustomPIDFCoefficients translationalPIDFCoefficients = new CustomPIDFCoefficients(
0.1, 0.1,
0, 0,
0, 0.01,
0); 0);
// Translational Integral // Translational Integral
@ -53,14 +53,14 @@ public class FollowerConstants {
0); 0);
// Feed forward constant added on to the translational PIDF // Feed forward constant added on to the translational PIDF
public static double translationalPIDFFeedForward = 0.015; public static double translationalPIDFFeedForward = 0.00;
// Heading error PIDF coefficients // Heading error PIDF coefficients
public static CustomPIDFCoefficients headingPIDFCoefficients = new CustomPIDFCoefficients( public static CustomPIDFCoefficients headingPIDFCoefficients = new CustomPIDFCoefficients(
1, 2,
0,
0, 0,
0.025,
0); 0);
// Feed forward constant added on to the heading PIDF // Feed forward constant added on to the heading PIDF
@ -69,10 +69,10 @@ public class FollowerConstants {
// Drive PIDF coefficients // Drive PIDF coefficients
public static CustomFilteredPIDFCoefficients drivePIDFCoefficients = new CustomFilteredPIDFCoefficients( public static CustomFilteredPIDFCoefficients drivePIDFCoefficients = new CustomFilteredPIDFCoefficients(
0.025, 0.006,
0, 0,
0.00001, 0.00001,
0.6, 0.8,
0); 0);
// Feed forward constant added on to the drive PIDF // 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 // Kalman filter parameters for the drive error Kalman filter
public static KalmanFilterParameters driveKalmanFilterParameters = new KalmanFilterParameters( public static KalmanFilterParameters driveKalmanFilterParameters = new KalmanFilterParameters(
6, 6,
1); 3);
// Mass of robot in kilograms // Mass of robot in kilograms

View File

@ -93,11 +93,13 @@ public class ForwardVelocityTuner extends OpMode {
} }
telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); 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("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("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("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.addLine("Press CROSS or A on game pad 1 to stop.");
telemetryA.update(); //
//
// telemetryA.update();
} }
@ -138,6 +140,13 @@ public class ForwardVelocityTuner extends OpMode {
velocities.add(currentVelocity); velocities.add(currentVelocity);
velocities.remove(0); 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 { } else {
double average = 0; double average = 0;
for (Double velocity : velocities) { for (Double velocity : velocities) {
@ -146,7 +155,12 @@ public class ForwardVelocityTuner extends OpMode {
average /= (double) velocities.size(); average /= (double) velocities.size();
telemetryA.addData("forward velocity:", average); 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();
} }
} }
} }

View File

@ -0,0 +1,18 @@
package org.firstinspires.ftc.teamcode.states;
public class FieldStates {
public enum FieldLocation {
BUCKET, SUBMARINE, FLOATING, TRAVELING
}
private FieldLocation fieldLocation;
public FieldLocation getFieldLocation() {
return fieldLocation;
}
public void setFieldLocation(FieldLocation fieldLocation) {
this.fieldLocation = fieldLocation;
}
}

View File

@ -0,0 +1,72 @@
package org.firstinspires.ftc.teamcode.subsystem;
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_LEFT_MOTOR;
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_RIGHT_MOTOR;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.util.ElapsedTime;
@Config
@Autonomous(name = "Lift Motor Subsystem - PID Test")
public class LiftMotorSubsystem extends LinearOpMode {
private DcMotorEx liftSlideLeft;
private DcMotorEx liftSlideRight;
public static double kp = 0.0015, ki = 0, kd = 0;
private double lastError = 0;
private double integralSum = 0;
public static int targetPosition = 0;
private final FtcDashboard dashboard = FtcDashboard.getInstance();
private ElapsedTime timer = new ElapsedTime();
@Override
public void runOpMode() throws InterruptedException {
TelemetryPacket packet = new TelemetryPacket();
dashboard.setTelemetryTransmissionInterval(25);
liftSlideLeft = hardwareMap.get(DcMotorEx.class, LIFT_SLIDE_LEFT_MOTOR);
liftSlideRight = hardwareMap.get(DcMotorEx.class, LIFT_SLIDE_RIGHT_MOTOR);
liftSlideLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
liftSlideLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
liftSlideLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
liftSlideRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
liftSlideRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
liftSlideRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
waitForStart();
while(opModeIsActive()) {
double power = calculatePower(targetPosition, liftSlideLeft.getCurrentPosition());
packet.put("Power", power);
packet.put("Position", liftSlideLeft.getCurrentPosition());
packet.put("Error", lastError);
packet.put("Seconds", timer.seconds());
liftSlideLeft.setPower(power);
liftSlideRight.setPower(power);
dashboard.sendTelemetryPacket(packet);
}
}
private double calculatePower(int targetPosition, int currentPosition) {
// reference is targetPosition, state is currentPosition
double error = targetPosition - currentPosition;
integralSum += error * timer.seconds();
double derivative = (error - lastError) / timer.seconds();
lastError = error;
timer.reset();
return (error * kp) + (derivative * kd) + (integralSum * ki);
}
}

View File

@ -0,0 +1,105 @@
package org.firstinspires.ftc.teamcode.subsystem;
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.MAX_POWER;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Gamepad;
import com.qualcomm.robotcore.hardware.HardwareMap;
import org.firstinspires.ftc.robotcore.external.Telemetry;
public class MotorsSubsystem {
public HardwareMap hardwareMap;
public Telemetry telemetry;
public DcMotor frontLeftMotor;
public DcMotor backLeftMotor;
public DcMotor frontRightMotor;
public DcMotor backRightMotor;
public enum TravelState {
STOPPED, MOVING
}
public TravelState travelState;
public double power;
public MotorsSubsystem(HardwareMap hardwareMap, Telemetry telemetry) {
this.hardwareMap = hardwareMap;
this.telemetry = telemetry;
this.power = MAX_POWER;
}
public MotorsSubsystem(HardwareMap hardwareMap, Telemetry telemetry, double power) {
this.hardwareMap = hardwareMap;
this.telemetry = telemetry;
this.power = power;
}
public void init() {
frontLeftMotor = hardwareMap.get(DcMotor.class, FRONT_LEFT_MOTOR);
backLeftMotor = hardwareMap.get(DcMotor.class, BACK_LEFT_MOTOR);
frontRightMotor = hardwareMap.get(DcMotor.class, FRONT_RIGHT_MOTOR);
backRightMotor = hardwareMap.get(DcMotor.class, BACK_RIGHT_MOTOR);
frontLeftMotor.setDirection(FRONT_LEFT_MOTOR_DIRECTION);
backLeftMotor.setDirection(BACK_LEFT_MOTOR_DIRECTION);
frontRightMotor.setDirection(FRONT_RIGHT_MOTOR_DIRECTION);
backRightMotor.setDirection(BACK_RIGHT_MOTOR_DIRECTION);
frontLeftMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backLeftMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
frontRightMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backRightMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
this.setState(TravelState.STOPPED);
}
public void setFrontLeftMotorPower(double power) {
frontLeftMotor.setPower(power);
}
public void setBackLeftMotorPower(double power) {
backLeftMotor.setPower(power);
}
public void setFrontRightMotorPower(double power) {
frontRightMotor.setPower(power);
}
public void setBackRightMotorPower(double power) {
backRightMotor.setPower(power);
}
public void setState(TravelState travelState) {
this.travelState = travelState;
}
public TravelState getState() {
return this.travelState;
}
public void setPower(DcMotor motor, double power) {
motor.setPower(power);
if (power < 0.05) {
this.setState(TravelState.MOVING);
} else {
this.setState(TravelState.STOPPED);
}
}
}

View File

@ -6,16 +6,19 @@ repositories {
} }
dependencies { dependencies {
implementation 'org.firstinspires.ftc:Inspection:10.0.0' implementation 'org.firstinspires.ftc:Inspection:10.1.0'
implementation 'org.firstinspires.ftc:Blocks:10.0.0' implementation 'org.firstinspires.ftc:Blocks:10.1.0'
implementation 'org.firstinspires.ftc:RobotCore:10.0.0' implementation 'org.firstinspires.ftc:RobotCore:10.1.0'
implementation 'org.firstinspires.ftc:RobotServer:10.0.0' implementation 'org.firstinspires.ftc:RobotServer:10.1.0'
implementation 'org.firstinspires.ftc:OnBotJava:10.0.0' implementation 'org.firstinspires.ftc:OnBotJava:10.1.0'
implementation 'org.firstinspires.ftc:Hardware:10.0.0' implementation 'org.firstinspires.ftc:Hardware:10.1.0'
implementation 'org.firstinspires.ftc:FtcCommon:10.0.0' implementation 'org.firstinspires.ftc:FtcCommon:10.1.0'
implementation 'org.firstinspires.ftc:Vision:10.0.0' implementation 'org.firstinspires.ftc:Vision:10.1.0'
implementation 'androidx.appcompat:appcompat:1.2.0' implementation 'androidx.appcompat:appcompat:1.2.0'
implementation 'com.acmerobotics.dashboard:dashboard:0.4.5' implementation "com.acmerobotics.roadrunner:ftc:0.1.14"
implementation "com.acmerobotics.roadrunner:core:1.0.0"
implementation "com.acmerobotics.roadrunner:actions:1.0.0"
implementation "com.acmerobotics.dashboard:dashboard:0.4.16"
} }