Skip to content
Merged
Show file tree
Hide file tree
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
27 changes: 26 additions & 1 deletion src/main/java/frc/robot/vision/VisionConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -325,12 +325,37 @@ public class AlignmentConfig {
// public static final Distance LATERAL_TARGET_L4_LEFT = Meters.of(0.05);
// public static final Distance LATERAL_TARGET_L4_RIGHT = Meters.of(0.02);

//April Tag IDs
public static final double id1 = 1;
public static final double id2 = 2;
public static final double id3 = 3;
public static final double id4 = 4;
public static final double id5 = 5;
public static final double id6 = 6;
public static final double id7 = 7;
public static final double id8 = 8;
public static final double id9 = 9;
public static final double id10 = 10;
public static final double id11 = 11;
public static final double id12 = 12;
public static final double id13 = 13;
public static final double id14 = 14;
public static final double id15 = 15;
public static final double id16 = 16;
public static final double id17 = 17;
public static final double id18 = 18;
public static final double id19 = 19;
public static final double id20 = 20;
public static final double id21 = 21;
public static final double id22 = 22;




//Joey's Pose Constants for the Reef Locations
public static final Pose2d Error = new Pose2d(6, 6, Rotation2d.fromDegrees(0));

public static final Pose2d Ablue = new Pose2d(3.180, 4.175, Rotation2d.fromDegrees(0));
public static final Pose2d Ablue = new Pose2d(3.180, 4.175, Rotation2d.fromDegrees(0));
public static final Pose2d Bblue = new Pose2d(3.180, 3.850, Rotation2d.fromDegrees(0));
public static final Pose2d Cblue = new Pose2d(3.685, 2.975, Rotation2d.fromDegrees(60));
public static final Pose2d Dblue = new Pose2d(3.975, 2.825, Rotation2d.fromDegrees(60));
Expand Down
9 changes: 6 additions & 3 deletions src/main/java/frc/robot/vision/commands/LineupCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
import edu.wpi.first.units.measure.LinearVelocity;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;

import frc.robot.vision.VisionConfig;
Expand Down Expand Up @@ -103,11 +104,11 @@ public void initialize() {
@Override
public void execute() {
currentPose = PoseEstimatorSubsystem.getInstance().getCurrentPose();
ChassisSpeeds currentSpeeds = CommandSwerveDrivetrain.getInstance().getState().Speeds;
// ChassisSpeeds currentSpeeds = CommandSwerveDrivetrain.getInstance().getState().Speeds;
x = currentPose.getTranslation().getX();
y = currentPose.getTranslation().getY();
double Xvel = currentSpeeds.vxMetersPerSecond;
double Yvel = currentSpeeds.vyMetersPerSecond;
// double Xvel = currentSpeeds.vxMetersPerSecond;
// double Yvel = currentSpeeds.vyMetersPerSecond;
double XOutput = 0.15 * kLineupSpeed.in(MetersPerSecond) * 0.95 * xDistanceController.calculate(x, targetPose.getX());
double YOutput = 0.15 * kLineupSpeed.in(MetersPerSecond) * 0.95 * xDistanceController.calculate(y, targetPose.getY());
double thetaOutput = 0.15 * RotationsPerSecond.of(0.75).in(RadiansPerSecond) * thetaController.calculate(currentPose.getRotation().getRadians(), targetPose.getRotation().getRadians());
Expand All @@ -127,6 +128,8 @@ public void execute() {
).execute();
}

SmartDashboard.putString("Target Pose X", targetPose.toString());

}


Expand Down