Skip to content
This repository has been archived by the owner on Dec 2, 2024. It is now read-only.

Commit

Permalink
odometry ????
Browse files Browse the repository at this point in the history
  • Loading branch information
carokhan committed Oct 17, 2024
1 parent cd5533e commit eb4256d
Show file tree
Hide file tree
Showing 7 changed files with 200 additions and 15 deletions.
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "Forte-2-5";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 82;
public static final String GIT_SHA = "6f4b11f204b606abef1cec758d79762da118ae86";
public static final String GIT_DATE = "2024-10-11 08:02:33 EDT";
public static final String GIT_BRANCH = "HEAD";
public static final String BUILD_DATE = "2024-10-15 20:11:28 EDT";
public static final long BUILD_UNIX_TIME = 1729037488004L;
public static final int GIT_REVISION = 83;
public static final String GIT_SHA = "cd5533efceedea228db5f5c1abfb4d489944d593";
public static final String GIT_DATE = "2024-10-16 05:10:03 EDT";
public static final String GIT_BRANCH = "main";
public static final String BUILD_DATE = "2024-10-17 07:03:41 EDT";
public static final long BUILD_UNIX_TIME = 1729163021410L;
public static final int DIRTY = 1;

private BuildConstants() {}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
public final class Constants {
public static final double loopPeriodSecs = 0.02;

public static final Mode currentMode = Mode.REAL;
public static final Mode currentMode = Mode.SIM;

public static enum Mode {
/** Running on a real robot. */
Expand Down
30 changes: 29 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,18 @@
package frc.robot.subsystems.drive;

import com.google.common.collect.Streams;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Twist2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand All @@ -47,6 +52,8 @@ public class Drive extends SubsystemBase {
new SwerveModulePosition(),
new SwerveModulePosition()
};
private SwerveDrivePoseEstimator poseEstimator =
new SwerveDrivePoseEstimator(kinematics, rawGyroRotation, lastModulePositions, new Pose2d());

public Drive(
GyroIO gyroIO,
Expand All @@ -61,7 +68,8 @@ public Drive(
modules[3] = new Module(brModuleIO, 3);

// Start threads (no-op for each if no signals have been created)
SparkMaxOdometryThread.getInstance().start();
HybridOdometryThread.getInstance().start();
// SparkMaxOdometryThread.getInstance().start();
// PhoenixOdometryThread.getInstance().start();

}
Expand Down Expand Up @@ -116,6 +124,8 @@ public void periodic() {
Twist2d twist = kinematics.toTwist2d(moduleDeltas);
rawGyroRotation = rawGyroRotation.plus(new Rotation2d(twist.dtheta));
}

poseEstimator.updateWithTime(sampleTimestamps[i], rawGyroRotation, modulePositions);
}
}

Expand Down Expand Up @@ -200,4 +210,22 @@ public Command zeroGyro() {
gyroIO.setYaw(0);
});
}

@AutoLogOutput(key = "Odometry/Robot")
public Pose2d getPose() {
return poseEstimator.getEstimatedPosition();
}

public void setPose(Pose2d pose) {
poseEstimator.resetPosition(rawGyroRotation, getModulePositions(), pose);
}

public void addVisionMeasurement(Pose2d visionPose, double timestamp) {
poseEstimator.addVisionMeasurement(visionPose, timestamp);
}

public void addVisionMeasurement(
Pose2d visionPose, double timestamp, Matrix<N3, N1> visionMeasurementStdDevs) {
poseEstimator.addVisionMeasurement(visionPose, timestamp, visionMeasurementStdDevs);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@ public GyroIOPigeon2Phoenix6() {
yawVelocity.setUpdateFrequency(100.0);
pigeon.optimizeBusUtilization();

yawTimestampQueue = SparkMaxOdometryThread.getInstance().makeTimestampQueue();
yawTimestampQueue = HybridOdometryThread.getInstance().makeTimestampQueue();
yawPositionQueue =
SparkMaxOdometryThread.getInstance()
HybridOdometryThread.getInstance()
.registerSignal(
() -> {
boolean valid = yaw.refresh().getStatus().isOK();
Expand Down
152 changes: 152 additions & 0 deletions src/main/java/frc/robot/subsystems/drive/HybridOdometryThread.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,152 @@
package frc.robot.subsystems.drive;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.hardware.ParentDevice;
import java.util.ArrayList;
import java.util.List;
import java.util.OptionalDouble;
import java.util.Queue;
import java.util.concurrent.ArrayBlockingQueue;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;
import java.util.function.Supplier;
import org.littletonrobotics.junction.Logger;

public class HybridOdometryThread extends Thread {

private final Lock signalsLock = new ReentrantLock();
private List<BaseStatusSignal> phoenixSignals = new ArrayList<>();
private List<Supplier<OptionalDouble>> polledSignals = new ArrayList<>();
private List<Queue<Double>> queues = new ArrayList<>();
private List<Queue<Double>> timestampQueues = new ArrayList<>();

// Ensures samples added to correct queue
private List<Integer> signalTypes = new ArrayList<>(); // 0 for Phoenix 1 for polled

private static final int PHOENIX_SIGNAL = 0;
private static final int POLLED_SIGNAL = 1;

private static HybridOdometryThread instance = null;

public static HybridOdometryThread getInstance() {
if (instance == null) {
instance = new HybridOdometryThread();
}
return instance;
}

private HybridOdometryThread() {
setName("HybridOdometryThread");
setDaemon(true);
}

@Override
public void start() {
if (timestampQueues.size() > 0) {
super.start();
}
}

public Queue<Double> registerSignal(ParentDevice device, StatusSignal<Double> signal) {
Queue<Double> queue = new ArrayBlockingQueue<>(20);
signalsLock.lock();
Drive.odometryLock.lock();
try {
phoenixSignals.add(signal);
queues.add(queue);
signalTypes.add(PHOENIX_SIGNAL);
} finally {
signalsLock.unlock();
Drive.odometryLock.unlock();
}
return queue;
}

public Queue<Double> registerSignal(Supplier<OptionalDouble> signal) {
Queue<Double> queue = new ArrayBlockingQueue<>(20);
Drive.odometryLock.lock();
try {
polledSignals.add(signal);
queues.add(queue);
signalTypes.add(POLLED_SIGNAL);
} finally {
Drive.odometryLock.unlock();
}
return queue;
}

public Queue<Double> makeTimestampQueue() {
Queue<Double> queue = new ArrayBlockingQueue<>(20);
Drive.odometryLock.lock();
try {
timestampQueues.add(queue);
} finally {
Drive.odometryLock.unlock();
}
return queue;
}

@Override
public void run() {
while (true) {
signalsLock.lock();
try {
if (!phoenixSignals.isEmpty()) {
BaseStatusSignal.waitForAll(2.0 / 250.0, phoenixSignals.toArray(new BaseStatusSignal[0]));
} else {
Thread.sleep((long) (1000.0 / 250.0));
}
} catch (InterruptedException e) {
e.printStackTrace();
} finally {
signalsLock.unlock();
}

Drive.odometryLock.lock();
try {
double timestamp = Logger.getRealTimestamp() / 1e6;
double totalLatency = 0.0;
for (BaseStatusSignal signal : phoenixSignals) {
totalLatency += signal.getTimestamp().getLatency();
}
if (!phoenixSignals.isEmpty()) {
timestamp -= totalLatency / phoenixSignals.size();
}

// If 1 thing breaks everything breaks, probably a bad idea idrc
boolean allValid = true;
int phoenixIndex = 0;
int polledIndex = 0;

for (int i = 0; i < signalTypes.size(); i++) {
double value;
if (signalTypes.get(i) == PHOENIX_SIGNAL) {
value = phoenixSignals.get(phoenixIndex++).getValueAsDouble();
} else {
OptionalDouble optionalValue = polledSignals.get(polledIndex++).get();
if (optionalValue.isPresent()) {
value = optionalValue.getAsDouble();
} else {
allValid = false;
break;
}
}

if (allValid) {
queues.get(i).offer(value);
}
}

// All thingies sampled together
if (allValid) {
for (Queue<Double> timestampQueue : timestampQueues) {
timestampQueue.offer(timestamp);
}
}
} finally {
Drive.odometryLock.unlock();
}
}
}
}
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/subsystems/drive/ModuleIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -195,10 +195,11 @@ public ModuleIOReal(int index) {

turnRelativeEncoder.setPosition(getAbsoluteEncoder());

timestampQueue = PhoenixOdometryThread.getInstance().makeTimestampQueue();
timestampQueue = HybridOdometryThread.getInstance().makeTimestampQueue();

drivePosition = driveTalon.getPosition();
drivePositionQueue =
PhoenixOdometryThread.getInstance().registerSignal(driveTalon, driveTalon.getPosition());
HybridOdometryThread.getInstance().registerSignal(driveTalon, driveTalon.getPosition());
driveVelocity = driveTalon.getVelocity();
driveAppliedVolts = driveTalon.getMotorVoltage();
driveCurrent = driveTalon.getStatorCurrent();
Expand All @@ -208,7 +209,7 @@ public ModuleIOReal(int index) {
driveTalon.optimizeBusUtilization();

turnPositionQueue =
SparkMaxOdometryThread.getInstance()
HybridOdometryThread.getInstance()
.registerSignal(
() -> {
double value = turnRelativeEncoder.getPosition();
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,12 @@ public void runTurnVoltage(double volts) {
@Override
public void runDriveVelocitySetpoint(double velocityRadsPerSec, double feedForward) {
runDriveVoltage(
feedForward
+ driveFeedback.calculate(driveSim.getAngularVelocityRadPerSec(), velocityRadsPerSec));
// feedForward
// + driveFeedback.calculate(driveSim.getAngularVelocityRadPerSec(),
// velocityRadsPerSec));
Math.signum(velocityRadsPerSec)
* Math.pow((velocityRadsPerSec / DriveConstants.maxLinearVelocity), 2)
* 12.0);
}

@Override
Expand Down

0 comments on commit eb4256d

Please sign in to comment.