Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Road runner calib #39

Merged
merged 24 commits into from
Jun 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
package com.example.meepmeeptesting;

import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.geometry.Vector2d;
import com.acmerobotics.roadrunner.trajectory.constraints.MecanumVelocityConstraint;
import com.acmerobotics.roadrunner.trajectory.constraints.ProfileAccelerationConstraint;
import com.noahbres.meepmeep.MeepMeep;
import com.noahbres.meepmeep.roadrunner.DefaultBotBuilder;
import com.noahbres.meepmeep.roadrunner.entity.RoadRunnerBotEntity;
Expand All @@ -14,15 +17,15 @@ public static void main(String[] args) {
.setConstraints(60, 60, Math.toRadians(180), Math.toRadians(180), 15)
.followTrajectorySequence(drive ->
// add your trajectory here:
drive.trajectorySequenceBuilder(new Pose2d(0, 0, 0))
.forward(30)
.turn(Math.toRadians(90))
.forward(30)
.turn(Math.toRadians(90))
.forward(30)
.turn(Math.toRadians(90))
.forward(30)
.turn(Math.toRadians(90))
drive.trajectorySequenceBuilder(new Pose2d(10, -60, -Math.PI/2))
.lineToLinearHeading(new Pose2d(15, -40, Math.toRadians(225)))
.addTemporalMarker(() -> {})
.waitSeconds(0.5)
.lineTo(new Vector2d(25, -55))
.lineToLinearHeading(new Pose2d(40, -35, 0))
.lineToLinearHeading(new Pose2d(50, -40))
.addTemporalMarker(() -> {})
.waitSeconds(0.5)
.build()
);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,9 @@ public void runOpMode() throws InterruptedException {
}

public abstract Alliance getAlliance();

public abstract FieldStartingLocation getFieldStartingLocation();

public abstract void run() throws InterruptedException;

}
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ public class DriveConstants {
/*
* These are motor constants that should be listed online for your motors.
*/
public static final double TICKS_PER_REV = 1;
public static final double MAX_RPM = 1;
public static final double TICKS_PER_REVOLUTION = 537.7;
public static final double MAX_RPM = 312;

/*
* Set RUN_USING_ENCODER to true to enable built-in hub velocity control using drive encoders.
Expand All @@ -31,9 +31,9 @@ public class DriveConstants {
* If using the built-in motor velocity PID, update MOTOR_VELO_PID with the tuned coefficients
* from DriveVelocityPIDTuner.
*/
public static final boolean RUN_USING_ENCODER = true;
public static PIDFCoefficients MOTOR_VELO_PID = new PIDFCoefficients(0, 0, 0,
getMotorVelocityF(MAX_RPM / 60 * TICKS_PER_REV));
public static final boolean RUN_USING_ENCODER = false;
public static PIDFCoefficients MOTOR_VELOCITY_PID = new PIDFCoefficients(1, 0, 0,
getMotorVelocityF(MAX_RPM / 60 * TICKS_PER_REVOLUTION));

/*
* These are physical constants that can be determined from your robot (including the track
Expand All @@ -43,19 +43,19 @@ public class DriveConstants {
* angular distances although most angular parameters are wrapped in Math.toRadians() for
* convenience. Make sure to exclude any gear ratio included in MOTOR_CONFIG from GEAR_RATIO.
*/
public static double WHEEL_RADIUS = 2; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 1; // in
public static double WHEEL_RADIUS = 1.8; // in
public static double GEAR_RATIO = 1.05; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 325; // in

/*
* These are the feedforward parameters used to model the drive motor behavior. If you are using
* the built-in velocity PID, *these values are fine as is*. However, if you do not have drive
* motor encoders or have elected not to use them for velocity control, these values should be
* empirically tuned.
*/
public static double kV = 1.0 / rpmToVelocity(MAX_RPM);
public static double kA = 0;
public static double kStatic = 0;
public static double kV = 0.00095;
public static double kA = 0.0003;
public static double kStatic = -0.07;

/*
* These values are used to generate the trajectories for you robot. To ensure proper operation,
Expand All @@ -64,14 +64,16 @@ public class DriveConstants {
* small and gradually increase them later after everything is working. All distance units are
* inches.
*/
public static double MAX_VEL = 30;
public static double MAX_ACCEL = 30;
public static double MAX_ANG_VEL = Math.toRadians(60);
public static double MAX_ANG_ACCEL = Math.toRadians(60);
public static double MAX_VELOCITY = 900;
public static double MAX_ACCELERATION = 500;
public static double MAX_ANGULAR_VELOCITY = 18.016340020937598;
public static double MAX_ANGULAR_ACCELERATION = Math.toRadians(60);

public static double MAX_BATTERY_VOLTAGE = 12;


public static double encoderTicksToInches(double ticks) {
return WHEEL_RADIUS * 2 * Math.PI * GEAR_RATIO * ticks / TICKS_PER_REV;
return WHEEL_RADIUS * 2 * Math.PI * GEAR_RATIO * ticks / TICKS_PER_REVOLUTION;
}

public static double rpmToVelocity(double rpm) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.qualcomm.robotcore.hardware.VoltageSensor;
Expand All @@ -29,17 +30,21 @@
import org.firstinspires.ftc.teamcode.roadrunner.trajectorysequence.TrajectorySequence;
import org.firstinspires.ftc.teamcode.roadrunner.trajectorysequence.TrajectorySequenceBuilder;
import org.firstinspires.ftc.teamcode.roadrunner.trajectorysequence.TrajectorySequenceRunner;
import org.firstinspires.ftc.teamcode.roadrunner.util.AxisDirection;
import org.firstinspires.ftc.teamcode.roadrunner.util.BNO055IMUUtil;
import org.firstinspires.ftc.teamcode.roadrunner.util.LynxModuleUtil;
import org.firstinspires.ftc.teamcode.subsystems.chassis.ChassisConstants;

import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ACCEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANG_ACCEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANG_VEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_VEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MOTOR_VELO_PID;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ACCELERATION;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANGULAR_ACCELERATION;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANGULAR_VELOCITY;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_BATTERY_VOLTAGE;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_VELOCITY;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MOTOR_VELOCITY_PID;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.TRACK_WIDTH;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.encoderTicksToInches;
Expand All @@ -53,19 +58,21 @@
@Config
public class SampleMecanumDrive extends MecanumDrive {

public static PIDCoefficients TRANSLATIONAL_PID = new PIDCoefficients(0, 0, 0);
public static PIDCoefficients HEADING_PID = new PIDCoefficients(0, 0, 0);
public static PIDCoefficients TRANSLATIONAL_PID = new PIDCoefficients(65, 0, 0);
public static PIDCoefficients HEADING_PID = new PIDCoefficients(0.25, 0, 0);

public static double LATERAL_MULTIPLIER = 1;
public static double LATERAL_MULTIPLIER = 1.0856210671340743708609271523179;

public static double VX_WEIGHT = 1;
public static double VY_WEIGHT = 1;
public static double OMEGA_WEIGHT = 1;

private TrajectorySequenceRunner trajectorySequenceRunner;

private static final TrajectoryVelocityConstraint VEL_CONSTRAINT = getVelocityConstraint(MAX_VEL, MAX_ANG_VEL, TRACK_WIDTH);
private static final TrajectoryAccelerationConstraint ACCEL_CONSTRAINT = getAccelerationConstraint(MAX_ACCEL);
private static final TrajectoryVelocityConstraint VEL_CONSTRAINT = getVelocityConstraint(MAX_VELOCITY, MAX_ANGULAR_VELOCITY, TRACK_WIDTH);
private static final TrajectoryAccelerationConstraint ACCEL_CONSTRAINT = getAccelerationConstraint(MAX_ACCELERATION);

private static final double ACHIEVABLE_MAX_MOTOR_RPM_FRACTION = 1.0;

private TrajectoryFollower follower;

Expand Down Expand Up @@ -94,8 +101,9 @@ public SampleMecanumDrive(HardwareMap hardwareMap) {
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.angleUnit = BNO055IMU.AngleUnit.RADIANS;
imu.initialize(parameters);
BNO055IMUUtil.remapZAxis(imu, AxisDirection.NEG_Y);

// TODO: If the hub containing the IMU you are using is mounted so that the "REV" logo does
// If the hub containing the IMU you are using is mounted so that the "REV" logo does
// not face up, remap the IMU axes so that the z-axis points upward (normal to the floor.)
//
// | +Z axis
Expand All @@ -117,16 +125,16 @@ public SampleMecanumDrive(HardwareMap hardwareMap) {
// For example, if +Y in this diagram faces downwards, you would use AxisDirection.NEG_Y.
// BNO055IMUUtil.remapZAxis(imu, AxisDirection.NEG_Y);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
leftFront = hardwareMap.get(DcMotorEx.class, ChassisConstants.FRONT_LEFT_ID);
leftRear = hardwareMap.get(DcMotorEx.class, ChassisConstants.BACK_LEFT_ID);
rightRear = hardwareMap.get(DcMotorEx.class, ChassisConstants.BACK_RIGHT_ID);
rightFront = hardwareMap.get(DcMotorEx.class, ChassisConstants.FRONT_RIGHT_ID);

motors = Arrays.asList(leftFront, leftRear, rightRear, rightFront);

for (DcMotorEx motor : motors) {
MotorConfigurationType motorConfigurationType = motor.getMotorType().clone();
motorConfigurationType.setAchieveableMaxRPMFraction(1.0);
motorConfigurationType.setAchieveableMaxRPMFraction(ACHIEVABLE_MAX_MOTOR_RPM_FRACTION);
motor.setMotorType(motorConfigurationType);
}

Expand All @@ -136,11 +144,13 @@ public SampleMecanumDrive(HardwareMap hardwareMap) {

setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);

if (RUN_USING_ENCODER && MOTOR_VELO_PID != null) {
setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELO_PID);
if (RUN_USING_ENCODER && MOTOR_VELOCITY_PID != null) {
setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELOCITY_PID);
}

// TODO: reverse any motors using DcMotor.setDirection()
// reverse any motors using DcMotor.setDirection()
rightFront.setDirection(DcMotorSimple.Direction.REVERSE);
rightRear.setDirection(DcMotorSimple.Direction.REVERSE);

// TODO: if desired, use setLocalizer() to change the localization method
// for instance, setLocalizer(new ThreeTrackingWheelLocalizer(...));
Expand All @@ -164,7 +174,7 @@ public TrajectorySequenceBuilder trajectorySequenceBuilder(Pose2d startPose) {
return new TrajectorySequenceBuilder(
startPose,
VEL_CONSTRAINT, ACCEL_CONSTRAINT,
MAX_ANG_VEL, MAX_ANG_ACCEL
MAX_ANGULAR_VELOCITY, MAX_ANGULAR_ACCELERATION
);
}

Expand Down Expand Up @@ -237,7 +247,7 @@ public void setZeroPowerBehavior(DcMotor.ZeroPowerBehavior zeroPowerBehavior) {
public void setPIDFCoefficients(DcMotor.RunMode runMode, PIDFCoefficients coefficients) {
PIDFCoefficients compensatedCoefficients = new PIDFCoefficients(
coefficients.p, coefficients.i, coefficients.d,
coefficients.f * 12 / batteryVoltageSensor.getVoltage()
coefficients.f * MAX_BATTERY_VOLTAGE / batteryVoltageSensor.getVoltage()
);

for (DcMotorEx motor : motors) {
Expand Down Expand Up @@ -304,7 +314,7 @@ public Double getExternalHeadingVelocity() {
// expected). This bug does NOT affect orientation.
//
// See https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/251 for details.
return (double) -imu.getAngularVelocity().xRotationRate;
return (double) imu.getAngularVelocity().yRotationRate;
}

public static TrajectoryVelocityConstraint getVelocityConstraint(double maxVel, double maxAngularVel, double trackWidth) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,11 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ACCEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANG_ACCEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANG_VEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_VEL;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MOTOR_VELO_PID;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ACCELERATION;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANGULAR_ACCELERATION;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_ANGULAR_VELOCITY;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MAX_VELOCITY;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.MOTOR_VELOCITY_PID;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.TRACK_WIDTH;
import static org.firstinspires.ftc.teamcode.roadrunner.drive.DriveConstants.encoderTicksToInches;
Expand All @@ -61,8 +61,8 @@ public class SampleTankDrive extends TankDrive {

private TrajectorySequenceRunner trajectorySequenceRunner;

private static final TrajectoryVelocityConstraint VEL_CONSTRAINT = getVelocityConstraint(MAX_VEL, MAX_ANG_VEL, TRACK_WIDTH);
private static final TrajectoryAccelerationConstraint accelConstraint = getAccelerationConstraint(MAX_ACCEL);
private static final TrajectoryVelocityConstraint VEL_CONSTRAINT = getVelocityConstraint(MAX_VELOCITY, MAX_ANGULAR_VELOCITY, TRACK_WIDTH);
private static final TrajectoryAccelerationConstraint accelConstraint = getAccelerationConstraint(MAX_ACCELERATION);

private TrajectoryFollower follower;

Expand Down Expand Up @@ -135,8 +135,8 @@ public SampleTankDrive(HardwareMap hardwareMap) {

setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);

if (RUN_USING_ENCODER && MOTOR_VELO_PID != null) {
setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELO_PID);
if (RUN_USING_ENCODER && MOTOR_VELOCITY_PID != null) {
setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELOCITY_PID);
}

// TODO: reverse any motors using DcMotor.setDirection()
Expand All @@ -163,7 +163,7 @@ public TrajectorySequenceBuilder trajectorySequenceBuilder(Pose2d startPose) {
return new TrajectorySequenceBuilder(
startPose,
VEL_CONSTRAINT, accelConstraint,
MAX_ANG_VEL, MAX_ANG_ACCEL
MAX_ANGULAR_VELOCITY, MAX_ANGULAR_ACCELERATION
);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.util.NanoClock;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.RobotLog;

Expand All @@ -28,6 +29,7 @@
* 4. Adjust the encoder data based on the velocity tuning data and find kA with another linear
* regression.
*/
@Disabled
@Config
@Autonomous(group = "drive")
public class AutomaticFeedforwardTuner extends LinearOpMode {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;

import org.firstinspires.ftc.teamcode.roadrunner.drive.SampleMecanumDrive;
Expand All @@ -24,6 +25,7 @@
* This opmode is designed as a convenient, coarse tuning for the follower PID coefficients. It
* is recommended that you use the FollowerPIDTuner opmode for further fine tuning.
*/

@Config
@Autonomous(group = "drive")
public class BackAndForth extends LinearOpMode {
Expand Down
Loading
Loading