Merge branch 'main' of https://git.demerso.net/sdesharnais/Rebuilt-2026
This commit is contained in:
@@ -16,6 +16,7 @@ import edu.wpi.first.math.MathUtil;
|
|||||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||||
|
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||||
import frc.robot.commands.Aspirer;
|
import frc.robot.commands.Aspirer;
|
||||||
import frc.robot.commands.DescendreBalyeuse;
|
import frc.robot.commands.DescendreBalyeuse;
|
||||||
import frc.robot.commands.DescendreGrimpeur;
|
import frc.robot.commands.DescendreGrimpeur;
|
||||||
@@ -96,6 +97,11 @@ public class RobotContainer {
|
|||||||
)
|
)
|
||||||
);
|
);
|
||||||
//manette 1
|
//manette 1
|
||||||
|
manette.y().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
|
||||||
|
manette.a().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
|
||||||
|
manette.b().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kForward));
|
||||||
|
manette.x().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kReverse));
|
||||||
|
|
||||||
manette.povUp().whileTrue(new LancerAuto(lanceur));
|
manette.povUp().whileTrue(new LancerAuto(lanceur));
|
||||||
manette.a().whileTrue(new Lancer(lanceur,limeLight3G,balayeuse,led));
|
manette.a().whileTrue(new Lancer(lanceur,limeLight3G,balayeuse,led));
|
||||||
manette.x().whileTrue(new LancerBaseVitesse(lanceur, limeLight3));
|
manette.x().whileTrue(new LancerBaseVitesse(lanceur, limeLight3));
|
||||||
|
|||||||
@@ -49,6 +49,73 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
|||||||
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;
|
||||||
|
/* Swerve requests to apply during SysId characterization */
|
||||||
|
private final SwerveRequest.SysIdSwerveTranslation m_translationCharacterization = new SwerveRequest.SysIdSwerveTranslation();
|
||||||
|
private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains();
|
||||||
|
private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation();
|
||||||
|
|
||||||
|
/* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */
|
||||||
|
private final SysIdRoutine m_sysIdRoutineTranslation = new SysIdRoutine(
|
||||||
|
new SysIdRoutine.Config(
|
||||||
|
null, // Use default ramp rate (1 V/s)
|
||||||
|
Volts.of(4), // Reduce dynamic step voltage to 4 V to prevent brownout
|
||||||
|
null, // Use default timeout (10 s)
|
||||||
|
// Log state with SignalLogger class
|
||||||
|
state -> SignalLogger.writeString("SysIdTranslation_State", state.toString())
|
||||||
|
),
|
||||||
|
new SysIdRoutine.Mechanism(
|
||||||
|
output -> setControl(m_translationCharacterization.withVolts(output)),
|
||||||
|
null,
|
||||||
|
this
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
/* SysId routine for characterizing steer. This is used to find PID gains for the steer motors. */
|
||||||
|
private final SysIdRoutine m_sysIdRoutineSteer = new SysIdRoutine(
|
||||||
|
new SysIdRoutine.Config(
|
||||||
|
null, // Use default ramp rate (1 V/s)
|
||||||
|
Volts.of(7), // Use dynamic voltage of 7 V
|
||||||
|
null, // Use default timeout (10 s)
|
||||||
|
// Log state with SignalLogger class
|
||||||
|
state -> SignalLogger.writeString("SysIdSteer_State", state.toString())
|
||||||
|
),
|
||||||
|
new SysIdRoutine.Mechanism(
|
||||||
|
volts -> setControl(m_steerCharacterization.withVolts(volts)),
|
||||||
|
null,
|
||||||
|
this
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* SysId routine for characterizing rotation.
|
||||||
|
* This is used to find PID gains for the FieldCentricFacingAngle HeadingController.
|
||||||
|
* See the documentation of SwerveRequest.SysIdSwerveRotation for info on importing the log to SysId.
|
||||||
|
*/
|
||||||
|
private final SysIdRoutine m_sysIdRoutineRotation = new SysIdRoutine(
|
||||||
|
new SysIdRoutine.Config(
|
||||||
|
/* This is in radians per second², but SysId only supports "volts per second" */
|
||||||
|
Volts.of(Math.PI / 6).per(Second),
|
||||||
|
/* This is in radians per second, but SysId only supports "volts" */
|
||||||
|
Volts.of(Math.PI),
|
||||||
|
null, // Use default timeout (10 s)
|
||||||
|
// Log state with SignalLogger class
|
||||||
|
state -> SignalLogger.writeString("SysIdRotation_State", state.toString())
|
||||||
|
),
|
||||||
|
new SysIdRoutine.Mechanism(
|
||||||
|
output -> {
|
||||||
|
/* output is actually radians per second, but SysId only supports "volts" */
|
||||||
|
setControl(m_rotationCharacterization.withRotationalRate(output.in(Volts)));
|
||||||
|
/* also log the requested output for SysId */
|
||||||
|
SignalLogger.writeDouble("Rotational_Rate", output.in(Volts));
|
||||||
|
},
|
||||||
|
null,
|
||||||
|
this
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
/* The SysId routine to test */
|
||||||
|
private SysIdRoutine m_sysIdRoutineToApply = m_sysIdRoutineTranslation;
|
||||||
|
|
||||||
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
|
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
|
||||||
private void configureAutoBuilder() {
|
private void configureAutoBuilder() {
|
||||||
try {
|
try {
|
||||||
@@ -162,6 +229,20 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
|||||||
public Command applyRequest(Supplier<SwerveRequest> request) {
|
public Command applyRequest(Supplier<SwerveRequest> request) {
|
||||||
return run(() -> this.setControl(request.get()));
|
return run(() -> this.setControl(request.get()));
|
||||||
}
|
}
|
||||||
|
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
|
||||||
|
return m_sysIdRoutineToApply.quasistatic(direction);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Runs the SysId Dynamic test in the given direction for the routine
|
||||||
|
* specified by {@link #m_sysIdRoutineToApply}.
|
||||||
|
*
|
||||||
|
* @param direction Direction of the SysId Dynamic test
|
||||||
|
* @return Command to run
|
||||||
|
*/
|
||||||
|
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
|
||||||
|
return m_sysIdRoutineToApply.dynamic(direction);
|
||||||
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
|||||||
Reference in New Issue
Block a user