sisid manque drive
This commit is contained in:
		| @@ -22,6 +22,7 @@ import edu.wpi.first.wpilibj2.command.Command; | ||||
| import edu.wpi.first.wpilibj2.command.Commands; | ||||
| import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; | ||||
| import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | ||||
| import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; | ||||
| import frc.robot.TunerConstants.TunerConstants; | ||||
| import frc.robot.commands.AprilTag3; | ||||
| import frc.robot.commands.AprilTag3G; | ||||
| @@ -77,6 +78,10 @@ public class RobotContainer { | ||||
|         ); | ||||
|  | ||||
|         // reset the field-centric heading on left bumper press | ||||
|         manette1.y().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kForward)); | ||||
|         manette1.a().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kReverse)); | ||||
|         manette1.b().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kForward)); | ||||
|         manette1.x().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kReverse)); | ||||
|         manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric())); | ||||
|         manette1.leftTrigger().whileTrue(new AprilTag3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||
|         manette1.rightTrigger().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||
|   | ||||
| @@ -24,8 +24,8 @@ public class TunerConstants { | ||||
|     // The steer motor uses any SwerveModule.SteerRequestType control request with the | ||||
|     // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput | ||||
|     private static final Slot0Configs steerGains = new Slot0Configs() | ||||
|         .withKP(100).withKI(0).withKD(0.5) | ||||
|         .withKS(0.1).withKV(2.66).withKA(0) | ||||
|         .withKP(52.109).withKI(0).withKD(3.0232) | ||||
|         .withKS(0.24757).withKV(2.4715).withKA(0.062286) | ||||
|         .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); | ||||
|     // When using closed-loop control, the drive motor uses the control | ||||
|     // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput | ||||
|   | ||||
		Reference in New Issue
	
	Block a user