Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Use transforms when applying vision pose #13

Merged
merged 2 commits into from
Feb 16, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 12 additions & 6 deletions src/main/java/org/littletonrobotics/frc2024/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -143,15 +143,21 @@ public void addVisionObservation(VisionObservation observation) {
}
}
// difference between estimate and vision pose
Twist2d twist = estimateAtTime.log(observation.visionPose());
// scale twist by visionK
var kTimesTwist = visionK.times(VecBuilder.fill(twist.dx, twist.dy, twist.dtheta));
Twist2d scaledTwist =
new Twist2d(kTimesTwist.get(0, 0), kTimesTwist.get(1, 0), kTimesTwist.get(2, 0));
Transform2d transform = new Transform2d(estimateAtTime, observation.visionPose());
// scale transform by visionK
var kTimesTransform =
visionK.times(
VecBuilder.fill(
transform.getX(), transform.getY(), transform.getRotation().getRadians()));
Transform2d scaledTransform =
new Transform2d(
kTimesTransform.get(0, 0),
kTimesTransform.get(1, 0),
Rotation2d.fromRadians(kTimesTransform.get(2, 0)));

// Recalculate current estimate by applying scaled twist to old estimate
// then replaying odometry data
estimatedPose = estimateAtTime.exp(scaledTwist).plus(sampleToOdometryTransform);
estimatedPose = estimateAtTime.plus(scaledTransform).plus(sampleToOdometryTransform);
}

public void addVelocityData(Twist2d robotVelocity) {
Expand Down
Loading