Setup RR
This commit is contained in:
@@ -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);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -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();
|
||||||
|
}
|
||||||
@@ -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<Pose2d> 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<Time> twist = kinematics.forward(new MecanumKinematics.WheelIncrements<>(
|
||||||
|
new DualNum<Time>(new double[]{
|
||||||
|
(leftFrontPosVel.position - lastLeftFrontPos),
|
||||||
|
leftFrontPosVel.velocity,
|
||||||
|
}).times(PARAMS.inPerTick),
|
||||||
|
new DualNum<Time>(new double[]{
|
||||||
|
(leftBackPosVel.position - lastLeftBackPos),
|
||||||
|
leftBackPosVel.velocity,
|
||||||
|
}).times(PARAMS.inPerTick),
|
||||||
|
new DualNum<Time>(new double[]{
|
||||||
|
(rightBackPosVel.position - lastRightBackPos),
|
||||||
|
rightBackPosVel.velocity,
|
||||||
|
}).times(PARAMS.inPerTick),
|
||||||
|
new DualNum<Time>(new double[]{
|
||||||
|
(rightFrontPosVel.position - lastRightFrontPos),
|
||||||
|
rightFrontPosVel.velocity,
|
||||||
|
}).times(PARAMS.inPerTick)
|
||||||
|
));
|
||||||
|
|
||||||
|
lastLeftFrontPos = leftFrontPosVel.position;
|
||||||
|
lastLeftBackPos = leftBackPosVel.position;
|
||||||
|
lastRightBackPos = rightBackPosVel.position;
|
||||||
|
lastRightFrontPos = rightFrontPosVel.position;
|
||||||
|
|
||||||
|
lastHeading = heading;
|
||||||
|
|
||||||
|
pose = pose.plus(new Twist2d(
|
||||||
|
twist.line.value(),
|
||||||
|
headingDelta
|
||||||
|
));
|
||||||
|
|
||||||
|
return twist.velocity().value();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||||
|
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||||
|
|
||||||
|
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||||
|
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: make sure your config has motors with these names (or change them)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
|
||||||
|
leftBack = hardwareMap.get(DcMotorEx.class, "leftBack");
|
||||||
|
rightBack = hardwareMap.get(DcMotorEx.class, "rightBack");
|
||||||
|
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
|
||||||
|
|
||||||
|
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
|
||||||
|
// TODO: reverse motor directions if needed
|
||||||
|
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||||
|
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||||
|
|
||||||
|
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||||
|
|
||||||
|
localizer = new DriveLocalizer(pose);
|
||||||
|
|
||||||
|
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setDrivePowers(PoseVelocity2d powers) {
|
||||||
|
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||||
|
PoseVelocity2dDual.constant(powers, 1));
|
||||||
|
|
||||||
|
double maxPowerMag = 1;
|
||||||
|
for (DualNum<Time> power : wheelVels.all()) {
|
||||||
|
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||||
|
}
|
||||||
|
|
||||||
|
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||||
|
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||||
|
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||||
|
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||||
|
}
|
||||||
|
|
||||||
|
public final class FollowTrajectoryAction implements Action {
|
||||||
|
public final TimeTrajectory timeTrajectory;
|
||||||
|
private double beginTs = -1;
|
||||||
|
|
||||||
|
private final double[] xPoints, yPoints;
|
||||||
|
|
||||||
|
public FollowTrajectoryAction(TimeTrajectory t) {
|
||||||
|
timeTrajectory = t;
|
||||||
|
|
||||||
|
List<Double> disps = com.acmerobotics.roadrunner.Math.range(
|
||||||
|
0, t.path.length(),
|
||||||
|
Math.max(2, (int) Math.ceil(t.path.length() / 2)));
|
||||||
|
xPoints = new double[disps.size()];
|
||||||
|
yPoints = new double[disps.size()];
|
||||||
|
for (int i = 0; i < disps.size(); i++) {
|
||||||
|
Pose2d p = t.path.get(disps.get(i), 1).value();
|
||||||
|
xPoints[i] = p.position.x;
|
||||||
|
yPoints[i] = p.position.y;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket p) {
|
||||||
|
double t;
|
||||||
|
if (beginTs < 0) {
|
||||||
|
beginTs = Actions.now();
|
||||||
|
t = 0;
|
||||||
|
} else {
|
||||||
|
t = Actions.now() - beginTs;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t >= timeTrajectory.duration) {
|
||||||
|
leftFront.setPower(0);
|
||||||
|
leftBack.setPower(0);
|
||||||
|
rightBack.setPower(0);
|
||||||
|
rightFront.setPower(0);
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
||||||
|
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||||
|
|
||||||
|
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||||
|
|
||||||
|
PoseVelocity2dDual<Time> command = new HolonomicController(
|
||||||
|
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
||||||
|
PARAMS.axialVelGain, PARAMS.lateralVelGain, PARAMS.headingVelGain
|
||||||
|
)
|
||||||
|
.compute(txWorldTarget, localizer.getPose(), robotVelRobot);
|
||||||
|
driveCommandWriter.write(new DriveCommandMessage(command));
|
||||||
|
|
||||||
|
MecanumKinematics.WheelVelocities<Time> wheelVels = kinematics.inverse(command);
|
||||||
|
double voltage = voltageSensor.getVoltage();
|
||||||
|
|
||||||
|
final MotorFeedforward feedforward = new MotorFeedforward(PARAMS.kS,
|
||||||
|
PARAMS.kV / PARAMS.inPerTick, PARAMS.kA / PARAMS.inPerTick);
|
||||||
|
double leftFrontPower = feedforward.compute(wheelVels.leftFront) / voltage;
|
||||||
|
double leftBackPower = feedforward.compute(wheelVels.leftBack) / voltage;
|
||||||
|
double rightBackPower = feedforward.compute(wheelVels.rightBack) / voltage;
|
||||||
|
double rightFrontPower = feedforward.compute(wheelVels.rightFront) / voltage;
|
||||||
|
mecanumCommandWriter.write(new MecanumCommandMessage(
|
||||||
|
voltage, leftFrontPower, leftBackPower, rightBackPower, rightFrontPower
|
||||||
|
));
|
||||||
|
|
||||||
|
leftFront.setPower(leftFrontPower);
|
||||||
|
leftBack.setPower(leftBackPower);
|
||||||
|
rightBack.setPower(rightBackPower);
|
||||||
|
rightFront.setPower(rightFrontPower);
|
||||||
|
|
||||||
|
p.put("x", localizer.getPose().position.x);
|
||||||
|
p.put("y", localizer.getPose().position.y);
|
||||||
|
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
||||||
|
|
||||||
|
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
||||||
|
p.put("xError", error.position.x);
|
||||||
|
p.put("yError", error.position.y);
|
||||||
|
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
||||||
|
|
||||||
|
// only draw when active; only one drive action should be active at a time
|
||||||
|
Canvas c = p.fieldOverlay();
|
||||||
|
drawPoseHistory(c);
|
||||||
|
|
||||||
|
c.setStroke("#4CAF50");
|
||||||
|
Drawing.drawRobot(c, txWorldTarget.value());
|
||||||
|
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
Drawing.drawRobot(c, localizer.getPose());
|
||||||
|
|
||||||
|
c.setStroke("#4CAF50FF");
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void preview(Canvas c) {
|
||||||
|
c.setStroke("#4CAF507A");
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public final class TurnAction implements Action {
|
||||||
|
private final TimeTurn turn;
|
||||||
|
|
||||||
|
private double beginTs = -1;
|
||||||
|
|
||||||
|
public TurnAction(TimeTurn turn) {
|
||||||
|
this.turn = turn;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket p) {
|
||||||
|
double t;
|
||||||
|
if (beginTs < 0) {
|
||||||
|
beginTs = Actions.now();
|
||||||
|
t = 0;
|
||||||
|
} else {
|
||||||
|
t = Actions.now() - beginTs;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t >= turn.duration) {
|
||||||
|
leftFront.setPower(0);
|
||||||
|
leftBack.setPower(0);
|
||||||
|
rightBack.setPower(0);
|
||||||
|
rightFront.setPower(0);
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Pose2dDual<Time> txWorldTarget = turn.get(t);
|
||||||
|
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||||
|
|
||||||
|
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||||
|
|
||||||
|
PoseVelocity2dDual<Time> command = new HolonomicController(
|
||||||
|
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
||||||
|
PARAMS.axialVelGain, PARAMS.lateralVelGain, PARAMS.headingVelGain
|
||||||
|
)
|
||||||
|
.compute(txWorldTarget, localizer.getPose(), robotVelRobot);
|
||||||
|
driveCommandWriter.write(new DriveCommandMessage(command));
|
||||||
|
|
||||||
|
MecanumKinematics.WheelVelocities<Time> wheelVels = kinematics.inverse(command);
|
||||||
|
double voltage = voltageSensor.getVoltage();
|
||||||
|
final MotorFeedforward feedforward = new MotorFeedforward(PARAMS.kS,
|
||||||
|
PARAMS.kV / PARAMS.inPerTick, PARAMS.kA / PARAMS.inPerTick);
|
||||||
|
double leftFrontPower = feedforward.compute(wheelVels.leftFront) / voltage;
|
||||||
|
double leftBackPower = feedforward.compute(wheelVels.leftBack) / voltage;
|
||||||
|
double rightBackPower = feedforward.compute(wheelVels.rightBack) / voltage;
|
||||||
|
double rightFrontPower = feedforward.compute(wheelVels.rightFront) / voltage;
|
||||||
|
mecanumCommandWriter.write(new MecanumCommandMessage(
|
||||||
|
voltage, leftFrontPower, leftBackPower, rightBackPower, rightFrontPower
|
||||||
|
));
|
||||||
|
|
||||||
|
leftFront.setPower(feedforward.compute(wheelVels.leftFront) / voltage);
|
||||||
|
leftBack.setPower(feedforward.compute(wheelVels.leftBack) / voltage);
|
||||||
|
rightBack.setPower(feedforward.compute(wheelVels.rightBack) / voltage);
|
||||||
|
rightFront.setPower(feedforward.compute(wheelVels.rightFront) / voltage);
|
||||||
|
|
||||||
|
Canvas c = p.fieldOverlay();
|
||||||
|
drawPoseHistory(c);
|
||||||
|
|
||||||
|
c.setStroke("#4CAF50");
|
||||||
|
Drawing.drawRobot(c, txWorldTarget.value());
|
||||||
|
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
Drawing.drawRobot(c, localizer.getPose());
|
||||||
|
|
||||||
|
c.setStroke("#7C4DFFFF");
|
||||||
|
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void preview(Canvas c) {
|
||||||
|
c.setStroke("#7C4DFF7A");
|
||||||
|
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public PoseVelocity2d updatePoseEstimate() {
|
||||||
|
PoseVelocity2d vel = localizer.update();
|
||||||
|
poseHistory.add(localizer.getPose());
|
||||||
|
|
||||||
|
while (poseHistory.size() > 100) {
|
||||||
|
poseHistory.removeFirst();
|
||||||
|
}
|
||||||
|
|
||||||
|
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||||
|
|
||||||
|
|
||||||
|
return vel;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void drawPoseHistory(Canvas c) {
|
||||||
|
double[] xPoints = new double[poseHistory.size()];
|
||||||
|
double[] yPoints = new double[poseHistory.size()];
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for (Pose2d t : poseHistory) {
|
||||||
|
xPoints[i] = t.position.x;
|
||||||
|
yPoints[i] = t.position.y;
|
||||||
|
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
}
|
||||||
|
|
||||||
|
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||||
|
return new TrajectoryActionBuilder(
|
||||||
|
TurnAction::new,
|
||||||
|
FollowTrajectoryAction::new,
|
||||||
|
new TrajectoryBuilderParams(
|
||||||
|
1e-6,
|
||||||
|
new ProfileParams(
|
||||||
|
0.25, 0.1, 1e-2
|
||||||
|
)
|
||||||
|
),
|
||||||
|
beginPose, 0.0,
|
||||||
|
defaultTurnConstraints,
|
||||||
|
defaultVelConstraint, defaultAccelConstraint
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,68 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.Rotation2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSKt;
|
||||||
|
import com.qualcomm.hardware.sparkfun.SparkFunOTOS;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class OTOSLocalizer implements Localizer {
|
||||||
|
public static class Params {
|
||||||
|
public double angularScalar = 1.0;
|
||||||
|
public double linearScalar = 1.0;
|
||||||
|
|
||||||
|
// Note: units are in inches and radians
|
||||||
|
public SparkFunOTOS.Pose2D offset = new SparkFunOTOS.Pose2D(0, 0, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
|
public final SparkFunOTOS otos;
|
||||||
|
private Pose2d currentPose;
|
||||||
|
|
||||||
|
public OTOSLocalizer(HardwareMap hardwareMap, Pose2d initialPose) {
|
||||||
|
// TODO: make sure your config has an OTOS device with this name
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
otos = hardwareMap.get(SparkFunOTOS.class, "sensor_otos");
|
||||||
|
currentPose = initialPose;
|
||||||
|
otos.setPosition(OTOSKt.toOTOSPose(currentPose));
|
||||||
|
otos.setLinearUnit(DistanceUnit.INCH);
|
||||||
|
otos.setAngularUnit(AngleUnit.RADIANS);
|
||||||
|
|
||||||
|
otos.calibrateImu();
|
||||||
|
otos.setLinearScalar(PARAMS.linearScalar);
|
||||||
|
otos.setAngularScalar(PARAMS.angularScalar);
|
||||||
|
otos.setOffset(PARAMS.offset);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public Pose2d getPose() {
|
||||||
|
return currentPose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void setPose(Pose2d pose) {
|
||||||
|
currentPose = pose;
|
||||||
|
otos.setPosition(OTOSKt.toOTOSPose(currentPose));
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public PoseVelocity2d update() {
|
||||||
|
SparkFunOTOS.Pose2D otosPose = new SparkFunOTOS.Pose2D();
|
||||||
|
SparkFunOTOS.Pose2D otosVel = new SparkFunOTOS.Pose2D();
|
||||||
|
SparkFunOTOS.Pose2D otosAcc = new SparkFunOTOS.Pose2D();
|
||||||
|
otos.getPosVelAcc(otosPose, otosVel, otosAcc);
|
||||||
|
|
||||||
|
currentPose = OTOSKt.toRRPose(otosPose);
|
||||||
|
Vector2d fieldVel = new Vector2d(otosVel.x, otosVel.y);
|
||||||
|
Vector2d robotVel = Rotation2d.exp(otosPose.h).inverse().times(fieldVel);
|
||||||
|
return new PoseVelocity2d(robotVel, otosVel.h);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,73 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.Rotation2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.UnnormalizedAngleUnit;
|
||||||
|
|
||||||
|
import java.util.Objects;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public final class PinpointLocalizer implements Localizer {
|
||||||
|
public static class Params {
|
||||||
|
public double parYTicks = 0.0; // y position of the parallel encoder (in tick units)
|
||||||
|
public double perpXTicks = 0.0; // x position of the perpendicular encoder (in tick units)
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
|
public final GoBildaPinpointDriver driver;
|
||||||
|
public final GoBildaPinpointDriver.EncoderDirection initialParDirection, initialPerpDirection;
|
||||||
|
|
||||||
|
private Pose2d txWorldPinpoint;
|
||||||
|
private Pose2d txPinpointRobot = new Pose2d(0, 0, 0);
|
||||||
|
|
||||||
|
public PinpointLocalizer(HardwareMap hardwareMap, double inPerTick, Pose2d initialPose) {
|
||||||
|
// TODO: make sure your config has a Pinpoint device with this name
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
driver = hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint");
|
||||||
|
|
||||||
|
double mmPerTick = inPerTick * 25.4;
|
||||||
|
driver.setEncoderResolution(1 / mmPerTick, DistanceUnit.MM);
|
||||||
|
driver.setOffsets(mmPerTick * PARAMS.parYTicks, mmPerTick * PARAMS.perpXTicks, DistanceUnit.MM);
|
||||||
|
|
||||||
|
// TODO: reverse encoder directions if needed
|
||||||
|
initialParDirection = GoBildaPinpointDriver.EncoderDirection.FORWARD;
|
||||||
|
initialPerpDirection = GoBildaPinpointDriver.EncoderDirection.FORWARD;
|
||||||
|
|
||||||
|
driver.setEncoderDirections(initialParDirection, initialPerpDirection);
|
||||||
|
|
||||||
|
driver.resetPosAndIMU();
|
||||||
|
|
||||||
|
txWorldPinpoint = initialPose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void setPose(Pose2d pose) {
|
||||||
|
txWorldPinpoint = pose.times(txPinpointRobot.inverse());
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public Pose2d getPose() {
|
||||||
|
return txWorldPinpoint.times(txPinpointRobot);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public PoseVelocity2d update() {
|
||||||
|
driver.update();
|
||||||
|
if (Objects.requireNonNull(driver.getDeviceStatus()) == GoBildaPinpointDriver.DeviceStatus.READY) {
|
||||||
|
txPinpointRobot = new Pose2d(driver.getPosX(DistanceUnit.INCH), driver.getPosY(DistanceUnit.INCH), driver.getHeading(UnnormalizedAngleUnit.RADIANS));
|
||||||
|
Vector2d worldVelocity = new Vector2d(driver.getVelX(DistanceUnit.INCH), driver.getVelY(DistanceUnit.INCH));
|
||||||
|
Vector2d robotVelocity = Rotation2d.fromDouble(-txPinpointRobot.heading.log()).times(worldVelocity);
|
||||||
|
|
||||||
|
return new PoseVelocity2d(robotVelocity, driver.getHeadingVelocity(UnnormalizedAngleUnit.RADIANS));
|
||||||
|
}
|
||||||
|
return new PoseVelocity2d(new Vector2d(0, 0), 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,509 @@
|
|||||||
|
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.AccelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.Actions;
|
||||||
|
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.Arclength;
|
||||||
|
import com.acmerobotics.roadrunner.DualNum;
|
||||||
|
import com.acmerobotics.roadrunner.MinVelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.MotorFeedforward;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.ProfileParams;
|
||||||
|
import com.acmerobotics.roadrunner.RamseteController;
|
||||||
|
import com.acmerobotics.roadrunner.TankKinematics;
|
||||||
|
import com.acmerobotics.roadrunner.Time;
|
||||||
|
import com.acmerobotics.roadrunner.TimeTrajectory;
|
||||||
|
import com.acmerobotics.roadrunner.TimeTurn;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
|
||||||
|
import com.acmerobotics.roadrunner.TurnConstraints;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2dDual;
|
||||||
|
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.VoltageSensor;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.DriveCommandMessage;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.TankCommandMessage;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.TankLocalizerInputsMessage;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.Arrays;
|
||||||
|
import java.util.Collections;
|
||||||
|
import java.util.LinkedList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public final class TankDrive {
|
||||||
|
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 = 0;
|
||||||
|
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 ramseteZeta = 0.7; // in the range (0, 1)
|
||||||
|
public double ramseteBBar = 2.0; // positive
|
||||||
|
|
||||||
|
// turn controller gains
|
||||||
|
public double turnGain = 0.0;
|
||||||
|
public double turnVelGain = 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
|
public final TankKinematics kinematics = new TankKinematics(PARAMS.inPerTick * PARAMS.trackWidthTicks);
|
||||||
|
|
||||||
|
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 List<DcMotorEx> leftMotors, rightMotors;
|
||||||
|
|
||||||
|
public final LazyImu lazyImu;
|
||||||
|
|
||||||
|
public final VoltageSensor voltageSensor;
|
||||||
|
|
||||||
|
public final Localizer localizer;
|
||||||
|
private final LinkedList<Pose2d> 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 tankCommandWriter = new DownsampledWriter("TANK_COMMAND", 50_000_000);
|
||||||
|
|
||||||
|
public class DriveLocalizer implements Localizer {
|
||||||
|
public final List<Encoder> leftEncs, rightEncs;
|
||||||
|
private Pose2d pose;
|
||||||
|
|
||||||
|
private double lastLeftPos, lastRightPos;
|
||||||
|
private boolean initialized;
|
||||||
|
|
||||||
|
public DriveLocalizer(Pose2d pose) {
|
||||||
|
{
|
||||||
|
List<Encoder> leftEncs = new ArrayList<>();
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
Encoder e = new OverflowEncoder(new RawEncoder(m));
|
||||||
|
leftEncs.add(e);
|
||||||
|
}
|
||||||
|
this.leftEncs = Collections.unmodifiableList(leftEncs);
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
List<Encoder> rightEncs = new ArrayList<>();
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
Encoder e = new OverflowEncoder(new RawEncoder(m));
|
||||||
|
rightEncs.add(e);
|
||||||
|
}
|
||||||
|
this.rightEncs = Collections.unmodifiableList(rightEncs);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: reverse encoder directions if needed
|
||||||
|
// leftEncs.get(0).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() {
|
||||||
|
Twist2dDual<Time> delta;
|
||||||
|
|
||||||
|
List<PositionVelocityPair> leftReadings = new ArrayList<>(), rightReadings = new ArrayList<>();
|
||||||
|
double meanLeftPos = 0.0, meanLeftVel = 0.0;
|
||||||
|
for (Encoder e : leftEncs) {
|
||||||
|
PositionVelocityPair p = e.getPositionAndVelocity();
|
||||||
|
meanLeftPos += p.position;
|
||||||
|
meanLeftVel += p.velocity;
|
||||||
|
leftReadings.add(p);
|
||||||
|
}
|
||||||
|
meanLeftPos /= leftEncs.size();
|
||||||
|
meanLeftVel /= leftEncs.size();
|
||||||
|
|
||||||
|
double meanRightPos = 0.0, meanRightVel = 0.0;
|
||||||
|
for (Encoder e : rightEncs) {
|
||||||
|
PositionVelocityPair p = e.getPositionAndVelocity();
|
||||||
|
meanRightPos += p.position;
|
||||||
|
meanRightVel += p.velocity;
|
||||||
|
rightReadings.add(p);
|
||||||
|
}
|
||||||
|
meanRightPos /= rightEncs.size();
|
||||||
|
meanRightVel /= rightEncs.size();
|
||||||
|
|
||||||
|
FlightRecorder.write("TANK_LOCALIZER_INPUTS",
|
||||||
|
new TankLocalizerInputsMessage(leftReadings, rightReadings));
|
||||||
|
|
||||||
|
if (!initialized) {
|
||||||
|
initialized = true;
|
||||||
|
|
||||||
|
lastLeftPos = meanLeftPos;
|
||||||
|
lastRightPos = meanRightPos;
|
||||||
|
|
||||||
|
return new PoseVelocity2d(new Vector2d(0.0, 0.0), 0.0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Twist2dDual<Time> twist = kinematics.forward(new TankKinematics.WheelIncrements<>(
|
||||||
|
new DualNum<Time>(new double[]{
|
||||||
|
meanLeftPos - lastLeftPos,
|
||||||
|
meanLeftVel
|
||||||
|
}).times(PARAMS.inPerTick),
|
||||||
|
new DualNum<Time>(new double[]{
|
||||||
|
meanRightPos - lastRightPos,
|
||||||
|
meanRightVel,
|
||||||
|
}).times(PARAMS.inPerTick)
|
||||||
|
));
|
||||||
|
|
||||||
|
lastLeftPos = meanLeftPos;
|
||||||
|
lastRightPos = meanRightPos;
|
||||||
|
|
||||||
|
pose = pose.plus(twist.value());
|
||||||
|
|
||||||
|
return twist.velocity().value();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public TankDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||||
|
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||||
|
|
||||||
|
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||||
|
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: make sure your config has motors with these names (or change them)
|
||||||
|
// add additional motors on each side if you have them
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
leftMotors = Arrays.asList(hardwareMap.get(DcMotorEx.class, "left"));
|
||||||
|
rightMotors = Arrays.asList(hardwareMap.get(DcMotorEx.class, "right"));
|
||||||
|
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
m.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
}
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
m.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: reverse motor directions if needed
|
||||||
|
// leftMotors.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||||
|
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||||
|
|
||||||
|
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||||
|
|
||||||
|
localizer = new DriveLocalizer(pose);
|
||||||
|
|
||||||
|
FlightRecorder.write("TANK_PARAMS", PARAMS);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setDrivePowers(PoseVelocity2d powers) {
|
||||||
|
TankKinematics.WheelVelocities<Time> wheelVels = new TankKinematics(2).inverse(
|
||||||
|
PoseVelocity2dDual.constant(powers, 1));
|
||||||
|
|
||||||
|
double maxPowerMag = 1;
|
||||||
|
for (DualNum<Time> power : wheelVels.all()) {
|
||||||
|
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||||
|
}
|
||||||
|
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
m.setPower(wheelVels.left.get(0) / maxPowerMag);
|
||||||
|
}
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
m.setPower(wheelVels.right.get(0) / maxPowerMag);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public final class FollowTrajectoryAction implements Action {
|
||||||
|
public final TimeTrajectory timeTrajectory;
|
||||||
|
private double beginTs = -1;
|
||||||
|
|
||||||
|
private final double[] xPoints, yPoints;
|
||||||
|
|
||||||
|
public FollowTrajectoryAction(TimeTrajectory t) {
|
||||||
|
timeTrajectory = t;
|
||||||
|
|
||||||
|
List<Double> disps = com.acmerobotics.roadrunner.Math.range(
|
||||||
|
0, t.path.length(),
|
||||||
|
Math.max(2, (int) Math.ceil(t.path.length() / 2)));
|
||||||
|
xPoints = new double[disps.size()];
|
||||||
|
yPoints = new double[disps.size()];
|
||||||
|
for (int i = 0; i < disps.size(); i++) {
|
||||||
|
Pose2d p = t.path.get(disps.get(i), 1).value();
|
||||||
|
xPoints[i] = p.position.x;
|
||||||
|
yPoints[i] = p.position.y;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket p) {
|
||||||
|
double t;
|
||||||
|
if (beginTs < 0) {
|
||||||
|
beginTs = Actions.now();
|
||||||
|
t = 0;
|
||||||
|
} else {
|
||||||
|
t = Actions.now() - beginTs;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t >= timeTrajectory.duration) {
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
m.setPower(0);
|
||||||
|
}
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
m.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
DualNum<Time> x = timeTrajectory.profile.get(t);
|
||||||
|
|
||||||
|
Pose2dDual<Arclength> txWorldTarget = timeTrajectory.path.get(x.value(), 3);
|
||||||
|
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||||
|
|
||||||
|
updatePoseEstimate();
|
||||||
|
|
||||||
|
PoseVelocity2dDual<Time> command = new RamseteController(kinematics.trackWidth, PARAMS.ramseteZeta, PARAMS.ramseteBBar)
|
||||||
|
.compute(x, txWorldTarget, localizer.getPose());
|
||||||
|
driveCommandWriter.write(new DriveCommandMessage(command));
|
||||||
|
|
||||||
|
TankKinematics.WheelVelocities<Time> wheelVels = kinematics.inverse(command);
|
||||||
|
double voltage = voltageSensor.getVoltage();
|
||||||
|
final MotorFeedforward feedforward = new MotorFeedforward(PARAMS.kS,
|
||||||
|
PARAMS.kV / PARAMS.inPerTick, PARAMS.kA / PARAMS.inPerTick);
|
||||||
|
double leftPower = feedforward.compute(wheelVels.left) / voltage;
|
||||||
|
double rightPower = feedforward.compute(wheelVels.right) / voltage;
|
||||||
|
tankCommandWriter.write(new TankCommandMessage(voltage, leftPower, rightPower));
|
||||||
|
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
m.setPower(leftPower);
|
||||||
|
}
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
m.setPower(rightPower);
|
||||||
|
}
|
||||||
|
|
||||||
|
p.put("x", localizer.getPose().position.x);
|
||||||
|
p.put("y", localizer.getPose().position.y);
|
||||||
|
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
||||||
|
|
||||||
|
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
||||||
|
p.put("xError", error.position.x);
|
||||||
|
p.put("yError", error.position.y);
|
||||||
|
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
||||||
|
|
||||||
|
// only draw when active; only one drive action should be active at a time
|
||||||
|
Canvas c = p.fieldOverlay();
|
||||||
|
drawPoseHistory(c);
|
||||||
|
|
||||||
|
c.setStroke("#4CAF50");
|
||||||
|
Drawing.drawRobot(c, txWorldTarget.value());
|
||||||
|
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
Drawing.drawRobot(c, localizer.getPose());
|
||||||
|
|
||||||
|
c.setStroke("#4CAF50FF");
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void preview(Canvas c) {
|
||||||
|
c.setStroke("#4CAF507A");
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public final class TurnAction implements Action {
|
||||||
|
private final TimeTurn turn;
|
||||||
|
|
||||||
|
private double beginTs = -1;
|
||||||
|
|
||||||
|
public TurnAction(TimeTurn turn) {
|
||||||
|
this.turn = turn;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket p) {
|
||||||
|
double t;
|
||||||
|
if (beginTs < 0) {
|
||||||
|
beginTs = Actions.now();
|
||||||
|
t = 0;
|
||||||
|
} else {
|
||||||
|
t = Actions.now() - beginTs;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t >= turn.duration) {
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
m.setPower(0);
|
||||||
|
}
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
m.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Pose2dDual<Time> txWorldTarget = turn.get(t);
|
||||||
|
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||||
|
|
||||||
|
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||||
|
|
||||||
|
PoseVelocity2dDual<Time> command = new PoseVelocity2dDual<>(
|
||||||
|
Vector2dDual.constant(new Vector2d(0, 0), 3),
|
||||||
|
txWorldTarget.heading.velocity().plus(
|
||||||
|
PARAMS.turnGain * localizer.getPose().heading.minus(txWorldTarget.heading.value()) +
|
||||||
|
PARAMS.turnVelGain * (robotVelRobot.angVel - txWorldTarget.heading.velocity().value())
|
||||||
|
)
|
||||||
|
);
|
||||||
|
driveCommandWriter.write(new DriveCommandMessage(command));
|
||||||
|
|
||||||
|
TankKinematics.WheelVelocities<Time> wheelVels = kinematics.inverse(command);
|
||||||
|
double voltage = voltageSensor.getVoltage();
|
||||||
|
final MotorFeedforward feedforward = new MotorFeedforward(PARAMS.kS,
|
||||||
|
PARAMS.kV / PARAMS.inPerTick, PARAMS.kA / PARAMS.inPerTick);
|
||||||
|
double leftPower = feedforward.compute(wheelVels.left) / voltage;
|
||||||
|
double rightPower = feedforward.compute(wheelVels.right) / voltage;
|
||||||
|
tankCommandWriter.write(new TankCommandMessage(voltage, leftPower, rightPower));
|
||||||
|
|
||||||
|
for (DcMotorEx m : leftMotors) {
|
||||||
|
m.setPower(leftPower);
|
||||||
|
}
|
||||||
|
for (DcMotorEx m : rightMotors) {
|
||||||
|
m.setPower(rightPower);
|
||||||
|
}
|
||||||
|
|
||||||
|
Canvas c = p.fieldOverlay();
|
||||||
|
drawPoseHistory(c);
|
||||||
|
|
||||||
|
c.setStroke("#4CAF50");
|
||||||
|
Drawing.drawRobot(c, txWorldTarget.value());
|
||||||
|
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
Drawing.drawRobot(c, localizer.getPose());
|
||||||
|
|
||||||
|
c.setStroke("#7C4DFFFF");
|
||||||
|
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void preview(Canvas c) {
|
||||||
|
c.setStroke("#7C4DFF7A");
|
||||||
|
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public PoseVelocity2d updatePoseEstimate() {
|
||||||
|
PoseVelocity2d vel = localizer.update();
|
||||||
|
poseHistory.add(localizer.getPose());
|
||||||
|
|
||||||
|
while (poseHistory.size() > 100) {
|
||||||
|
poseHistory.removeFirst();
|
||||||
|
}
|
||||||
|
|
||||||
|
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||||
|
|
||||||
|
|
||||||
|
return vel;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void drawPoseHistory(Canvas c) {
|
||||||
|
double[] xPoints = new double[poseHistory.size()];
|
||||||
|
double[] yPoints = new double[poseHistory.size()];
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for (Pose2d t : poseHistory) {
|
||||||
|
xPoints[i] = t.position.x;
|
||||||
|
yPoints[i] = t.position.y;
|
||||||
|
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
}
|
||||||
|
|
||||||
|
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||||
|
return new TrajectoryActionBuilder(
|
||||||
|
TurnAction::new,
|
||||||
|
FollowTrajectoryAction::new,
|
||||||
|
new TrajectoryBuilderParams(
|
||||||
|
1e-6,
|
||||||
|
new ProfileParams(
|
||||||
|
0.25, 0.1, 1e-2
|
||||||
|
)
|
||||||
|
),
|
||||||
|
beginPose, 0.0,
|
||||||
|
defaultTurnConstraints,
|
||||||
|
defaultVelConstraint, defaultAccelConstraint
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,113 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.DualNum;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.Time;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.FlightRecorder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OverflowEncoder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.RawEncoder;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.ThreeDeadWheelInputsMessage;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public final class ThreeDeadWheelLocalizer implements Localizer {
|
||||||
|
public static class Params {
|
||||||
|
public double par0YTicks = 0.0; // y position of the first parallel encoder (in tick units)
|
||||||
|
public double par1YTicks = 1.0; // y position of the second parallel encoder (in tick units)
|
||||||
|
public double perpXTicks = 0.0; // x position of the perpendicular encoder (in tick units)
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
|
public final Encoder par0, par1, perp;
|
||||||
|
|
||||||
|
public final double inPerTick;
|
||||||
|
|
||||||
|
private int lastPar0Pos, lastPar1Pos, lastPerpPos;
|
||||||
|
private boolean initialized;
|
||||||
|
private Pose2d pose;
|
||||||
|
|
||||||
|
public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick, Pose2d initialPose) {
|
||||||
|
// TODO: make sure your config has **motors** with these names (or change them)
|
||||||
|
// the encoders should be plugged into the slot matching the named motor
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par0")));
|
||||||
|
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par1")));
|
||||||
|
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));
|
||||||
|
|
||||||
|
// TODO: reverse encoder directions if needed
|
||||||
|
// par0.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
this.inPerTick = inPerTick;
|
||||||
|
|
||||||
|
FlightRecorder.write("THREE_DEAD_WHEEL_PARAMS", PARAMS);
|
||||||
|
|
||||||
|
pose = initialPose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void setPose(Pose2d pose) {
|
||||||
|
this.pose = pose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public Pose2d getPose() {
|
||||||
|
return pose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public PoseVelocity2d update() {
|
||||||
|
PositionVelocityPair par0PosVel = par0.getPositionAndVelocity();
|
||||||
|
PositionVelocityPair par1PosVel = par1.getPositionAndVelocity();
|
||||||
|
PositionVelocityPair perpPosVel = perp.getPositionAndVelocity();
|
||||||
|
|
||||||
|
FlightRecorder.write("THREE_DEAD_WHEEL_INPUTS", new ThreeDeadWheelInputsMessage(par0PosVel, par1PosVel, perpPosVel));
|
||||||
|
|
||||||
|
if (!initialized) {
|
||||||
|
initialized = true;
|
||||||
|
|
||||||
|
lastPar0Pos = par0PosVel.position;
|
||||||
|
lastPar1Pos = par1PosVel.position;
|
||||||
|
lastPerpPos = perpPosVel.position;
|
||||||
|
|
||||||
|
return new PoseVelocity2d(new Vector2d(0.0, 0.0), 0.0);
|
||||||
|
}
|
||||||
|
|
||||||
|
int par0PosDelta = par0PosVel.position - lastPar0Pos;
|
||||||
|
int par1PosDelta = par1PosVel.position - lastPar1Pos;
|
||||||
|
int perpPosDelta = perpPosVel.position - lastPerpPos;
|
||||||
|
|
||||||
|
Twist2dDual<Time> twist = new Twist2dDual<>(
|
||||||
|
new Vector2dDual<>(
|
||||||
|
new DualNum<Time>(new double[] {
|
||||||
|
(PARAMS.par0YTicks * par1PosDelta - PARAMS.par1YTicks * par0PosDelta) / (PARAMS.par0YTicks - PARAMS.par1YTicks),
|
||||||
|
(PARAMS.par0YTicks * par1PosVel.velocity - PARAMS.par1YTicks * par0PosVel.velocity) / (PARAMS.par0YTicks - PARAMS.par1YTicks),
|
||||||
|
}).times(inPerTick),
|
||||||
|
new DualNum<Time>(new double[] {
|
||||||
|
(PARAMS.perpXTicks / (PARAMS.par0YTicks - PARAMS.par1YTicks) * (par1PosDelta - par0PosDelta) + perpPosDelta),
|
||||||
|
(PARAMS.perpXTicks / (PARAMS.par0YTicks - PARAMS.par1YTicks) * (par1PosVel.velocity - par0PosVel.velocity) + perpPosVel.velocity),
|
||||||
|
}).times(inPerTick)
|
||||||
|
),
|
||||||
|
new DualNum<>(new double[] {
|
||||||
|
(par0PosDelta - par1PosDelta) / (PARAMS.par0YTicks - PARAMS.par1YTicks),
|
||||||
|
(par0PosVel.velocity - par1PosVel.velocity) / (PARAMS.par0YTicks - PARAMS.par1YTicks),
|
||||||
|
})
|
||||||
|
);
|
||||||
|
|
||||||
|
lastPar0Pos = par0PosVel.position;
|
||||||
|
lastPar1Pos = par1PosVel.position;
|
||||||
|
lastPerpPos = perpPosVel.position;
|
||||||
|
|
||||||
|
pose = pose.plus(twist.value());
|
||||||
|
return twist.velocity().value();
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,143 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.DualNum;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.Rotation2d;
|
||||||
|
import com.acmerobotics.roadrunner.Time;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.FlightRecorder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OverflowEncoder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.RawEncoder;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
import com.qualcomm.robotcore.hardware.IMU;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngularVelocity;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.UnnormalizedAngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.TwoDeadWheelInputsMessage;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public final class TwoDeadWheelLocalizer implements Localizer {
|
||||||
|
public static class Params {
|
||||||
|
public double parYTicks = 0.0; // y position of the parallel encoder (in tick units)
|
||||||
|
public double perpXTicks = 0.0; // x position of the perpendicular encoder (in tick units)
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
|
public final Encoder par, perp;
|
||||||
|
public final IMU imu;
|
||||||
|
|
||||||
|
private int lastParPos, lastPerpPos;
|
||||||
|
private Rotation2d lastHeading;
|
||||||
|
|
||||||
|
private final double inPerTick;
|
||||||
|
|
||||||
|
private double lastRawHeadingVel, headingVelOffset;
|
||||||
|
private boolean initialized;
|
||||||
|
private Pose2d pose;
|
||||||
|
|
||||||
|
public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick, Pose2d initialPose) {
|
||||||
|
// TODO: make sure your config has **motors** with these names (or change them)
|
||||||
|
// the encoders should be plugged into the slot matching the named motor
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
par = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par")));
|
||||||
|
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));
|
||||||
|
|
||||||
|
// TODO: reverse encoder directions if needed
|
||||||
|
// par.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
this.imu = imu;
|
||||||
|
|
||||||
|
this.inPerTick = inPerTick;
|
||||||
|
|
||||||
|
FlightRecorder.write("TWO_DEAD_WHEEL_PARAMS", PARAMS);
|
||||||
|
|
||||||
|
pose = initialPose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void setPose(Pose2d pose) {
|
||||||
|
this.pose = pose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public Pose2d getPose() {
|
||||||
|
return pose;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public PoseVelocity2d update() {
|
||||||
|
PositionVelocityPair parPosVel = par.getPositionAndVelocity();
|
||||||
|
PositionVelocityPair perpPosVel = perp.getPositionAndVelocity();
|
||||||
|
|
||||||
|
YawPitchRollAngles angles = imu.getRobotYawPitchRollAngles();
|
||||||
|
// Use degrees here to work around https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1070
|
||||||
|
AngularVelocity angularVelocityDegrees = imu.getRobotAngularVelocity(AngleUnit.DEGREES);
|
||||||
|
AngularVelocity angularVelocity = new AngularVelocity(
|
||||||
|
UnnormalizedAngleUnit.RADIANS,
|
||||||
|
(float) Math.toRadians(angularVelocityDegrees.xRotationRate),
|
||||||
|
(float) Math.toRadians(angularVelocityDegrees.yRotationRate),
|
||||||
|
(float) Math.toRadians(angularVelocityDegrees.zRotationRate),
|
||||||
|
angularVelocityDegrees.acquisitionTime
|
||||||
|
);
|
||||||
|
|
||||||
|
FlightRecorder.write("TWO_DEAD_WHEEL_INPUTS", new TwoDeadWheelInputsMessage(parPosVel, perpPosVel, angles, angularVelocity));
|
||||||
|
|
||||||
|
Rotation2d heading = Rotation2d.exp(angles.getYaw(AngleUnit.RADIANS));
|
||||||
|
|
||||||
|
// see https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/617
|
||||||
|
double rawHeadingVel = angularVelocity.zRotationRate;
|
||||||
|
if (Math.abs(rawHeadingVel - lastRawHeadingVel) > Math.PI) {
|
||||||
|
headingVelOffset -= Math.signum(rawHeadingVel) * 2 * Math.PI;
|
||||||
|
}
|
||||||
|
lastRawHeadingVel = rawHeadingVel;
|
||||||
|
double headingVel = headingVelOffset + rawHeadingVel;
|
||||||
|
|
||||||
|
if (!initialized) {
|
||||||
|
initialized = true;
|
||||||
|
|
||||||
|
lastParPos = parPosVel.position;
|
||||||
|
lastPerpPos = perpPosVel.position;
|
||||||
|
lastHeading = heading;
|
||||||
|
|
||||||
|
return new PoseVelocity2d(new Vector2d(0.0, 0.0), 0.0);
|
||||||
|
}
|
||||||
|
|
||||||
|
int parPosDelta = parPosVel.position - lastParPos;
|
||||||
|
int perpPosDelta = perpPosVel.position - lastPerpPos;
|
||||||
|
double headingDelta = heading.minus(lastHeading);
|
||||||
|
|
||||||
|
Twist2dDual<Time> twist = new Twist2dDual<>(
|
||||||
|
new Vector2dDual<>(
|
||||||
|
new DualNum<Time>(new double[] {
|
||||||
|
parPosDelta - PARAMS.parYTicks * headingDelta,
|
||||||
|
parPosVel.velocity - PARAMS.parYTicks * headingVel,
|
||||||
|
}).times(inPerTick),
|
||||||
|
new DualNum<Time>(new double[] {
|
||||||
|
perpPosDelta - PARAMS.perpXTicks * headingDelta,
|
||||||
|
perpPosVel.velocity - PARAMS.perpXTicks * headingVel,
|
||||||
|
}).times(inPerTick)
|
||||||
|
),
|
||||||
|
new DualNum<>(new double[] {
|
||||||
|
headingDelta,
|
||||||
|
headingVel,
|
||||||
|
})
|
||||||
|
);
|
||||||
|
|
||||||
|
lastParPos = parPosVel.position;
|
||||||
|
lastPerpPos = perpPosVel.position;
|
||||||
|
lastHeading = heading;
|
||||||
|
|
||||||
|
pose = pose.plus(twist.value());
|
||||||
|
return twist.velocity().value();
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,24 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.Time;
|
||||||
|
|
||||||
|
public final class DriveCommandMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public double forwardVelocity;
|
||||||
|
public double forwardAcceleration;
|
||||||
|
public double lateralVelocity;
|
||||||
|
public double lateralAcceleration;
|
||||||
|
public double angularVelocity;
|
||||||
|
public double angularAcceleration;
|
||||||
|
|
||||||
|
public DriveCommandMessage(PoseVelocity2dDual<Time> poseVelocity) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.forwardVelocity = poseVelocity.linearVel.x.get(0);
|
||||||
|
this.forwardAcceleration = poseVelocity.linearVel.x.get(1);
|
||||||
|
this.lateralVelocity = poseVelocity.linearVel.y.get(0);
|
||||||
|
this.lateralAcceleration = poseVelocity.linearVel.y.get(1);
|
||||||
|
this.angularVelocity = poseVelocity.angVel.get(0);
|
||||||
|
this.angularAcceleration = poseVelocity.angVel.get(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,19 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
public final class MecanumCommandMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public double voltage;
|
||||||
|
public double leftFrontPower;
|
||||||
|
public double leftBackPower;
|
||||||
|
public double rightBackPower;
|
||||||
|
public double rightFrontPower;
|
||||||
|
|
||||||
|
public MecanumCommandMessage(double voltage, double leftFrontPower, double leftBackPower, double rightBackPower, double rightFrontPower) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.voltage = voltage;
|
||||||
|
this.leftFrontPower = leftFrontPower;
|
||||||
|
this.leftBackPower = leftBackPower;
|
||||||
|
this.rightBackPower = rightBackPower;
|
||||||
|
this.rightFrontPower = rightFrontPower;
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,30 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
|
||||||
|
|
||||||
|
public final class MecanumLocalizerInputsMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public PositionVelocityPair leftFront;
|
||||||
|
public PositionVelocityPair leftBack;
|
||||||
|
public PositionVelocityPair rightBack;
|
||||||
|
public PositionVelocityPair rightFront;
|
||||||
|
public double yaw;
|
||||||
|
public double pitch;
|
||||||
|
public double roll;
|
||||||
|
|
||||||
|
public MecanumLocalizerInputsMessage(PositionVelocityPair leftFront, PositionVelocityPair leftBack, PositionVelocityPair rightBack, PositionVelocityPair rightFront, YawPitchRollAngles angles) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.leftFront = leftFront;
|
||||||
|
this.leftBack = leftBack;
|
||||||
|
this.rightBack = rightBack;
|
||||||
|
this.rightFront = rightFront;
|
||||||
|
{
|
||||||
|
this.yaw = angles.getYaw(AngleUnit.RADIANS);
|
||||||
|
this.pitch = angles.getPitch(AngleUnit.RADIANS);
|
||||||
|
this.roll = angles.getRoll(AngleUnit.RADIANS);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,18 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
|
||||||
|
public final class PoseMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public double x;
|
||||||
|
public double y;
|
||||||
|
public double heading;
|
||||||
|
|
||||||
|
public PoseMessage(Pose2d pose) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.x = pose.position.x;
|
||||||
|
this.y = pose.position.y;
|
||||||
|
this.heading = pose.heading.toDouble();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
@@ -0,0 +1,15 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
public final class TankCommandMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public double voltage;
|
||||||
|
public double leftPower;
|
||||||
|
public double rightPower;
|
||||||
|
|
||||||
|
public TankCommandMessage(double voltage, double leftPower, double rightPower) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.voltage = voltage;
|
||||||
|
this.leftPower = leftPower;
|
||||||
|
this.rightPower = rightPower;
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,17 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
public final class TankLocalizerInputsMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public PositionVelocityPair[] left;
|
||||||
|
public PositionVelocityPair[] right;
|
||||||
|
|
||||||
|
public TankLocalizerInputsMessage(List<PositionVelocityPair> left, List<PositionVelocityPair> right) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.left = left.toArray(new PositionVelocityPair[0]);
|
||||||
|
this.right = right.toArray(new PositionVelocityPair[0]);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,17 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
|
||||||
|
|
||||||
|
public final class ThreeDeadWheelInputsMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public PositionVelocityPair par0;
|
||||||
|
public PositionVelocityPair par1;
|
||||||
|
public PositionVelocityPair perp;
|
||||||
|
|
||||||
|
public ThreeDeadWheelInputsMessage(PositionVelocityPair par0, PositionVelocityPair par1, PositionVelocityPair perp) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.par0 = par0;
|
||||||
|
this.par1 = par1;
|
||||||
|
this.perp = perp;
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,35 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.messages;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngularVelocity;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
|
||||||
|
|
||||||
|
public final class TwoDeadWheelInputsMessage {
|
||||||
|
public long timestamp;
|
||||||
|
public PositionVelocityPair par;
|
||||||
|
public PositionVelocityPair perp;
|
||||||
|
public double yaw;
|
||||||
|
public double pitch;
|
||||||
|
public double roll;
|
||||||
|
public double xRotationRate;
|
||||||
|
public double yRotationRate;
|
||||||
|
public double zRotationRate;
|
||||||
|
|
||||||
|
public TwoDeadWheelInputsMessage(PositionVelocityPair par, PositionVelocityPair perp, YawPitchRollAngles angles, AngularVelocity angularVelocity) {
|
||||||
|
this.timestamp = System.nanoTime();
|
||||||
|
this.par = par;
|
||||||
|
this.perp = perp;
|
||||||
|
{
|
||||||
|
this.yaw = angles.getYaw(AngleUnit.RADIANS);
|
||||||
|
this.pitch = angles.getPitch(AngleUnit.RADIANS);
|
||||||
|
this.roll = angles.getRoll(AngleUnit.RADIANS);
|
||||||
|
}
|
||||||
|
{
|
||||||
|
this.xRotationRate = angularVelocity.xRotationRate;
|
||||||
|
this.yRotationRate = angularVelocity.yRotationRate;
|
||||||
|
this.zRotationRate = angularVelocity.zRotationRate;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,78 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.tuning;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.Drawing;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.TankDrive;
|
||||||
|
|
||||||
|
public class LocalizationTest extends LinearOpMode {
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
if (TuningOpModes.DRIVE_CLASS.equals(MecanumDrive.class)) {
|
||||||
|
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
drive.setDrivePowers(new PoseVelocity2d(
|
||||||
|
new Vector2d(
|
||||||
|
-gamepad1.left_stick_y,
|
||||||
|
-gamepad1.left_stick_x
|
||||||
|
),
|
||||||
|
-gamepad1.right_stick_x
|
||||||
|
));
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
Pose2d pose = drive.localizer.getPose();
|
||||||
|
telemetry.addData("x", pose.position.x);
|
||||||
|
telemetry.addData("y", pose.position.y);
|
||||||
|
telemetry.addData("heading (deg)", Math.toDegrees(pose.heading.toDouble()));
|
||||||
|
telemetry.update();
|
||||||
|
|
||||||
|
TelemetryPacket packet = new TelemetryPacket();
|
||||||
|
packet.fieldOverlay().setStroke("#3F51B5");
|
||||||
|
Drawing.drawRobot(packet.fieldOverlay(), pose);
|
||||||
|
FtcDashboard.getInstance().sendTelemetryPacket(packet);
|
||||||
|
}
|
||||||
|
} else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) {
|
||||||
|
TankDrive drive = new TankDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
drive.setDrivePowers(new PoseVelocity2d(
|
||||||
|
new Vector2d(
|
||||||
|
-gamepad1.left_stick_y,
|
||||||
|
0.0
|
||||||
|
),
|
||||||
|
-gamepad1.right_stick_x
|
||||||
|
));
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
Pose2d pose = drive.localizer.getPose();
|
||||||
|
telemetry.addData("x", pose.position.x);
|
||||||
|
telemetry.addData("y", pose.position.y);
|
||||||
|
telemetry.addData("heading (deg)", Math.toDegrees(pose.heading.toDouble()));
|
||||||
|
telemetry.update();
|
||||||
|
|
||||||
|
TelemetryPacket packet = new TelemetryPacket();
|
||||||
|
packet.fieldOverlay().setStroke("#3F51B5");
|
||||||
|
Drawing.drawRobot(packet.fieldOverlay(), pose);
|
||||||
|
FtcDashboard.getInstance().sendTelemetryPacket(packet);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
throw new RuntimeException();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,63 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.tuning;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.TankDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.ThreeDeadWheelLocalizer;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.TwoDeadWheelLocalizer;
|
||||||
|
|
||||||
|
public final class ManualFeedbackTuner extends LinearOpMode {
|
||||||
|
public static double DISTANCE = 64;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
if (TuningOpModes.DRIVE_CLASS.equals(MecanumDrive.class)) {
|
||||||
|
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
|
||||||
|
if (drive.localizer instanceof TwoDeadWheelLocalizer) {
|
||||||
|
if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) {
|
||||||
|
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
|
||||||
|
}
|
||||||
|
} else if (drive.localizer instanceof ThreeDeadWheelLocalizer) {
|
||||||
|
if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) {
|
||||||
|
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
Actions.runBlocking(
|
||||||
|
drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.lineToX(DISTANCE)
|
||||||
|
.lineToX(0)
|
||||||
|
.build());
|
||||||
|
}
|
||||||
|
} else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) {
|
||||||
|
TankDrive drive = new TankDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
|
||||||
|
if (drive.localizer instanceof TwoDeadWheelLocalizer) {
|
||||||
|
if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) {
|
||||||
|
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
|
||||||
|
}
|
||||||
|
} else if (drive.localizer instanceof ThreeDeadWheelLocalizer) {
|
||||||
|
if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) {
|
||||||
|
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
Actions.runBlocking(
|
||||||
|
drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.lineToX(DISTANCE)
|
||||||
|
.lineToX(0)
|
||||||
|
.build());
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
throw new RuntimeException();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,39 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.tuning;
|
||||||
|
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.TankDrive;
|
||||||
|
|
||||||
|
public final class SplineTest extends LinearOpMode {
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
Pose2d beginPose = new Pose2d(0, 0, 0);
|
||||||
|
if (TuningOpModes.DRIVE_CLASS.equals(MecanumDrive.class)) {
|
||||||
|
MecanumDrive drive = new MecanumDrive(hardwareMap, beginPose);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
drive.actionBuilder(beginPose)
|
||||||
|
.splineTo(new Vector2d(30, 30), Math.PI / 2)
|
||||||
|
.splineTo(new Vector2d(0, 60), Math.PI)
|
||||||
|
.build());
|
||||||
|
} else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) {
|
||||||
|
TankDrive drive = new TankDrive(hardwareMap, beginPose);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
drive.actionBuilder(beginPose)
|
||||||
|
.splineTo(new Vector2d(30, 30), Math.PI / 2)
|
||||||
|
.splineTo(new Vector2d(0, 60), Math.PI)
|
||||||
|
.build());
|
||||||
|
} else {
|
||||||
|
throw new RuntimeException();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,321 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.libs.RR.tuning;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.reflection.ReflectionConfig;
|
||||||
|
import com.acmerobotics.roadrunner.MotorFeedforward;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.AngularRampLogger;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.DeadWheelDirectionDebugger;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.DriveType;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.DriveView;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.DriveViewFactory;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.EncoderGroup;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.EncoderRef;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.ForwardPushTest;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.ForwardRampLogger;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.LateralPushTest;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.LateralRampLogger;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.LazyImu;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.LynxQuadratureEncoderGroup;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.ManualFeedforwardTuner;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.MecanumMotorDirectionDebugger;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSAngularScalarTuner;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSEncoderGroup;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSHeadingOffsetTuner;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSIMU;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSLinearScalarTuner;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.OTOSPositionOffsetTuner;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PinpointEncoderGroup;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PinpointIMU;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PinpointView;
|
||||||
|
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
|
||||||
|
import com.qualcomm.hardware.lynx.LynxModule;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.OpModeManager;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.OpModeRegistrar;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.UnnormalizedAngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.internal.opmode.OpModeMeta;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.OTOSLocalizer;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.PinpointLocalizer;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.TankDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.ThreeDeadWheelLocalizer;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.TwoDeadWheelLocalizer;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.Arrays;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
public final class TuningOpModes {
|
||||||
|
// TODO: change this to TankDrive.class if you're using tank
|
||||||
|
public static final Class<?> DRIVE_CLASS = MecanumDrive.class;
|
||||||
|
|
||||||
|
public static final String GROUP = "quickstart";
|
||||||
|
public static final boolean DISABLED = false;
|
||||||
|
|
||||||
|
private TuningOpModes() {}
|
||||||
|
|
||||||
|
private static OpModeMeta metaForClass(Class<? extends OpMode> cls) {
|
||||||
|
return new OpModeMeta.Builder()
|
||||||
|
.setName(cls.getSimpleName())
|
||||||
|
.setGroup(GROUP)
|
||||||
|
.setFlavor(OpModeMeta.Flavor.TELEOP)
|
||||||
|
.build();
|
||||||
|
}
|
||||||
|
|
||||||
|
private static PinpointView makePinpointView(PinpointLocalizer pl) {
|
||||||
|
return new PinpointView() {
|
||||||
|
GoBildaPinpointDriver.EncoderDirection parDirection = pl.initialParDirection;
|
||||||
|
GoBildaPinpointDriver.EncoderDirection perpDirection = pl.initialPerpDirection;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
pl.driver.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public int getParEncoderPosition() {
|
||||||
|
return pl.driver.getEncoderX();
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public int getPerpEncoderPosition() {
|
||||||
|
return pl.driver.getEncoderY();
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public float getHeadingVelocity(UnnormalizedAngleUnit unit) {
|
||||||
|
return (float) pl.driver.getHeadingVelocity(unit);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void setParDirection(@NonNull DcMotorSimple.Direction direction) {
|
||||||
|
parDirection = direction == DcMotorSimple.Direction.FORWARD ?
|
||||||
|
GoBildaPinpointDriver.EncoderDirection.FORWARD :
|
||||||
|
GoBildaPinpointDriver.EncoderDirection.REVERSED;
|
||||||
|
pl.driver.setEncoderDirections(parDirection, perpDirection);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public DcMotorSimple.Direction getParDirection() {
|
||||||
|
return parDirection == GoBildaPinpointDriver.EncoderDirection.FORWARD ?
|
||||||
|
DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void setPerpDirection(@NonNull DcMotorSimple.Direction direction) {
|
||||||
|
perpDirection = direction == DcMotorSimple.Direction.FORWARD ?
|
||||||
|
GoBildaPinpointDriver.EncoderDirection.FORWARD :
|
||||||
|
GoBildaPinpointDriver.EncoderDirection.REVERSED;
|
||||||
|
pl.driver.setEncoderDirections(parDirection, perpDirection);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public DcMotorSimple.Direction getPerpDirection() {
|
||||||
|
return perpDirection == GoBildaPinpointDriver.EncoderDirection.FORWARD ?
|
||||||
|
DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@OpModeRegistrar
|
||||||
|
public static void register(OpModeManager manager) {
|
||||||
|
if (DISABLED) return;
|
||||||
|
|
||||||
|
DriveViewFactory dvf;
|
||||||
|
if (DRIVE_CLASS.equals(MecanumDrive.class)) {
|
||||||
|
dvf = hardwareMap -> {
|
||||||
|
MecanumDrive md = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
LazyImu lazyImu = md.lazyImu;
|
||||||
|
|
||||||
|
List<EncoderGroup> encoderGroups = new ArrayList<>();
|
||||||
|
List<EncoderRef> leftEncs = new ArrayList<>(), rightEncs = new ArrayList<>();
|
||||||
|
List<EncoderRef> parEncs = new ArrayList<>(), perpEncs = new ArrayList<>();
|
||||||
|
if (md.localizer instanceof MecanumDrive.DriveLocalizer) {
|
||||||
|
MecanumDrive.DriveLocalizer dl = (MecanumDrive.DriveLocalizer) md.localizer;
|
||||||
|
encoderGroups.add(new LynxQuadratureEncoderGroup(
|
||||||
|
hardwareMap.getAll(LynxModule.class),
|
||||||
|
Arrays.asList(dl.leftFront, dl.leftBack, dl.rightFront, dl.rightBack)
|
||||||
|
));
|
||||||
|
leftEncs.add(new EncoderRef(0, 0));
|
||||||
|
leftEncs.add(new EncoderRef(0, 1));
|
||||||
|
rightEncs.add(new EncoderRef(0, 2));
|
||||||
|
rightEncs.add(new EncoderRef(0, 3));
|
||||||
|
} else if (md.localizer instanceof ThreeDeadWheelLocalizer) {
|
||||||
|
ThreeDeadWheelLocalizer dl = (ThreeDeadWheelLocalizer) md.localizer;
|
||||||
|
encoderGroups.add(new LynxQuadratureEncoderGroup(
|
||||||
|
hardwareMap.getAll(LynxModule.class),
|
||||||
|
Arrays.asList(dl.par0, dl.par1, dl.perp)
|
||||||
|
));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
parEncs.add(new EncoderRef(0, 1));
|
||||||
|
perpEncs.add(new EncoderRef(0, 2));
|
||||||
|
} else if (md.localizer instanceof TwoDeadWheelLocalizer) {
|
||||||
|
TwoDeadWheelLocalizer dl = (TwoDeadWheelLocalizer) md.localizer;
|
||||||
|
encoderGroups.add(new LynxQuadratureEncoderGroup(
|
||||||
|
hardwareMap.getAll(LynxModule.class),
|
||||||
|
Arrays.asList(dl.par, dl.perp)
|
||||||
|
));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
perpEncs.add(new EncoderRef(0, 1));
|
||||||
|
} else if (md.localizer instanceof OTOSLocalizer) {
|
||||||
|
OTOSLocalizer ol = (OTOSLocalizer) md.localizer;
|
||||||
|
encoderGroups.add(new OTOSEncoderGroup(ol.otos));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
perpEncs.add(new EncoderRef(0, 1));
|
||||||
|
lazyImu = new OTOSIMU(ol.otos);
|
||||||
|
} else if (md.localizer instanceof PinpointLocalizer) {
|
||||||
|
PinpointView pv = makePinpointView((PinpointLocalizer) md.localizer);
|
||||||
|
encoderGroups.add(new PinpointEncoderGroup(pv));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
perpEncs.add(new EncoderRef(0, 1));
|
||||||
|
lazyImu = new PinpointIMU(pv);
|
||||||
|
} else {
|
||||||
|
throw new RuntimeException("unknown localizer: " + md.localizer.getClass().getName());
|
||||||
|
}
|
||||||
|
|
||||||
|
return new DriveView(
|
||||||
|
DriveType.MECANUM,
|
||||||
|
MecanumDrive.PARAMS.inPerTick,
|
||||||
|
MecanumDrive.PARAMS.maxWheelVel,
|
||||||
|
MecanumDrive.PARAMS.minProfileAccel,
|
||||||
|
MecanumDrive.PARAMS.maxProfileAccel,
|
||||||
|
encoderGroups,
|
||||||
|
Arrays.asList(
|
||||||
|
md.leftFront,
|
||||||
|
md.leftBack
|
||||||
|
),
|
||||||
|
Arrays.asList(
|
||||||
|
md.rightFront,
|
||||||
|
md.rightBack
|
||||||
|
),
|
||||||
|
leftEncs,
|
||||||
|
rightEncs,
|
||||||
|
parEncs,
|
||||||
|
perpEncs,
|
||||||
|
lazyImu,
|
||||||
|
md.voltageSensor,
|
||||||
|
() -> new MotorFeedforward(MecanumDrive.PARAMS.kS,
|
||||||
|
MecanumDrive.PARAMS.kV / MecanumDrive.PARAMS.inPerTick,
|
||||||
|
MecanumDrive.PARAMS.kA / MecanumDrive.PARAMS.inPerTick),
|
||||||
|
0
|
||||||
|
);
|
||||||
|
};
|
||||||
|
} else if (DRIVE_CLASS.equals(TankDrive.class)) {
|
||||||
|
dvf = hardwareMap -> {
|
||||||
|
TankDrive td = new TankDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
LazyImu lazyImu = td.lazyImu;
|
||||||
|
|
||||||
|
List<EncoderGroup> encoderGroups = new ArrayList<>();
|
||||||
|
List<EncoderRef> leftEncs = new ArrayList<>(), rightEncs = new ArrayList<>();
|
||||||
|
List<EncoderRef> parEncs = new ArrayList<>(), perpEncs = new ArrayList<>();
|
||||||
|
if (td.localizer instanceof TankDrive.DriveLocalizer) {
|
||||||
|
TankDrive.DriveLocalizer dl = (TankDrive.DriveLocalizer) td.localizer;
|
||||||
|
List<Encoder> allEncoders = new ArrayList<>();
|
||||||
|
allEncoders.addAll(dl.leftEncs);
|
||||||
|
allEncoders.addAll(dl.rightEncs);
|
||||||
|
encoderGroups.add(new LynxQuadratureEncoderGroup(
|
||||||
|
hardwareMap.getAll(LynxModule.class),
|
||||||
|
allEncoders
|
||||||
|
));
|
||||||
|
for (int i = 0; i < dl.leftEncs.size(); i++) {
|
||||||
|
leftEncs.add(new EncoderRef(0, i));
|
||||||
|
}
|
||||||
|
for (int i = 0; i < dl.rightEncs.size(); i++) {
|
||||||
|
rightEncs.add(new EncoderRef(0, dl.leftEncs.size() + i));
|
||||||
|
}
|
||||||
|
} else if (td.localizer instanceof ThreeDeadWheelLocalizer) {
|
||||||
|
ThreeDeadWheelLocalizer dl = (ThreeDeadWheelLocalizer) td.localizer;
|
||||||
|
encoderGroups.add(new LynxQuadratureEncoderGroup(
|
||||||
|
hardwareMap.getAll(LynxModule.class),
|
||||||
|
Arrays.asList(dl.par0, dl.par1, dl.perp)
|
||||||
|
));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
parEncs.add(new EncoderRef(0, 1));
|
||||||
|
perpEncs.add(new EncoderRef(0, 2));
|
||||||
|
} else if (td.localizer instanceof TwoDeadWheelLocalizer) {
|
||||||
|
TwoDeadWheelLocalizer dl = (TwoDeadWheelLocalizer) td.localizer;
|
||||||
|
encoderGroups.add(new LynxQuadratureEncoderGroup(
|
||||||
|
hardwareMap.getAll(LynxModule.class),
|
||||||
|
Arrays.asList(dl.par, dl.perp)
|
||||||
|
));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
perpEncs.add(new EncoderRef(0, 1));
|
||||||
|
} else if (td.localizer instanceof PinpointLocalizer) {
|
||||||
|
PinpointView pv = makePinpointView((PinpointLocalizer) td.localizer);
|
||||||
|
encoderGroups.add(new PinpointEncoderGroup(pv));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
perpEncs.add(new EncoderRef(0, 1));
|
||||||
|
lazyImu = new PinpointIMU(pv);
|
||||||
|
} else if (td.localizer instanceof OTOSLocalizer) {
|
||||||
|
OTOSLocalizer ol = (OTOSLocalizer) td.localizer;
|
||||||
|
encoderGroups.add(new OTOSEncoderGroup(ol.otos));
|
||||||
|
parEncs.add(new EncoderRef(0, 0));
|
||||||
|
perpEncs.add(new EncoderRef(0, 1));
|
||||||
|
lazyImu = new OTOSIMU(ol.otos);
|
||||||
|
} else {
|
||||||
|
throw new RuntimeException("unknown localizer: " + td.localizer.getClass().getName());
|
||||||
|
}
|
||||||
|
|
||||||
|
return new DriveView(
|
||||||
|
DriveType.TANK,
|
||||||
|
TankDrive.PARAMS.inPerTick,
|
||||||
|
TankDrive.PARAMS.maxWheelVel,
|
||||||
|
TankDrive.PARAMS.minProfileAccel,
|
||||||
|
TankDrive.PARAMS.maxProfileAccel,
|
||||||
|
encoderGroups,
|
||||||
|
td.leftMotors,
|
||||||
|
td.rightMotors,
|
||||||
|
leftEncs,
|
||||||
|
rightEncs,
|
||||||
|
parEncs,
|
||||||
|
perpEncs,
|
||||||
|
lazyImu,
|
||||||
|
td.voltageSensor,
|
||||||
|
() -> new MotorFeedforward(TankDrive.PARAMS.kS,
|
||||||
|
TankDrive.PARAMS.kV / TankDrive.PARAMS.inPerTick,
|
||||||
|
TankDrive.PARAMS.kA / TankDrive.PARAMS.inPerTick),
|
||||||
|
0
|
||||||
|
);
|
||||||
|
};
|
||||||
|
} else {
|
||||||
|
throw new RuntimeException();
|
||||||
|
}
|
||||||
|
|
||||||
|
manager.register(metaForClass(AngularRampLogger.class), new AngularRampLogger(dvf));
|
||||||
|
manager.register(metaForClass(ForwardPushTest.class), new ForwardPushTest(dvf));
|
||||||
|
manager.register(metaForClass(ForwardRampLogger.class), new ForwardRampLogger(dvf));
|
||||||
|
manager.register(metaForClass(LateralPushTest.class), new LateralPushTest(dvf));
|
||||||
|
manager.register(metaForClass(LateralRampLogger.class), new LateralRampLogger(dvf));
|
||||||
|
manager.register(metaForClass(ManualFeedforwardTuner.class), new ManualFeedforwardTuner(dvf));
|
||||||
|
manager.register(metaForClass(MecanumMotorDirectionDebugger.class), new MecanumMotorDirectionDebugger(dvf));
|
||||||
|
manager.register(metaForClass(DeadWheelDirectionDebugger.class), new DeadWheelDirectionDebugger(dvf));
|
||||||
|
|
||||||
|
manager.register(metaForClass(ManualFeedbackTuner.class), ManualFeedbackTuner.class);
|
||||||
|
manager.register(metaForClass(SplineTest.class), SplineTest.class);
|
||||||
|
manager.register(metaForClass(LocalizationTest.class), LocalizationTest.class);
|
||||||
|
|
||||||
|
manager.register(metaForClass(OTOSAngularScalarTuner.class), new OTOSAngularScalarTuner(dvf));
|
||||||
|
manager.register(metaForClass(OTOSLinearScalarTuner.class), new OTOSLinearScalarTuner(dvf));
|
||||||
|
manager.register(metaForClass(OTOSHeadingOffsetTuner.class), new OTOSHeadingOffsetTuner(dvf));
|
||||||
|
manager.register(metaForClass(OTOSPositionOffsetTuner.class), new OTOSPositionOffsetTuner(dvf));
|
||||||
|
|
||||||
|
FtcDashboard.getInstance().withConfigRoot(configRoot -> {
|
||||||
|
for (Class<?> c : Arrays.asList(
|
||||||
|
AngularRampLogger.class,
|
||||||
|
ForwardRampLogger.class,
|
||||||
|
LateralRampLogger.class,
|
||||||
|
ManualFeedforwardTuner.class,
|
||||||
|
MecanumMotorDirectionDebugger.class,
|
||||||
|
ManualFeedbackTuner.class
|
||||||
|
)) {
|
||||||
|
configRoot.putVariable(c.getSimpleName(), ReflectionConfig.createVariableFromClass(c));
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -21,7 +21,7 @@ apply plugin: 'com.android.application'
|
|||||||
|
|
||||||
android {
|
android {
|
||||||
|
|
||||||
compileSdkVersion 30
|
compileSdkVersion 34
|
||||||
|
|
||||||
signingConfigs {
|
signingConfigs {
|
||||||
release {
|
release {
|
||||||
|
|||||||
@@ -3,6 +3,7 @@ repositories {
|
|||||||
google() // Needed for androidx
|
google() // Needed for androidx
|
||||||
maven { url = 'https://maven.pedropathing.com' } //Pedro
|
maven { url = 'https://maven.pedropathing.com' } //Pedro
|
||||||
maven { url = "https://mymaven.bylazar.com/releases" } //Panels
|
maven { url = "https://mymaven.bylazar.com/releases" } //Panels
|
||||||
|
maven { url = 'https://maven.brott.dev/' } //RR
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
@@ -21,6 +22,11 @@ dependencies {
|
|||||||
|
|
||||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||||
|
|
||||||
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
||||||
|
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
||||||
|
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
||||||
|
implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user