Fixed Deadband Issue

Made motors running at same speed.
This commit is contained in:
aarav18
2020-01-18 09:27:53 -08:00
parent 4d7a03d230
commit c72a32efb2
2 changed files with 8 additions and 5 deletions
@@ -88,8 +88,8 @@ public class RobotContainer {
new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON)
.whenPressed(new DriveAtVelocityPID(m_robotDrive, 2000));
new JoystickButton(getDriverJoystick(), XboxController.LEFT_JOYSTICK_BUTTON)
.whenPressed(new InstantCommand(null, m_robotDrive));
//new JoystickButton(getDriverJoystick(), XboxController.LEFT_JOYSTICK_BUTTON)
//.whenPressed(new InstantCommand(null, m_robotDrive));
}
/**
@@ -61,6 +61,9 @@ public class Drive extends SubsystemBase {
m_leftBackMotor.setInverted(InvertType.FollowMaster);
m_rightBackMotor.setInverted(InvertType.FollowMaster);
m_leftBackMotor.configNeutralDeadband(0.0); // DO NOT CHANGE
m_rightBackMotor.configNeutralDeadband(0.0); //Ensures motors run at the same speed
/* Motor Encoders */
//m_leftFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, DriveConstants.DRIVE_PID_LOOP_IDX, DriveConstants.DRIVE_TIMEOUT_MS);
//m_rightFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, DriveConstants.DRIVE_PID_LOOP_IDX, DriveConstants.DRIVE_TIMEOUT_MS);
@@ -83,7 +86,7 @@ public class Drive extends SubsystemBase {
m_leftFrontMotor.configMotionAcceleration(6000, DriveConstants.DRIVE_TIMEOUT_MS);
m_rightFrontMotor.configMotionCruiseVelocity(15000, DriveConstants.DRIVE_TIMEOUT_MS);
m_rightFrontMotor.configMotionAcceleration(6000, DriveConstants.DRIVE_TIMEOUT_MS);
m_leftFrontMotor.setSelectedSensorPosition(0, DriveConstants.DRIVE_PID_LOOP_IDX, DriveConstants.DRIVE_TIMEOUT_MS);
m_rightFrontMotor.setSelectedSensorPosition(0, DriveConstants.DRIVE_PID_LOOP_IDX, DriveConstants.DRIVE_TIMEOUT_MS);
@@ -142,8 +145,8 @@ public class Drive extends SubsystemBase {
public void setDriveTrainNeutralMode(NeutralMode mode) {
m_leftFrontMotor.setNeutralMode(mode);
m_rightFrontMotor.setNeutralMode(mode);
m_leftFrontMotor.setNeutralMode(mode);
m_rightFrontMotor.setNeutralMode(mode);
m_leftBackMotor.setNeutralMode(mode);
m_rightBackMotor.setNeutralMode(mode);
}
/**