This commit is contained in:
Michael Mikovsky
2026-02-21 14:08:32 -08:00
parent 81edff83bc
commit 4907e0c8a0
5 changed files with 54 additions and 20 deletions
+5
View File
@@ -1,4 +1,9 @@
{ {
"System Joysticks": {
"window": {
"enabled": false
}
},
"keyboardJoysticks": [ "keyboardJoysticks": [
{ {
"axisConfig": [ "axisConfig": [
@@ -3,25 +3,25 @@
"waypoints": [ "waypoints": [
{ {
"anchor": { "anchor": {
"x": 2.42775, "x": 3.0,
"y": 4.0055 "y": 4.0
}, },
"prevControl": null, "prevControl": null,
"nextControl": { "nextControl": {
"x": 3.4277499999999996, "x": 4.0,
"y": 4.0055 "y": 4.0
}, },
"isLocked": false, "isLocked": false,
"linkedName": null "linkedName": null
}, },
{ {
"anchor": { "anchor": {
"x": 2.42775, "x": 3.0,
"y": 4.0055 "y": 4.0
}, },
"prevControl": { "prevControl": {
"x": 1.42775, "x": 2.0,
"y": 4.0055 "y": 4.0
}, },
"nextControl": null, "nextControl": null,
"isLocked": false, "isLocked": false,
@@ -42,13 +42,13 @@
}, },
"goalEndState": { "goalEndState": {
"velocity": 0, "velocity": 0,
"rotation": 0.0 "rotation": 90.0
}, },
"reversed": false, "reversed": false,
"folder": null, "folder": null,
"idealStartingState": { "idealStartingState": {
"velocity": 0, "velocity": 0,
"rotation": -90.48219994972354 "rotation": 0.0
}, },
"useDefaultConstraints": false "useDefaultConstraints": false
} }
@@ -10,7 +10,9 @@ package frc4388.robot;
import java.io.File; import java.io.File;
import com.pathplanner.lib.commands.PathPlannerAuto; import com.pathplanner.lib.commands.PathPlannerAuto;
import com.pathplanner.lib.trajectory.PathPlannerTrajectory;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation;
@@ -353,16 +355,21 @@ public class RobotContainer {
autoChooser.onChange((filename) -> { autoChooser.onChange((filename) -> {
autoChooserUpdated = true; autoChooserUpdated = true;
if (filename.equals("Taxi")) { // if (filename.equals("Taxi")) {
autoCommand = new SequentialCommandGroup( // autoCommand = new SequentialCommandGroup(
new MoveForTimeCommand(m_robotSwerveDrive, // new MoveForTimeCommand(m_robotSwerveDrive,
new Translation2d(0, -1), // new Translation2d(0, -1),
new Translation2d(), 1000, true // new Translation2d(), 1000, true
), new InstantCommand(()-> {m_robotSwerveDrive.softStop();} , m_robotSwerveDrive)); // ), new InstantCommand(()-> {m_robotSwerveDrive.softStop();} , m_robotSwerveDrive));
} else { // } else {
autoCommand = new PathPlannerAuto(filename); autoCommand = new PathPlannerAuto(filename);
} // }
System.out.println("Robot Auto Changed " + filename); System.out.println("Robot Auto Changed " + filename);
//----
PathPlannerAuto auto = new PathPlannerAuto(filename);
m_robotSwerveDrive.setInitalPose(auto.getStartingPose());
//-----
}); });
SmartDashboard.putData(autoChooser); SmartDashboard.putData(autoChooser);
@@ -14,6 +14,7 @@ import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.config.PIDConstants; import com.pathplanner.lib.config.PIDConstants;
import com.pathplanner.lib.config.RobotConfig; import com.pathplanner.lib.config.RobotConfig;
import com.pathplanner.lib.controllers.PPHolonomicDriveController; import com.pathplanner.lib.controllers.PPHolonomicDriveController;
import com.pathplanner.lib.trajectory.PathPlannerTrajectory;
import com.pathplanner.lib.util.PathPlannerLogging; import com.pathplanner.lib.util.PathPlannerLogging;
import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose2d;
@@ -21,6 +22,7 @@ import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.robot.constants.Constants.AutoConstants; import frc4388.robot.constants.Constants.AutoConstants;
import frc4388.robot.subsystems.vision.Vision; import frc4388.robot.subsystems.vision.Vision;
@@ -50,7 +52,8 @@ public class SwerveDrive extends SubsystemBase implements Queryable {
public double lastOdomSpeed; public double lastOdomSpeed;
public Pose2d initalPose2d = new Pose2d(); // Mira aqui public Pose2d initalPose2d = new Pose2d();
public double rotTarget = 0.0; public double rotTarget = 0.0;
@@ -136,7 +139,11 @@ public class SwerveDrive extends SubsystemBase implements Queryable {
public void setOdoPose(Pose2d pose) { public void setOdoPose(Pose2d pose) {
if (pose == null) return; if (pose == null) return;
initalPose2d = pose; initalPose2d = pose;
io.resetPose(pose); io.resetPose(initalPose2d);
}
public void setInitalPose(Pose2d startingAutoPose){
initalPose2d = startingAutoPose;
} }
// MIRA public void setOdoPose(Pose2d pose) { // MIRA public void setOdoPose(Pose2d pose) {
// if (pose == null) return; // if (pose == null) return;
@@ -10,6 +10,7 @@ import com.ctre.phoenix6.swerve.SwerveDrivetrain;
import com.ctre.phoenix6.swerve.SwerveModule; import com.ctre.phoenix6.swerve.SwerveModule;
import com.ctre.phoenix6.swerve.SwerveRequest; import com.ctre.phoenix6.swerve.SwerveRequest;
import edu.wpi.first.math.geometry.Pose2d;
import frc4388.robot.subsystems.vision.Vision; import frc4388.robot.subsystems.vision.Vision;
import frc4388.robot.subsystems.vision.VisionIO.PoseObservation; import frc4388.robot.subsystems.vision.VisionIO.PoseObservation;
@@ -40,6 +41,20 @@ public class SwerveReal implements SwerveIO {
swerveDriveTrain.tareEverything(); swerveDriveTrain.tareEverything();
} }
@Override
public void resetPose(Pose2d pose) {
if (pose == null) return;
try {
// Preferred: ask the drivetrain to reset its odometry directly
System.out.println("!"+pose);
swerveDriveTrain.resetPose(pose);
} catch (NoSuchMethodError | RuntimeException e) {
// Fallback: tare sensors then add a timed vision measurement so odometry is seeded
swerveDriveTrain.tareEverything();
swerveDriveTrain.addVisionMeasurement(pose, Utils.fpgaToCurrentTime(Vision.getTime()));
}
}
@Override @Override
public void setLimits(double limitInAmps) { public void setLimits(double limitInAmps) {
for (SwerveModule<TalonFX, TalonFX, CANcoder> module : swerveDriveTrain.getModules()) { for (SwerveModule<TalonFX, TalonFX, CANcoder> module : swerveDriveTrain.getModules()) {