Add Roadrunner
This commit is contained in:
70
TeamCode/util/AssetsTrajectoryManager.java
Normal file
70
TeamCode/util/AssetsTrajectoryManager.java
Normal file
@ -0,0 +1,70 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import androidx.annotation.Nullable;
|
||||
|
||||
import com.acmerobotics.roadrunner.trajectory.Trajectory;
|
||||
import com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder;
|
||||
import com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig;
|
||||
import com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager;
|
||||
import com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.internal.system.AppUtil;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.io.InputStream;
|
||||
|
||||
/**
|
||||
* Set of utilities for loading trajectories from assets (the plugin save location).
|
||||
*/
|
||||
public class AssetsTrajectoryManager {
|
||||
|
||||
/**
|
||||
* Loads the group config.
|
||||
*/
|
||||
public static @Nullable
|
||||
TrajectoryGroupConfig loadGroupConfig() {
|
||||
try {
|
||||
InputStream inputStream = AppUtil.getDefContext().getAssets().open(
|
||||
"trajectory/" + TrajectoryConfigManager.GROUP_FILENAME);
|
||||
return TrajectoryConfigManager.loadGroupConfig(inputStream);
|
||||
} catch (IOException e) {
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Loads a trajectory config with the given name.
|
||||
*/
|
||||
public static @Nullable TrajectoryConfig loadConfig(String name) {
|
||||
try {
|
||||
InputStream inputStream = AppUtil.getDefContext().getAssets().open(
|
||||
"trajectory/" + name + ".yaml");
|
||||
return TrajectoryConfigManager.loadConfig(inputStream);
|
||||
} catch (IOException e) {
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Loads a trajectory builder with the given name.
|
||||
*/
|
||||
public static @Nullable TrajectoryBuilder loadBuilder(String name) {
|
||||
TrajectoryGroupConfig groupConfig = loadGroupConfig();
|
||||
TrajectoryConfig config = loadConfig(name);
|
||||
if (groupConfig == null || config == null) {
|
||||
return null;
|
||||
}
|
||||
return config.toTrajectoryBuilder(groupConfig);
|
||||
}
|
||||
|
||||
/**
|
||||
* Loads a trajectory with the given name.
|
||||
*/
|
||||
public static @Nullable Trajectory load(String name) {
|
||||
TrajectoryBuilder builder = loadBuilder(name);
|
||||
if (builder == null) {
|
||||
return null;
|
||||
}
|
||||
return builder.build();
|
||||
}
|
||||
}
|
45
TeamCode/util/AxesSigns.java
Normal file
45
TeamCode/util/AxesSigns.java
Normal file
@ -0,0 +1,45 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
/**
|
||||
* IMU axes signs in the order XYZ (after remapping).
|
||||
*/
|
||||
public enum AxesSigns {
|
||||
PPP(0b000),
|
||||
PPN(0b001),
|
||||
PNP(0b010),
|
||||
PNN(0b011),
|
||||
NPP(0b100),
|
||||
NPN(0b101),
|
||||
NNP(0b110),
|
||||
NNN(0b111);
|
||||
|
||||
public final int bVal;
|
||||
|
||||
AxesSigns(int bVal) {
|
||||
this.bVal = bVal;
|
||||
}
|
||||
|
||||
public static AxesSigns fromBinaryValue(int bVal) {
|
||||
int maskedVal = bVal & 0x07;
|
||||
switch (maskedVal) {
|
||||
case 0b000:
|
||||
return AxesSigns.PPP;
|
||||
case 0b001:
|
||||
return AxesSigns.PPN;
|
||||
case 0b010:
|
||||
return AxesSigns.PNP;
|
||||
case 0b011:
|
||||
return AxesSigns.PNN;
|
||||
case 0b100:
|
||||
return AxesSigns.NPP;
|
||||
case 0b101:
|
||||
return AxesSigns.NPN;
|
||||
case 0b110:
|
||||
return AxesSigns.NNP;
|
||||
case 0b111:
|
||||
return AxesSigns.NNN;
|
||||
default:
|
||||
throw new IllegalStateException("Unexpected value for maskedVal: " + maskedVal);
|
||||
}
|
||||
}
|
||||
}
|
8
TeamCode/util/AxisDirection.java
Normal file
8
TeamCode/util/AxisDirection.java
Normal file
@ -0,0 +1,8 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
/**
|
||||
* A direction for an axis to be remapped to
|
||||
*/
|
||||
public enum AxisDirection {
|
||||
POS_X, NEG_X, POS_Y, NEG_Y, POS_Z, NEG_Z
|
||||
}
|
54
TeamCode/util/DashboardUtil.java
Normal file
54
TeamCode/util/DashboardUtil.java
Normal file
@ -0,0 +1,54 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||
import com.acmerobotics.roadrunner.geometry.Pose2d;
|
||||
import com.acmerobotics.roadrunner.geometry.Vector2d;
|
||||
import com.acmerobotics.roadrunner.path.Path;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
/**
|
||||
* Set of helper functions for drawing Road Runner paths and trajectories on dashboard canvases.
|
||||
*/
|
||||
public class DashboardUtil {
|
||||
private static final double DEFAULT_RESOLUTION = 2.0; // distance units; presumed inches
|
||||
private static final double ROBOT_RADIUS = 9; // in
|
||||
|
||||
|
||||
public static void drawPoseHistory(Canvas canvas, List<Pose2d> poseHistory) {
|
||||
double[] xPoints = new double[poseHistory.size()];
|
||||
double[] yPoints = new double[poseHistory.size()];
|
||||
for (int i = 0; i < poseHistory.size(); i++) {
|
||||
Pose2d pose = poseHistory.get(i);
|
||||
xPoints[i] = pose.getX();
|
||||
yPoints[i] = pose.getY();
|
||||
}
|
||||
canvas.strokePolyline(xPoints, yPoints);
|
||||
}
|
||||
|
||||
public static void drawSampledPath(Canvas canvas, Path path, double resolution) {
|
||||
int samples = (int) Math.ceil(path.length() / resolution);
|
||||
double[] xPoints = new double[samples];
|
||||
double[] yPoints = new double[samples];
|
||||
double dx = path.length() / (samples - 1);
|
||||
for (int i = 0; i < samples; i++) {
|
||||
double displacement = i * dx;
|
||||
Pose2d pose = path.get(displacement);
|
||||
xPoints[i] = pose.getX();
|
||||
yPoints[i] = pose.getY();
|
||||
}
|
||||
canvas.strokePolyline(xPoints, yPoints);
|
||||
}
|
||||
|
||||
public static void drawSampledPath(Canvas canvas, Path path) {
|
||||
drawSampledPath(canvas, path, DEFAULT_RESOLUTION);
|
||||
}
|
||||
|
||||
public static void drawRobot(Canvas canvas, Pose2d pose) {
|
||||
canvas.strokeCircle(pose.getX(), pose.getY(), ROBOT_RADIUS);
|
||||
Vector2d v = pose.headingVec().times(ROBOT_RADIUS);
|
||||
double x1 = pose.getX() + v.getX() / 2, y1 = pose.getY() + v.getY() / 2;
|
||||
double x2 = pose.getX() + v.getX(), y2 = pose.getY() + v.getY();
|
||||
canvas.strokeLine(x1, y1, x2, y2);
|
||||
}
|
||||
}
|
125
TeamCode/util/Encoder.java
Normal file
125
TeamCode/util/Encoder.java
Normal file
@ -0,0 +1,125 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import com.acmerobotics.roadrunner.util.NanoClock;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
|
||||
/**
|
||||
* Wraps a motor instance to provide corrected velocity counts and allow reversing independently of the corresponding
|
||||
* slot's motor direction
|
||||
*/
|
||||
public class Encoder {
|
||||
private final static int CPS_STEP = 0x10000;
|
||||
|
||||
private static double inverseOverflow(double input, double estimate) {
|
||||
// convert to uint16
|
||||
int real = (int) input & 0xffff;
|
||||
// initial, modulo-based correction: it can recover the remainder of 5 of the upper 16 bits
|
||||
// because the velocity is always a multiple of 20 cps due to Expansion Hub's 50ms measurement window
|
||||
real += ((real % 20) / 4) * CPS_STEP;
|
||||
// estimate-based correction: it finds the nearest multiple of 5 to correct the upper bits by
|
||||
real += Math.round((estimate - real) / (5 * CPS_STEP)) * 5 * CPS_STEP;
|
||||
return real;
|
||||
}
|
||||
|
||||
public enum Direction {
|
||||
FORWARD(1),
|
||||
REVERSE(-1);
|
||||
|
||||
private int multiplier;
|
||||
|
||||
Direction(int multiplier) {
|
||||
this.multiplier = multiplier;
|
||||
}
|
||||
|
||||
public int getMultiplier() {
|
||||
return multiplier;
|
||||
}
|
||||
}
|
||||
|
||||
private DcMotorEx motor;
|
||||
private NanoClock clock;
|
||||
|
||||
private Direction direction;
|
||||
|
||||
private int lastPosition;
|
||||
private int velocityEstimateIdx;
|
||||
private double[] velocityEstimates;
|
||||
private double lastUpdateTime;
|
||||
|
||||
public Encoder(DcMotorEx motor, NanoClock clock) {
|
||||
this.motor = motor;
|
||||
this.clock = clock;
|
||||
|
||||
this.direction = Direction.FORWARD;
|
||||
|
||||
this.lastPosition = 0;
|
||||
this.velocityEstimates = new double[3];
|
||||
this.lastUpdateTime = clock.seconds();
|
||||
}
|
||||
|
||||
public Encoder(DcMotorEx motor) {
|
||||
this(motor, NanoClock.system());
|
||||
}
|
||||
|
||||
public Direction getDirection() {
|
||||
return direction;
|
||||
}
|
||||
|
||||
private int getMultiplier() {
|
||||
return getDirection().getMultiplier() * (motor.getDirection() == DcMotorSimple.Direction.FORWARD ? 1 : -1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Allows you to set the direction of the counts and velocity without modifying the motor's direction state
|
||||
* @param direction either reverse or forward depending on if encoder counts should be negated
|
||||
*/
|
||||
public void setDirection(Direction direction) {
|
||||
this.direction = direction;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the position from the underlying motor and adjusts for the set direction.
|
||||
* Additionally, this method updates the velocity estimates used for compensated velocity
|
||||
*
|
||||
* @return encoder position
|
||||
*/
|
||||
public int getCurrentPosition() {
|
||||
int multiplier = getMultiplier();
|
||||
int currentPosition = motor.getCurrentPosition() * multiplier;
|
||||
if (currentPosition != lastPosition) {
|
||||
double currentTime = clock.seconds();
|
||||
double dt = currentTime - lastUpdateTime;
|
||||
velocityEstimates[velocityEstimateIdx] = (currentPosition - lastPosition) / dt;
|
||||
velocityEstimateIdx = (velocityEstimateIdx + 1) % 3;
|
||||
lastPosition = currentPosition;
|
||||
lastUpdateTime = currentTime;
|
||||
}
|
||||
return currentPosition;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the velocity directly from the underlying motor and compensates for the direction
|
||||
* See {@link #getCorrectedVelocity} for high (>2^15) counts per second velocities (such as on REV Through Bore)
|
||||
*
|
||||
* @return raw velocity
|
||||
*/
|
||||
public double getRawVelocity() {
|
||||
int multiplier = getMultiplier();
|
||||
return motor.getVelocity() * multiplier;
|
||||
}
|
||||
|
||||
/**
|
||||
* Uses velocity estimates gathered in {@link #getCurrentPosition} to estimate the upper bits of velocity
|
||||
* that are lost in overflow due to velocity being transmitted as 16 bits.
|
||||
* CAVEAT: must regularly call {@link #getCurrentPosition} for the compensation to work correctly.
|
||||
*
|
||||
* @return corrected velocity
|
||||
*/
|
||||
public double getCorrectedVelocity() {
|
||||
double median = velocityEstimates[0] > velocityEstimates[1]
|
||||
? Math.max(velocityEstimates[1], Math.min(velocityEstimates[0], velocityEstimates[2]))
|
||||
: Math.max(velocityEstimates[0], Math.min(velocityEstimates[1], velocityEstimates[2]));
|
||||
return inverseOverflow(getRawVelocity(), median);
|
||||
}
|
||||
}
|
273
TeamCode/util/LogFiles.java
Normal file
273
TeamCode/util/LogFiles.java
Normal file
@ -0,0 +1,273 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import android.annotation.SuppressLint;
|
||||
import android.content.Context;
|
||||
|
||||
import com.acmerobotics.roadrunner.geometry.Pose2d;
|
||||
import com.fasterxml.jackson.core.JsonFactory;
|
||||
import com.fasterxml.jackson.databind.ObjectMapper;
|
||||
import com.fasterxml.jackson.databind.ObjectWriter;
|
||||
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpModeManagerImpl;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpModeManagerNotifier;
|
||||
import com.qualcomm.robotcore.util.RobotLog;
|
||||
import com.qualcomm.robotcore.util.WebHandlerManager;
|
||||
|
||||
import org.firstinspires.ftc.ftccommon.external.WebHandlerRegistrar;
|
||||
import org.firstinspires.ftc.robotcore.internal.system.AppUtil;
|
||||
import org.firstinspires.ftc.teamcode.drive.DriveConstants;
|
||||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.drive.SampleTankDrive;
|
||||
import org.firstinspires.ftc.teamcode.drive.StandardTrackingWheelLocalizer;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.FileInputStream;
|
||||
import java.io.IOException;
|
||||
import java.text.DateFormat;
|
||||
import java.text.SimpleDateFormat;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.Date;
|
||||
import java.util.List;
|
||||
import java.util.Objects;
|
||||
|
||||
import fi.iki.elonen.NanoHTTPD;
|
||||
|
||||
public final class LogFiles {
|
||||
private static final File ROOT =
|
||||
new File(AppUtil.ROOT_FOLDER + "/RoadRunner/logs/");
|
||||
|
||||
public static LogFile log = new LogFile("uninitialized");
|
||||
|
||||
public static class LogFile {
|
||||
public String version = "quickstart1 v2";
|
||||
|
||||
public String opModeName;
|
||||
public long msInit = System.currentTimeMillis();
|
||||
public long nsInit = System.nanoTime();
|
||||
public long nsStart, nsStop;
|
||||
|
||||
public double ticksPerRev = DriveConstants.TICKS_PER_REV;
|
||||
public double maxRpm = DriveConstants.MAX_RPM;
|
||||
public boolean runUsingEncoder = DriveConstants.RUN_USING_ENCODER;
|
||||
public double motorP = DriveConstants.MOTOR_VELO_PID.p;
|
||||
public double motorI = DriveConstants.MOTOR_VELO_PID.i;
|
||||
public double motorD = DriveConstants.MOTOR_VELO_PID.d;
|
||||
public double motorF = DriveConstants.MOTOR_VELO_PID.f;
|
||||
public double wheelRadius = DriveConstants.WHEEL_RADIUS;
|
||||
public double gearRatio = DriveConstants.GEAR_RATIO;
|
||||
public double trackWidth = DriveConstants.TRACK_WIDTH;
|
||||
public double kV = DriveConstants.kV;
|
||||
public double kA = DriveConstants.kA;
|
||||
public double kStatic = DriveConstants.kStatic;
|
||||
public double maxVel = DriveConstants.MAX_VEL;
|
||||
public double maxAccel = DriveConstants.MAX_ACCEL;
|
||||
public double maxAngVel = DriveConstants.MAX_ANG_VEL;
|
||||
public double maxAngAccel = DriveConstants.MAX_ANG_ACCEL;
|
||||
|
||||
public double mecTransP = SampleMecanumDrive.TRANSLATIONAL_PID.kP;
|
||||
public double mecTransI = SampleMecanumDrive.TRANSLATIONAL_PID.kI;
|
||||
public double mecTransD = SampleMecanumDrive.TRANSLATIONAL_PID.kD;
|
||||
public double mecHeadingP = SampleMecanumDrive.HEADING_PID.kP;
|
||||
public double mecHeadingI = SampleMecanumDrive.HEADING_PID.kI;
|
||||
public double mecHeadingD = SampleMecanumDrive.HEADING_PID.kD;
|
||||
public double mecLateralMultiplier = SampleMecanumDrive.LATERAL_MULTIPLIER;
|
||||
|
||||
public double tankAxialP = SampleTankDrive.AXIAL_PID.kP;
|
||||
public double tankAxialI = SampleTankDrive.AXIAL_PID.kI;
|
||||
public double tankAxialD = SampleTankDrive.AXIAL_PID.kD;
|
||||
public double tankCrossTrackP = SampleTankDrive.CROSS_TRACK_PID.kP;
|
||||
public double tankCrossTrackI = SampleTankDrive.CROSS_TRACK_PID.kI;
|
||||
public double tankCrossTrackD = SampleTankDrive.CROSS_TRACK_PID.kD;
|
||||
public double tankHeadingP = SampleTankDrive.HEADING_PID.kP;
|
||||
public double tankHeadingI = SampleTankDrive.HEADING_PID.kI;
|
||||
public double tankHeadingD = SampleTankDrive.HEADING_PID.kD;
|
||||
|
||||
public double trackingTicksPerRev = StandardTrackingWheelLocalizer.TICKS_PER_REV;
|
||||
public double trackingWheelRadius = StandardTrackingWheelLocalizer.WHEEL_RADIUS;
|
||||
public double trackingGearRatio = StandardTrackingWheelLocalizer.GEAR_RATIO;
|
||||
public double trackingLateralDistance = StandardTrackingWheelLocalizer.LATERAL_DISTANCE;
|
||||
public double trackingForwardOffset = StandardTrackingWheelLocalizer.FORWARD_OFFSET;
|
||||
|
||||
public RevHubOrientationOnRobot.LogoFacingDirection LOGO_FACING_DIR = DriveConstants.LOGO_FACING_DIR;
|
||||
public RevHubOrientationOnRobot.UsbFacingDirection USB_FACING_DIR = DriveConstants.USB_FACING_DIR;
|
||||
|
||||
public List<Long> nsTimes = new ArrayList<>();
|
||||
|
||||
public List<Double> targetXs = new ArrayList<>();
|
||||
public List<Double> targetYs = new ArrayList<>();
|
||||
public List<Double> targetHeadings = new ArrayList<>();
|
||||
|
||||
public List<Double> xs = new ArrayList<>();
|
||||
public List<Double> ys = new ArrayList<>();
|
||||
public List<Double> headings = new ArrayList<>();
|
||||
|
||||
public List<Double> voltages = new ArrayList<>();
|
||||
|
||||
public List<List<Integer>> driveEncPositions = new ArrayList<>();
|
||||
public List<List<Integer>> driveEncVels = new ArrayList<>();
|
||||
public List<List<Integer>> trackingEncPositions = new ArrayList<>();
|
||||
public List<List<Integer>> trackingEncVels = new ArrayList<>();
|
||||
|
||||
public LogFile(String opModeName) {
|
||||
this.opModeName = opModeName;
|
||||
}
|
||||
}
|
||||
|
||||
public static void record(
|
||||
Pose2d targetPose, Pose2d pose, double voltage,
|
||||
List<Integer> lastDriveEncPositions, List<Integer> lastDriveEncVels, List<Integer> lastTrackingEncPositions, List<Integer> lastTrackingEncVels
|
||||
) {
|
||||
long nsTime = System.nanoTime();
|
||||
if (nsTime - log.nsStart > 3 * 60 * 1_000_000_000L) {
|
||||
return;
|
||||
}
|
||||
|
||||
log.nsTimes.add(nsTime);
|
||||
|
||||
log.targetXs.add(targetPose.getX());
|
||||
log.targetYs.add(targetPose.getY());
|
||||
log.targetHeadings.add(targetPose.getHeading());
|
||||
|
||||
log.xs.add(pose.getX());
|
||||
log.ys.add(pose.getY());
|
||||
log.headings.add(pose.getHeading());
|
||||
|
||||
log.voltages.add(voltage);
|
||||
|
||||
while (log.driveEncPositions.size() < lastDriveEncPositions.size()) {
|
||||
log.driveEncPositions.add(new ArrayList<>());
|
||||
}
|
||||
while (log.driveEncVels.size() < lastDriveEncVels.size()) {
|
||||
log.driveEncVels.add(new ArrayList<>());
|
||||
}
|
||||
while (log.trackingEncPositions.size() < lastTrackingEncPositions.size()) {
|
||||
log.trackingEncPositions.add(new ArrayList<>());
|
||||
}
|
||||
while (log.trackingEncVels.size() < lastTrackingEncVels.size()) {
|
||||
log.trackingEncVels.add(new ArrayList<>());
|
||||
}
|
||||
|
||||
for (int i = 0; i < lastDriveEncPositions.size(); i++) {
|
||||
log.driveEncPositions.get(i).add(lastDriveEncPositions.get(i));
|
||||
}
|
||||
for (int i = 0; i < lastDriveEncVels.size(); i++) {
|
||||
log.driveEncVels.get(i).add(lastDriveEncVels.get(i));
|
||||
}
|
||||
for (int i = 0; i < lastTrackingEncPositions.size(); i++) {
|
||||
log.trackingEncPositions.get(i).add(lastTrackingEncPositions.get(i));
|
||||
}
|
||||
for (int i = 0; i < lastTrackingEncVels.size(); i++) {
|
||||
log.trackingEncVels.get(i).add(lastTrackingEncVels.get(i));
|
||||
}
|
||||
}
|
||||
|
||||
private static final OpModeManagerNotifier.Notifications notifHandler = new OpModeManagerNotifier.Notifications() {
|
||||
@SuppressLint("SimpleDateFormat")
|
||||
final DateFormat dateFormat = new SimpleDateFormat("yyyy_MM_dd__HH_mm_ss_SSS");
|
||||
|
||||
final ObjectWriter jsonWriter = new ObjectMapper(new JsonFactory())
|
||||
.writerWithDefaultPrettyPrinter();
|
||||
|
||||
@Override
|
||||
public void onOpModePreInit(OpMode opMode) {
|
||||
log = new LogFile(opMode.getClass().getCanonicalName());
|
||||
|
||||
// clean up old files
|
||||
File[] fs = Objects.requireNonNull(ROOT.listFiles());
|
||||
Arrays.sort(fs, (a, b) -> Long.compare(a.lastModified(), b.lastModified()));
|
||||
long totalSizeBytes = 0;
|
||||
for (File f : fs) {
|
||||
totalSizeBytes += f.length();
|
||||
}
|
||||
|
||||
int i = 0;
|
||||
while (i < fs.length && totalSizeBytes >= 32 * 1000 * 1000) {
|
||||
totalSizeBytes -= fs[i].length();
|
||||
if (!fs[i].delete()) {
|
||||
RobotLog.setGlobalErrorMsg("Unable to delete file " + fs[i].getAbsolutePath());
|
||||
}
|
||||
++i;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void onOpModePreStart(OpMode opMode) {
|
||||
log.nsStart = System.nanoTime();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void onOpModePostStop(OpMode opMode) {
|
||||
log.nsStop = System.nanoTime();
|
||||
|
||||
if (!(opMode instanceof OpModeManagerImpl.DefaultOpMode)) {
|
||||
//noinspection ResultOfMethodCallIgnored
|
||||
ROOT.mkdirs();
|
||||
|
||||
String filename = dateFormat.format(new Date(log.msInit)) + "__" + opMode.getClass().getSimpleName() + ".json";
|
||||
File file = new File(ROOT, filename);
|
||||
try {
|
||||
jsonWriter.writeValue(file, log);
|
||||
} catch (IOException e) {
|
||||
RobotLog.setGlobalErrorMsg(new RuntimeException(e),
|
||||
"Unable to write data to " + file.getAbsolutePath());
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
@WebHandlerRegistrar
|
||||
public static void registerRoutes(Context context, WebHandlerManager manager) {
|
||||
//noinspection ResultOfMethodCallIgnored
|
||||
ROOT.mkdirs();
|
||||
|
||||
// op mode manager only stores a weak reference, so we need to keep notifHandler alive ourselves
|
||||
// don't use @OnCreateEventLoop because it's unreliable
|
||||
OpModeManagerImpl.getOpModeManagerOfActivity(
|
||||
AppUtil.getInstance().getActivity()
|
||||
).registerListener(notifHandler);
|
||||
|
||||
manager.register("/logs", session -> {
|
||||
final StringBuilder sb = new StringBuilder();
|
||||
sb.append("<!doctype html><html><head><title>Logs</title></head><body><ul>");
|
||||
File[] fs = Objects.requireNonNull(ROOT.listFiles());
|
||||
Arrays.sort(fs, (a, b) -> Long.compare(b.lastModified(), a.lastModified()));
|
||||
for (File f : fs) {
|
||||
sb.append("<li><a href=\"/logs/download?file=");
|
||||
sb.append(f.getName());
|
||||
sb.append("\" download=\"");
|
||||
sb.append(f.getName());
|
||||
sb.append("\">");
|
||||
sb.append(f.getName());
|
||||
sb.append("</a></li>");
|
||||
}
|
||||
sb.append("</ul></body></html>");
|
||||
return NanoHTTPD.newFixedLengthResponse(NanoHTTPD.Response.Status.OK,
|
||||
NanoHTTPD.MIME_HTML, sb.toString());
|
||||
});
|
||||
|
||||
manager.register("/logs/download", session -> {
|
||||
final String[] pairs = session.getQueryParameterString().split("&");
|
||||
if (pairs.length != 1) {
|
||||
return NanoHTTPD.newFixedLengthResponse(NanoHTTPD.Response.Status.BAD_REQUEST,
|
||||
NanoHTTPD.MIME_PLAINTEXT, "expected one query parameter, got " + pairs.length);
|
||||
}
|
||||
|
||||
final String[] parts = pairs[0].split("=");
|
||||
if (!parts[0].equals("file")) {
|
||||
return NanoHTTPD.newFixedLengthResponse(NanoHTTPD.Response.Status.BAD_REQUEST,
|
||||
NanoHTTPD.MIME_PLAINTEXT, "expected file query parameter, got " + parts[0]);
|
||||
}
|
||||
|
||||
File f = new File(ROOT, parts[1]);
|
||||
if (!f.exists()) {
|
||||
return NanoHTTPD.newFixedLengthResponse(NanoHTTPD.Response.Status.NOT_FOUND,
|
||||
NanoHTTPD.MIME_PLAINTEXT, "file " + f + " doesn't exist");
|
||||
}
|
||||
|
||||
return NanoHTTPD.newChunkedResponse(NanoHTTPD.Response.Status.OK,
|
||||
"application/json", new FileInputStream(f));
|
||||
});
|
||||
}
|
||||
}
|
60
TeamCode/util/LoggingUtil.java
Normal file
60
TeamCode/util/LoggingUtil.java
Normal file
@ -0,0 +1,60 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.internal.system.AppUtil;
|
||||
|
||||
import java.io.File;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Collections;
|
||||
import java.util.List;
|
||||
|
||||
/**
|
||||
* Utility functions for log files.
|
||||
*/
|
||||
public class LoggingUtil {
|
||||
public static final File ROAD_RUNNER_FOLDER =
|
||||
new File(AppUtil.ROOT_FOLDER + "/RoadRunner/");
|
||||
|
||||
private static final long LOG_QUOTA = 25 * 1024 * 1024; // 25MB log quota for now
|
||||
|
||||
private static void buildLogList(List<File> logFiles, File dir) {
|
||||
for (File file : dir.listFiles()) {
|
||||
if (file.isDirectory()) {
|
||||
buildLogList(logFiles, file);
|
||||
} else {
|
||||
logFiles.add(file);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private static void pruneLogsIfNecessary() {
|
||||
List<File> logFiles = new ArrayList<>();
|
||||
buildLogList(logFiles, ROAD_RUNNER_FOLDER);
|
||||
Collections.sort(logFiles, (lhs, rhs) ->
|
||||
Long.compare(lhs.lastModified(), rhs.lastModified()));
|
||||
|
||||
long dirSize = 0;
|
||||
for (File file: logFiles) {
|
||||
dirSize += file.length();
|
||||
}
|
||||
|
||||
while (dirSize > LOG_QUOTA) {
|
||||
if (logFiles.size() == 0) break;
|
||||
File fileToRemove = logFiles.remove(0);
|
||||
dirSize -= fileToRemove.length();
|
||||
//noinspection ResultOfMethodCallIgnored
|
||||
fileToRemove.delete();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Obtain a log file with the provided name
|
||||
*/
|
||||
public static File getLogFile(String name) {
|
||||
//noinspection ResultOfMethodCallIgnored
|
||||
ROAD_RUNNER_FOLDER.mkdirs();
|
||||
|
||||
pruneLogsIfNecessary();
|
||||
|
||||
return new File(ROAD_RUNNER_FOLDER, name);
|
||||
}
|
||||
}
|
124
TeamCode/util/LynxModuleUtil.java
Normal file
124
TeamCode/util/LynxModuleUtil.java
Normal file
@ -0,0 +1,124 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.internal.system.Misc;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
|
||||
/**
|
||||
* Collection of utilites for interacting with Lynx modules.
|
||||
*/
|
||||
public class LynxModuleUtil {
|
||||
|
||||
private static final LynxFirmwareVersion MIN_VERSION = new LynxFirmwareVersion(1, 8, 2);
|
||||
|
||||
/**
|
||||
* Parsed representation of a Lynx module firmware version.
|
||||
*/
|
||||
public static class LynxFirmwareVersion implements Comparable<LynxFirmwareVersion> {
|
||||
public final int major;
|
||||
public final int minor;
|
||||
public final int eng;
|
||||
|
||||
public LynxFirmwareVersion(int major, int minor, int eng) {
|
||||
this.major = major;
|
||||
this.minor = minor;
|
||||
this.eng = eng;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object other) {
|
||||
if (other instanceof LynxFirmwareVersion) {
|
||||
LynxFirmwareVersion otherVersion = (LynxFirmwareVersion) other;
|
||||
return major == otherVersion.major && minor == otherVersion.minor &&
|
||||
eng == otherVersion.eng;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public int compareTo(LynxFirmwareVersion other) {
|
||||
int majorComp = Integer.compare(major, other.major);
|
||||
if (majorComp == 0) {
|
||||
int minorComp = Integer.compare(minor, other.minor);
|
||||
if (minorComp == 0) {
|
||||
return Integer.compare(eng, other.eng);
|
||||
} else {
|
||||
return minorComp;
|
||||
}
|
||||
} else {
|
||||
return majorComp;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return Misc.formatInvariant("%d.%d.%d", major, minor, eng);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Retrieve and parse Lynx module firmware version.
|
||||
* @param module Lynx module
|
||||
* @return parsed firmware version
|
||||
*/
|
||||
public static LynxFirmwareVersion getFirmwareVersion(LynxModule module) {
|
||||
String versionString = module.getNullableFirmwareVersionString();
|
||||
if (versionString == null) {
|
||||
return null;
|
||||
}
|
||||
|
||||
String[] parts = versionString.split("[ :,]+");
|
||||
try {
|
||||
// note: for now, we ignore the hardware entry
|
||||
return new LynxFirmwareVersion(
|
||||
Integer.parseInt(parts[3]),
|
||||
Integer.parseInt(parts[5]),
|
||||
Integer.parseInt(parts[7])
|
||||
);
|
||||
} catch (NumberFormatException e) {
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Exception indicating an outdated Lynx firmware version.
|
||||
*/
|
||||
public static class LynxFirmwareVersionException extends RuntimeException {
|
||||
public LynxFirmwareVersionException(String detailMessage) {
|
||||
super(detailMessage);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Ensure all of the Lynx modules attached to the robot satisfy the minimum requirement.
|
||||
* @param hardwareMap hardware map containing Lynx modules
|
||||
*/
|
||||
public static void ensureMinimumFirmwareVersion(HardwareMap hardwareMap) {
|
||||
Map<String, LynxFirmwareVersion> outdatedModules = new HashMap<>();
|
||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||
LynxFirmwareVersion version = getFirmwareVersion(module);
|
||||
if (version == null || version.compareTo(MIN_VERSION) < 0) {
|
||||
for (String name : hardwareMap.getNamesOf(module)) {
|
||||
outdatedModules.put(name, version);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (outdatedModules.size() > 0) {
|
||||
StringBuilder msgBuilder = new StringBuilder();
|
||||
msgBuilder.append("One or more of the attached Lynx modules has outdated firmware\n");
|
||||
msgBuilder.append(Misc.formatInvariant("Mandatory minimum firmware version for Road Runner: %s\n",
|
||||
MIN_VERSION.toString()));
|
||||
for (Map.Entry<String, LynxFirmwareVersion> entry : outdatedModules.entrySet()) {
|
||||
msgBuilder.append(Misc.formatInvariant(
|
||||
"\t%s: %s\n", entry.getKey(),
|
||||
entry.getValue() == null ? "Unknown" : entry.getValue().toString()));
|
||||
}
|
||||
throw new LynxFirmwareVersionException(msgBuilder.toString());
|
||||
}
|
||||
}
|
||||
}
|
156
TeamCode/util/RegressionUtil.java
Normal file
156
TeamCode/util/RegressionUtil.java
Normal file
@ -0,0 +1,156 @@
|
||||
package org.firstinspires.ftc.teamcode.util;
|
||||
|
||||
import androidx.annotation.Nullable;
|
||||
|
||||
import com.acmerobotics.roadrunner.kinematics.Kinematics;
|
||||
|
||||
import org.apache.commons.math3.stat.regression.SimpleRegression;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.FileNotFoundException;
|
||||
import java.io.PrintWriter;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
/**
|
||||
* Various regression utilities.
|
||||
*/
|
||||
public class RegressionUtil {
|
||||
|
||||
/**
|
||||
* Feedforward parameter estimates from the ramp regression and additional summary statistics
|
||||
*/
|
||||
public static class RampResult {
|
||||
public final double kV, kStatic, rSquare;
|
||||
|
||||
public RampResult(double kV, double kStatic, double rSquare) {
|
||||
this.kV = kV;
|
||||
this.kStatic = kStatic;
|
||||
this.rSquare = rSquare;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Feedforward parameter estimates from the ramp regression and additional summary statistics
|
||||
*/
|
||||
public static class AccelResult {
|
||||
public final double kA, rSquare;
|
||||
|
||||
public AccelResult(double kA, double rSquare) {
|
||||
this.kA = kA;
|
||||
this.rSquare = rSquare;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Numerically compute dy/dx from the given x and y values. The returned list is padded to match
|
||||
* the length of the original sequences.
|
||||
*
|
||||
* @param x x-values
|
||||
* @param y y-values
|
||||
* @return derivative values
|
||||
*/
|
||||
private static List<Double> numericalDerivative(List<Double> x, List<Double> y) {
|
||||
List<Double> deriv = new ArrayList<>(x.size());
|
||||
for (int i = 1; i < x.size() - 1; i++) {
|
||||
deriv.add(
|
||||
(y.get(i + 1) - y.get(i - 1)) /
|
||||
(x.get(i + 1) - x.get(i - 1))
|
||||
);
|
||||
}
|
||||
// copy endpoints to pad output
|
||||
deriv.add(0, deriv.get(0));
|
||||
deriv.add(deriv.get(deriv.size() - 1));
|
||||
return deriv;
|
||||
}
|
||||
|
||||
/**
|
||||
* Run regression to compute velocity and static feedforward from ramp test data.
|
||||
*
|
||||
* Here's the general procedure for gathering the requisite data:
|
||||
* 1. Slowly ramp the motor power/voltage and record encoder values along the way.
|
||||
* 2. Run a linear regression on the encoder velocity vs. motor power plot to obtain a slope
|
||||
* (kV) and an optional intercept (kStatic).
|
||||
*
|
||||
* @param timeSamples time samples
|
||||
* @param positionSamples position samples
|
||||
* @param powerSamples power samples
|
||||
* @param fitStatic fit kStatic
|
||||
* @param file log file
|
||||
*/
|
||||
public static RampResult fitRampData(List<Double> timeSamples, List<Double> positionSamples,
|
||||
List<Double> powerSamples, boolean fitStatic,
|
||||
@Nullable File file) {
|
||||
if (file != null) {
|
||||
try (PrintWriter pw = new PrintWriter(file)) {
|
||||
pw.println("time,position,power");
|
||||
for (int i = 0; i < timeSamples.size(); i++) {
|
||||
double time = timeSamples.get(i);
|
||||
double pos = positionSamples.get(i);
|
||||
double power = powerSamples.get(i);
|
||||
pw.println(time + "," + pos + "," + power);
|
||||
}
|
||||
} catch (FileNotFoundException e) {
|
||||
// ignore
|
||||
}
|
||||
}
|
||||
|
||||
List<Double> velSamples = numericalDerivative(timeSamples, positionSamples);
|
||||
|
||||
SimpleRegression rampReg = new SimpleRegression(fitStatic);
|
||||
for (int i = 0; i < timeSamples.size(); i++) {
|
||||
double vel = velSamples.get(i);
|
||||
double power = powerSamples.get(i);
|
||||
|
||||
rampReg.addData(vel, power);
|
||||
}
|
||||
|
||||
return new RampResult(Math.abs(rampReg.getSlope()), Math.abs(rampReg.getIntercept()),
|
||||
rampReg.getRSquare());
|
||||
}
|
||||
|
||||
/**
|
||||
* Run regression to compute acceleration feedforward.
|
||||
*
|
||||
* @param timeSamples time samples
|
||||
* @param positionSamples position samples
|
||||
* @param powerSamples power samples
|
||||
* @param rampResult ramp result
|
||||
* @param file log file
|
||||
*/
|
||||
public static AccelResult fitAccelData(List<Double> timeSamples, List<Double> positionSamples,
|
||||
List<Double> powerSamples, RampResult rampResult,
|
||||
@Nullable File file) {
|
||||
if (file != null) {
|
||||
try (PrintWriter pw = new PrintWriter(file)) {
|
||||
pw.println("time,position,power");
|
||||
for (int i = 0; i < timeSamples.size(); i++) {
|
||||
double time = timeSamples.get(i);
|
||||
double pos = positionSamples.get(i);
|
||||
double power = powerSamples.get(i);
|
||||
pw.println(time + "," + pos + "," + power);
|
||||
}
|
||||
} catch (FileNotFoundException e) {
|
||||
// ignore
|
||||
}
|
||||
}
|
||||
|
||||
List<Double> velSamples = numericalDerivative(timeSamples, positionSamples);
|
||||
List<Double> accelSamples = numericalDerivative(timeSamples, velSamples);
|
||||
|
||||
SimpleRegression accelReg = new SimpleRegression(false);
|
||||
for (int i = 0; i < timeSamples.size(); i++) {
|
||||
double vel = velSamples.get(i);
|
||||
double accel = accelSamples.get(i);
|
||||
double power = powerSamples.get(i);
|
||||
|
||||
double powerFromVel = Kinematics.calculateMotorFeedforward(
|
||||
vel, 0.0, rampResult.kV, 0.0, rampResult.kStatic);
|
||||
double powerFromAccel = power - powerFromVel;
|
||||
|
||||
accelReg.addData(accel, powerFromAccel);
|
||||
}
|
||||
|
||||
return new AccelResult(Math.abs(accelReg.getSlope()), accelReg.getRSquare());
|
||||
}
|
||||
}
|
Reference in New Issue
Block a user