Skip to content

Remap keypad bindings #155

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 7 commits into from
Apr 18, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
106 changes: 49 additions & 57 deletions src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,105 +204,97 @@ void RobotContainer::ConfigureButtonBindings() {

#ifndef TEST_SWERVE_BOT
void RobotContainer::ConfigureAutoBindings() {
// Maps to 9 on keyboard
m_operatorController.A().OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::ScoringSpeaker;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 8 on keyboard
m_operatorController.B().OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::ScoringSubwoofer;
m_state.SetDesiredState();
}
}).ToPtr());
// Maps to / on keyboard
// m_operatorController.Button(0).OnTrue(
// TODO: GOTO APPROX SCORING
// );

// Maps to NUM LOCK on keyboard
m_operatorController.Button(3).OnTrue(
// GOTO SRC
frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState = RobotState::SourceCenter;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 7 on keyboard
m_operatorController.X().OnTrue(frc2::InstantCommand([this] {
m_operatorController.Button(4).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::ScoringAmp;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 4 on keyboard
m_operatorController.Y().OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::AutoSequenceAmp;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 1 on keyboard
m_operatorController.LeftBumper().OnTrue(frc2::InstantCommand([this] {
// Maps to 8 on keyboard
m_operatorController.Button(5).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::ClimbStageLeft;
RobotState::ScoringSpeaker;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 2 on keyboard
// m_operatorController.RightBumper().OnTrue(
// frc2::InstantCommand([this] {
// if (!m_state.m_active) {
// m_state.m_currentState = RobotState::ClimbStageCenter;
// m_state.SetDesiredState();
// }
// }).ToPtr());
m_operatorController.RightBumper().OnTrue(
m_rightClimb.MoveToPositionAbsolute(18_in));
// Maps to 9 on keyboard
m_operatorController.Button(6).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::ScoringSubwoofer;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 3 on keyboard
m_operatorController.LeftStick().OnTrue(frc2::InstantCommand([this] {
// Maps to 4 on keyboard
m_operatorController.Button(7).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::ClimbStageRight;
RobotState::AutoSequenceAmp;
m_state.SetDesiredState();
}
}).ToPtr());

m_operatorController.Button(15).OnTrue(frc2::InstantCommand([this] {
// Maps to 5 on keyboard
m_operatorController.Button(8).OnTrue(
frc2::InstantCommand([this] { m_drive.ZeroHeading(); }).ToPtr());

// Maps to 6 on keyboard
m_operatorController.Button(9).OnTrue(
m_rightClimb.MoveToPositionAbsolute(18_in).AlongWith(
m_leftClimb.MoveToPositionAbsolute(18_in)));

// Maps to 1 on keyboard
m_operatorController.Button(10).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::SourceLeft;
RobotState::ClimbStageLeft;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 2 on keyboard
m_operatorController.Button(16).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::SourceCenter;
RobotState::ClimbStageCenter;
m_state.SetDesiredState();
}
}).ToPtr());

// Maps to 3 on keyboard
m_operatorController.Button(17).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::SourceRight;
RobotState::ClimbStageRight;
m_state.SetDesiredState();
}
}).ToPtr());

m_operatorController.Button(18).OnTrue(frc2::InstantCommand([this] {
if (!m_state.m_active) {
m_state.m_currentState =
RobotState::Funni;
m_state.SetDesiredState();
}
}).ToPtr());

m_operatorController.Button(20).OnTrue(
frc2::InstantCommand([this] { m_drive.ZeroHeading(); }).ToPtr());
// Maps to 0 on keyboard
// m_operatorController.Button(17).OnTrue(
// TODO: FEED SCORING COMMAND
// );
}
#endif

Expand Down
2 changes: 1 addition & 1 deletion src/main/cpp/subsystems/StateSubsystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ bool StateSubsystem::IsControllerActive() {
active |= m_driverController.GetPOV(i) != -1;
}
// Check the operator's "stop" button
active |= m_operatorController.RightStick().Get();
active |= m_operatorController.Button(19).Get();
if (active) {
ConsoleWriter.logVerbose("StateSubsystem", "Controller interrupt! %s", "");
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/deploy/pathplanner/paths/Note 2 to Speaker.path
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
"eventMarkers": [
{
"name": "New Event Marker",
"waypointRelativePos": 0.0,
"waypointRelativePos": 0.2,
"command": {
"type": "parallel",
"data": {
Expand Down
5 changes: 3 additions & 2 deletions src/main/include/Constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ constexpr double kVectorSpeed = -0.4;

// These need to be different
// TODO: CHANGE TO VELOCITY RATHER THAN % OUTPUT
constexpr double kAmpLowerSpeed = -0.254 * 1.4; // .264
constexpr double kAmpLowerSpeed = -0.254 * 1.9; // .264
constexpr double kAmpUpperSpeed = -0.168 * 1.4; // .278

// These should match
Expand Down Expand Up @@ -486,7 +486,8 @@ constexpr double kRotationHomingSpeed = .15;
constexpr int kArmGearRatio = 125;
constexpr units::degree_t kArmRelativeDistancePerRev = 360_deg * (1 / 8.75);
constexpr units::degree_t kArmAbsoluteDistancePerRev = 360_deg;
constexpr units::degree_t kAmpRotation = 190_deg;
constexpr units::degree_t kAmpRotation = 142_deg;
constexpr units::degree_t kMaxRotation = 190_deg;
constexpr units::degree_t kHomeRotation = 10_deg;
constexpr units::degrees_per_second_t kDefaultVelocity = 10_deg_per_s;
constexpr double kVelocityScalar = 1.0;
Expand Down
2 changes: 1 addition & 1 deletion src/main/include/subsystems/ArmSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ class ArmSubsystem : public RotationalSingleAxisSubsystem<
{// Min distance
ArmConstants::kHomeRotation,
// Max distance
ArmConstants::kAmpRotation,
ArmConstants::kMaxRotation,
// Distance per revolution of relative encoder
ArmConstants::kArmRelativeDistancePerRev,
// Distance per revolution of absolute encoder
Expand Down