Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025
This commit is contained in:
@@ -2,6 +2,7 @@ package frc.robot.subsystems;
|
|||||||
|
|
||||||
import java.util.function.Supplier;
|
import java.util.function.Supplier;
|
||||||
import com.ctre.phoenix6.Utils;
|
import com.ctre.phoenix6.Utils;
|
||||||
|
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||||
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
|
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
|
||||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
|
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
|
||||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||||
@@ -10,8 +11,10 @@ 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 edu.wpi.first.math.Matrix;
|
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.Pose2d;
|
||||||
import edu.wpi.first.math.geometry.Rotation2d;
|
import edu.wpi.first.math.geometry.Rotation2d;
|
||||||
|
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
|
||||||
import edu.wpi.first.math.numbers.N1;
|
import edu.wpi.first.math.numbers.N1;
|
||||||
import edu.wpi.first.math.numbers.N3;
|
import edu.wpi.first.math.numbers.N3;
|
||||||
import edu.wpi.first.wpilibj.DriverStation;
|
import edu.wpi.first.wpilibj.DriverStation;
|
||||||
@@ -31,14 +34,15 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
|||||||
private static final double kSimLoopPeriod = 0.005; // 5 ms
|
private static final double kSimLoopPeriod = 0.005; // 5 ms
|
||||||
private Notifier m_simNotifier = null;
|
private Notifier m_simNotifier = null;
|
||||||
private double m_lastSimTime;
|
private double m_lastSimTime;
|
||||||
|
private Pigeon2 pigeon2 = new Pigeon2(13);
|
||||||
/* Blue alliance sees forward as 0 degrees (toward red alliance wall) */
|
/* Blue alliance sees forward as 0 degrees (toward red alliance wall) */
|
||||||
private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero;
|
private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero;
|
||||||
/* Red alliance sees forward as 180 degrees (toward blue alliance wall) */
|
/* Red alliance sees forward as 180 degrees (toward blue alliance wall) */
|
||||||
private static final Rotation2d kRedAlliancePerspectiveRotation = Rotation2d.k180deg;
|
private static final Rotation2d kRedAlliancePerspectiveRotation = Rotation2d.k180deg;
|
||||||
/* Keep track if we've ever applied the operator perspective before or not */
|
/* Keep track if we've ever applied the operator perspective before or not */
|
||||||
private boolean m_hasAppliedOperatorPerspective = false;
|
private boolean m_hasAppliedOperatorPerspective = false;
|
||||||
|
private SwerveDriveOdometry odometry;
|
||||||
|
private SwerveDrivePoseEstimator poseEstimator;
|
||||||
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
|
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
|
||||||
|
|
||||||
/* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */
|
/* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */
|
||||||
@@ -53,7 +57,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
|||||||
var config = RobotConfig.fromGUISettings();
|
var config = RobotConfig.fromGUISettings();
|
||||||
AutoBuilder.configure(
|
AutoBuilder.configure(
|
||||||
() -> getState().Pose, // Supplier of current robot pose
|
() -> getState().Pose, // Supplier of current robot pose
|
||||||
this::resetPose, // Consumer for seeding pose against auto
|
this::resetOdometry, // Consumer for seeding pose against auto
|
||||||
() -> getState().Speeds, // Supplier of current robot speeds
|
() -> getState().Speeds, // Supplier of current robot speeds
|
||||||
|
|
||||||
// Consumer of ChassisSpeeds and feedforwards to drive the robot
|
// Consumer of ChassisSpeeds and feedforwards to drive the robot
|
||||||
@@ -105,7 +109,26 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
|||||||
}
|
}
|
||||||
configureAutoBuilder();
|
configureAutoBuilder();
|
||||||
}
|
}
|
||||||
|
// public void resetPose(Pose2d pose) {
|
||||||
|
// // Reset gyro to match starting rotation
|
||||||
|
// pigeon2.setYaw(pose.getRotation().getDegrees());
|
||||||
|
|
||||||
|
// // Reset odometry
|
||||||
|
// m_odometry.resetPosition(
|
||||||
|
// pose.getRotation(),
|
||||||
|
// getState().ModulePositions,
|
||||||
|
// pose
|
||||||
|
// );
|
||||||
|
//}
|
||||||
|
public void resetOdometry(Pose2d pose) {
|
||||||
|
odometry = new SwerveDriveOdometry(getKinematics(), kBlueAlliancePerspectiveRotation, getState().ModulePositions);
|
||||||
|
odometry.resetPosition(
|
||||||
|
getPigeon2().getRotation2d(),
|
||||||
|
getState().ModulePositions,
|
||||||
|
pose
|
||||||
|
);
|
||||||
|
this.getPigeon2().setYaw(pose.getRotation().getDegrees());
|
||||||
|
}
|
||||||
/**
|
/**
|
||||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||||
* <p>
|
* <p>
|
||||||
@@ -128,7 +151,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
|||||||
if (Utils.isSimulation()) {
|
if (Utils.isSimulation()) {
|
||||||
startSimThread();
|
startSimThread();
|
||||||
}
|
}
|
||||||
configureAutoBuilder();
|
// configureAutoBuilder();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|||||||
Reference in New Issue
Block a user