diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/Drawing.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/Drawing.java new file mode 100644 index 0000000..764c4ee --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/Drawing.java @@ -0,0 +1,22 @@ +package org.firstinspires.ftc.teamcode.libs.RR; + +import com.acmerobotics.dashboard.canvas.Canvas; +import com.acmerobotics.roadrunner.Pose2d; +import com.acmerobotics.roadrunner.Vector2d; + +public final class Drawing { + private Drawing() {} + + + public static void drawRobot(Canvas c, Pose2d t) { + final double ROBOT_RADIUS = 9; + + c.setStrokeWidth(1); + c.strokeCircle(t.position.x, t.position.y, ROBOT_RADIUS); + + Vector2d halfv = t.heading.vec().times(0.5 * ROBOT_RADIUS); + Vector2d p1 = t.position.plus(halfv); + Vector2d p2 = p1.plus(halfv); + c.strokeLine(p1.x, p1.y, p2.x, p2.y); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/Localizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/Localizer.java new file mode 100644 index 0000000..970c400 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/Localizer.java @@ -0,0 +1,25 @@ +package org.firstinspires.ftc.teamcode.libs.RR; + +import com.acmerobotics.roadrunner.Pose2d; +import com.acmerobotics.roadrunner.PoseVelocity2d; + +/** + * Interface for localization methods. + */ +public interface Localizer { + void setPose(Pose2d pose); + + /** + * Returns the current pose estimate. + * NOTE: Does not update the pose estimate; + * you must call update() to update the pose estimate. + * @return the Localizer's current pose + */ + Pose2d getPose(); + + /** + * Updates the Localizer's pose estimate. + * @return the Localizer's current velocity estimate + */ + PoseVelocity2d update(); +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java new file mode 100644 index 0000000..6cc00c9 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java @@ -0,0 +1,496 @@ +package org.firstinspires.ftc.teamcode.libs.RR; + +import androidx.annotation.NonNull; + +import com.acmerobotics.dashboard.canvas.Canvas; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.TelemetryPacket; +import com.acmerobotics.roadrunner.*; +import com.acmerobotics.roadrunner.AngularVelConstraint; +import com.acmerobotics.roadrunner.DualNum; +import com.acmerobotics.roadrunner.HolonomicController; +import com.acmerobotics.roadrunner.MecanumKinematics; +import com.acmerobotics.roadrunner.MinVelConstraint; +import com.acmerobotics.roadrunner.MotorFeedforward; +import com.acmerobotics.roadrunner.Pose2d; +import com.acmerobotics.roadrunner.Pose2dDual; +import com.acmerobotics.roadrunner.ProfileAccelConstraint; +import com.acmerobotics.roadrunner.Time; +import com.acmerobotics.roadrunner.TimeTrajectory; +import com.acmerobotics.roadrunner.TimeTurn; +import com.acmerobotics.roadrunner.TrajectoryActionBuilder; +import com.acmerobotics.roadrunner.TurnConstraints; +import com.acmerobotics.roadrunner.VelConstraint; +import com.acmerobotics.roadrunner.ftc.DownsampledWriter; +import com.acmerobotics.roadrunner.ftc.Encoder; +import com.acmerobotics.roadrunner.ftc.FlightRecorder; +import com.acmerobotics.roadrunner.ftc.LazyHardwareMapImu; +import com.acmerobotics.roadrunner.ftc.LazyImu; +import com.acmerobotics.roadrunner.ftc.LynxFirmware; +import com.acmerobotics.roadrunner.ftc.OverflowEncoder; +import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; +import com.acmerobotics.roadrunner.ftc.RawEncoder; +import com.qualcomm.hardware.lynx.LynxModule; +import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; +import com.qualcomm.robotcore.hardware.VoltageSensor; + +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; +import org.firstinspires.ftc.teamcode.libs.RR.messages.DriveCommandMessage; +import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage; +import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage; +import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage; + +import java.lang.Math; +import java.util.Arrays; +import java.util.LinkedList; +import java.util.List; + +@Config +public final class MecanumDrive { + public static class Params { + // IMU orientation + // TODO: fill in these values based on + // see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting + public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection = + RevHubOrientationOnRobot.LogoFacingDirection.UP; + public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = + RevHubOrientationOnRobot.UsbFacingDirection.FORWARD; + + // drive model parameters + public double inPerTick = 1; + public double lateralInPerTick = inPerTick; + public double trackWidthTicks = 0; + + // feedforward parameters (in tick units) + public double kS = 0; + public double kV = 0; + public double kA = 0; + + // path profile parameters (in inches) + public double maxWheelVel = 50; + public double minProfileAccel = -30; + public double maxProfileAccel = 50; + + // turn profile parameters (in radians) + public double maxAngVel = Math.PI; // shared with path + public double maxAngAccel = Math.PI; + + // path controller gains + public double axialGain = 0.0; + public double lateralGain = 0.0; + public double headingGain = 0.0; // shared with turn + + public double axialVelGain = 0.0; + public double lateralVelGain = 0.0; + public double headingVelGain = 0.0; // shared with turn + } + + public static Params PARAMS = new Params(); + + public final MecanumKinematics kinematics = new MecanumKinematics( + PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick); + + public final TurnConstraints defaultTurnConstraints = new TurnConstraints( + PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel); + public final VelConstraint defaultVelConstraint = + new MinVelConstraint(Arrays.asList( + kinematics.new WheelVelConstraint(PARAMS.maxWheelVel), + new AngularVelConstraint(PARAMS.maxAngVel) + )); + public final AccelConstraint defaultAccelConstraint = + new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel); + + public final DcMotorEx leftFront, leftBack, rightBack, rightFront; + + public final VoltageSensor voltageSensor; + + public final LazyImu lazyImu; + + public final Localizer localizer; + private final LinkedList poseHistory = new LinkedList<>(); + + private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000); + private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000); + private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000); + private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000); + + public class DriveLocalizer implements Localizer { + public final Encoder leftFront, leftBack, rightBack, rightFront; + public final IMU imu; + + private int lastLeftFrontPos, lastLeftBackPos, lastRightBackPos, lastRightFrontPos; + private Rotation2d lastHeading; + private boolean initialized; + private Pose2d pose; + + public DriveLocalizer(Pose2d pose) { + leftFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftFront)); + leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack)); + rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack)); + rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront)); + + imu = lazyImu.get(); + + // TODO: reverse encoders if needed + // leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + + this.pose = pose; + } + + @Override + public void setPose(Pose2d pose) { + this.pose = pose; + } + + @Override + public Pose2d getPose() { + return pose; + } + + @Override + public PoseVelocity2d update() { + PositionVelocityPair leftFrontPosVel = leftFront.getPositionAndVelocity(); + PositionVelocityPair leftBackPosVel = leftBack.getPositionAndVelocity(); + PositionVelocityPair rightBackPosVel = rightBack.getPositionAndVelocity(); + PositionVelocityPair rightFrontPosVel = rightFront.getPositionAndVelocity(); + + YawPitchRollAngles angles = imu.getRobotYawPitchRollAngles(); + + FlightRecorder.write("MECANUM_LOCALIZER_INPUTS", new MecanumLocalizerInputsMessage( + leftFrontPosVel, leftBackPosVel, rightBackPosVel, rightFrontPosVel, angles)); + + Rotation2d heading = Rotation2d.exp(angles.getYaw(AngleUnit.RADIANS)); + + if (!initialized) { + initialized = true; + + lastLeftFrontPos = leftFrontPosVel.position; + lastLeftBackPos = leftBackPosVel.position; + lastRightBackPos = rightBackPosVel.position; + lastRightFrontPos = rightFrontPosVel.position; + + lastHeading = heading; + + return new PoseVelocity2d(new Vector2d(0.0, 0.0), 0.0); + } + + double headingDelta = heading.minus(lastHeading); + Twist2dDual