Skip to content

Commit

Permalink
Update shoot while moving
Browse files Browse the repository at this point in the history
  • Loading branch information
camearle20 committed Feb 10, 2024
1 parent 85912ce commit ba62b3b
Showing 1 changed file with 30 additions and 23 deletions.
53 changes: 30 additions & 23 deletions src/main/java/org/littletonrobotics/frc2024/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,14 @@
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import java.util.NoSuchElementException;
import lombok.experimental.ExtensionMethod;
import org.littletonrobotics.frc2024.subsystems.drive.DriveConstants;
import org.littletonrobotics.frc2024.util.AllianceFlipUtil;
import org.littletonrobotics.frc2024.util.GeomUtil;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
import org.littletonrobotics.junction.AutoLogOutput;

@ExtensionMethod({GeomUtil.class})
public class RobotState {
// Pose Estimation
public record OdometryObservation(
Expand All @@ -25,6 +29,9 @@ public record VisionObservation(Pose2d visionPose, double timestamp, Matrix<N3,
public record AimingParameters(
Rotation2d driveHeading, double effectiveDistance, double radialFF) {}

private static final LoggedTunableNumber lookahead =
new LoggedTunableNumber("RobotState/lookaheadS", 0.0);

private static final double poseBufferSizeSeconds = 2.0;

private static RobotState instance;
Expand Down Expand Up @@ -147,29 +154,29 @@ public AimingParameters getAimingParameters() {
return latestParameters;
}

Pose2d robot = getEstimatedPose();
Twist2d fieldVelocity = fieldVelocity();

Translation3d originToGoal3d =
AllianceFlipUtil.apply(FieldConstants.Speaker.centerSpeakerOpening);
Translation2d originToGoal = new Translation2d(originToGoal3d.getX(), originToGoal3d.getY());
Translation2d originToRobot = robot.getTranslation();

// Get robot to goal angle but limit to reasonable range
Rotation2d robotToGoalAngle = originToGoal.minus(originToGoal).getAngle();
// Subtract goal to robot angle from field velocity
Translation2d tangentialVelocity =
new Translation2d(fieldVelocity.dx, fieldVelocity.dy)
.rotateBy(robotToGoalAngle.unaryMinus());
// Subtract tangential velocity from goal to get virtual goal
Translation2d originToVirtualGoal = originToGoal.plus(tangentialVelocity.unaryMinus());

// Angle to virtual goal
Rotation2d driveHeading = originToVirtualGoal.minus(originToRobot).getAngle();
// Distance to virtual goal
double effectiveDistance = originToRobot.getDistance(originToVirtualGoal);
double radialFF = -tangentialVelocity.getX();
latestParameters = new AimingParameters(driveHeading, effectiveDistance, radialFF);
Transform2d fieldToTarget =
AllianceFlipUtil.apply(FieldConstants.Speaker.centerSpeakerOpening)
.toTranslation2d()
.toTransform2d();
Pose2d fieldToPredictedVehicle = getPredictedPose(lookahead.get(), lookahead.get());
Pose2d fieldToPredictedVehicleFixed =
new Pose2d(fieldToPredictedVehicle.getTranslation(), new Rotation2d());

Translation2d predictedVehicleToTargetTranslation =
fieldToPredictedVehicle.inverse().transformBy(fieldToTarget).getTranslation();
Translation2d predictedVehicleFixedToTargetTranslation =
fieldToPredictedVehicleFixed.inverse().transformBy(fieldToTarget).getTranslation();

Rotation2d vehicleToGoalDirection = predictedVehicleToTargetTranslation.getAngle();

Rotation2d targetVehicleDirection = predictedVehicleFixedToTargetTranslation.getAngle();
double targetDistance = predictedVehicleToTargetTranslation.getNorm();

double feedVelocity =
robotVelocity.dx * vehicleToGoalDirection.getSin() / targetDistance
- robotVelocity.dy * vehicleToGoalDirection.getCos() / targetDistance;

latestParameters = new AimingParameters(targetVehicleDirection, targetDistance, feedVelocity);
return latestParameters;
}

Expand Down

0 comments on commit ba62b3b

Please sign in to comment.