mirror of
https://github.com/Team4388/2024AcrossTheRidgebotiverse.git
synced 2026-06-08 16:28:03 -06:00
Add rumble
This commit is contained in:
@@ -74,13 +74,13 @@ public class RobotContainer {
|
||||
private final DeadbandedXboxController m_driverXbox = new DeadbandedXboxController(OIConstants.XBOX_DRIVER_ID);
|
||||
private final DeadbandedXboxController m_operatorXbox = new DeadbandedXboxController(OIConstants.XBOX_OPERATOR_ID);
|
||||
private final DeadbandedXboxController m_autoRecorderXbox = new DeadbandedXboxController(2);
|
||||
|
||||
private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.pivotMotor);
|
||||
|
||||
/* Virtual Controllers */
|
||||
private final VirtualController m_virtualDriver = new VirtualController(0);
|
||||
private final VirtualController m_virtualOperator = new VirtualController(1);
|
||||
|
||||
private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.pivotMotor, m_driverXbox, m_operatorXbox);
|
||||
|
||||
private Command intakeToShootStuff = new ArmIntakeIn(m_robotIntake, m_robotShooter);
|
||||
private Command interrupt = new InstantCommand(() -> {}, m_robotIntake, m_robotShooter);
|
||||
|
||||
|
||||
@@ -35,6 +35,7 @@ import frc4388.robot.Constants.IntakeConstants;
|
||||
import frc4388.robot.commands.PID;
|
||||
import frc4388.utility.Gains;
|
||||
import frc4388.utility.configurable.ConfigurableDouble;
|
||||
import frc4388.utility.controller.DeadbandedXboxController;
|
||||
|
||||
public class Intake extends SubsystemBase {
|
||||
|
||||
@@ -52,6 +53,9 @@ public class Intake extends SubsystemBase {
|
||||
private TalonFX talonPivot;
|
||||
private CANcoder encoder;
|
||||
|
||||
private DeadbandedXboxController m_driverXbox;
|
||||
private DeadbandedXboxController m_operatorXbox;
|
||||
|
||||
private boolean r;
|
||||
|
||||
private HardwareLimitSwitchConfigs l;
|
||||
@@ -96,9 +100,12 @@ public class Intake extends SubsystemBase {
|
||||
// }
|
||||
|
||||
//For Talon
|
||||
public Intake(TalonFX talonIntake, TalonFX talonPivot) {
|
||||
public Intake(TalonFX talonIntake, TalonFX talonPivot, DeadbandedXboxController driverXbox, DeadbandedXboxController operatorXbox) {
|
||||
this.talonIntake = talonIntake;
|
||||
this.talonPivot = talonPivot;
|
||||
|
||||
this.m_driverXbox = driverXbox;
|
||||
this.m_operatorXbox = operatorXbox;
|
||||
|
||||
talonIntake.getConfigurator().apply(new TalonFXConfiguration());
|
||||
talonPivot.getConfigurator().apply(new TalonFXConfiguration());
|
||||
@@ -323,6 +330,8 @@ public class Intake extends SubsystemBase {
|
||||
// }
|
||||
// }
|
||||
|
||||
private boolean isRumble = false;
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
@@ -336,5 +345,15 @@ public class Intake extends SubsystemBase {
|
||||
SmartDashboard.putNumber("Pivot Position", getArmPos());
|
||||
|
||||
smartDashboardOuttakeValue = SmartDashboard.getNumber("Outtake Speed", IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED);
|
||||
|
||||
// System.out.println(getTalonIntakeLimitSwitchState());
|
||||
|
||||
if(getTalonIntakeLimitSwitchState() && !isRumble){
|
||||
m_driverXbox.rumble(1);
|
||||
m_operatorXbox.rumble(1);
|
||||
isRumble = true;
|
||||
}else if(!getTalonIntakeLimitSwitchState() && isRumble){
|
||||
isRumble = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package frc4388.utility.configurable;
|
||||
package frc4388.utility.Configurable;
|
||||
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
|
||||
|
||||
@@ -24,4 +24,30 @@ public class DeadbandedXboxController extends XboxController {
|
||||
|
||||
return translation2d;
|
||||
}
|
||||
|
||||
/*
|
||||
Rumble for a select amount of time
|
||||
|
||||
For some reason, you cannot rumble an xbox controller while simulating the robot.
|
||||
This took me a very long time to find out.
|
||||
*/
|
||||
public void rumble(int seconds){
|
||||
//Default value
|
||||
|
||||
new Thread(() -> {
|
||||
// System.out.println("Start rumble");
|
||||
setRumble(RumbleType.kLeftRumble, 1.0);
|
||||
setRumble(RumbleType.kRightRumble, 1.0);
|
||||
|
||||
try {
|
||||
Thread.sleep(seconds*1000);
|
||||
} catch (InterruptedException e) {}
|
||||
|
||||
// System.out.println("Stop rumble");
|
||||
setRumble(RumbleType.kLeftRumble, 0.0);
|
||||
setRumble(RumbleType.kRightRumble, 0.0);
|
||||
|
||||
}).start();
|
||||
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user