Skip to content

Commit

Permalink
set x driver button to clench, behavior for intake retract and deploy…
Browse files Browse the repository at this point in the history
… working, changed max speed values to usable values
  • Loading branch information
CooperNelson16 authored and mray190 committed Sep 14, 2022
1 parent fdfcc6e commit 85bebfd
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 15 deletions.
12 changes: 5 additions & 7 deletions Competition/src/main/cpp/subsystems/Feeder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,19 +41,16 @@ void Feeder::init()
motor_stage.SetInverted(true);
motor_stage.EnableVoltageCompensation(true);
motor_stage.ConfigVoltageCompSaturation(10);





motor_rotateMain.ConfigForwardSoftLimitThreshold(FeederConstants::rotateForwardLimit);
motor_rotateMain.ConfigReverseSoftLimitThreshold(FeederConstants::rotateReverseLimit);

motor_rotateMain.ConfigForwardSoftLimitEnable(true);
motor_rotateMain.ConfigReverseSoftLimitEnable(true);

motor_rotateMain.SetSelectedSensorPosition(0);
motor_rotateMain.SetInverted(false); // needs to be tested
motor_rotateFollow.SetInverted(true); // needs to be tested
motor_rotateMain.SetInverted(true); // needs to be tested
motor_rotateFollow.SetInverted(false); // needs to be tested
motor_rotateFollow.Follow(motor_rotateMain);

motor_rotateMain.SetNeutralMode(ctre::phoenix::motorcontrol::Brake);
Expand Down Expand Up @@ -110,7 +107,7 @@ void Feeder::assessInputs()
state.feederState = FeederState::FEEDER_SHOOT; //intake and feeder run
resetIntakeSensor();
}
else if (driverController->GetBButton()) {
else if (driverController->GetXButton()) {
state.feederState = FeederState::FEEDER_RETRACT; //Set Intake rotate to upper setpoint
}
else if (driverController->GetLeftBumper()) {
Expand Down Expand Up @@ -144,6 +141,7 @@ void Feeder::analyzeDashboard()
table->PutBoolean("Banner: ", debounceSensor.getSensor());
table->PutNumber("current feeder state", state.feederState);

table->PutNumber("Intake Encoder Value", motor_rotateMain.GetSelectedSensorPosition());
}

void Feeder::assignOutputs()
Expand Down
3 changes: 2 additions & 1 deletion Competition/src/main/cpp/subsystems/Shooter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ void Shooter::init()
{
limeTable = nt::NetworkTableInstance::GetDefault().GetTable("limelight");
liftTable = nt::NetworkTableInstance::GetDefault().GetTable("Lift");
feederTable = nt::NetworkTableInstance::GetDefault().GetTable("Feeder");
initTable("Shooter");

table->PutBoolean("Zero Turret", false);
Expand Down Expand Up @@ -174,7 +175,7 @@ void Shooter::assessInputs()
state.turretState = TurretState::TURRET_HOME_LEFT;
}
else {
state.turretState == TurretState::TURRET_HOME_RIGHT;
state.turretState = TurretState::TURRET_HOME_RIGHT;
}
}
else if (operatorController->leftStickXActive()) {
Expand Down
2 changes: 1 addition & 1 deletion Competition/src/main/cpp/subsystems/ValorSwerve.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ void ValorSwerve::loadAndSetAzimuthZeroReference()
//azimuthSetpoint = fmod(azimuthSetpoint, SwerveConstants::AZIMUTH_COUNTS_PER_REV / SwerveConstants::AZIMUTH_GEAR_RATIO);

// Set the azimuth offset to the calculated setpoint (which will take over in teleop)
azimuthFalcon->SetSelectedSensorPosition(azimuthSetpoint, 0, 10);
azimuthFalcon->SetSelectedSensorPosition(0, 0, 10);
//std::cout << "pulled pospition from file" << std::endl;
}

Expand Down
9 changes: 3 additions & 6 deletions Competition/src/main/include/Constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -258,19 +258,16 @@ namespace FeederConstants{

constexpr static double tickToDegree = ((4200.0 /144.0) * 2048.0 ) / 360.0;

constexpr static double rotateForwardLimit = 10 * tickToDegree;
constexpr static double rotateForwardLimit = 20 * tickToDegree;
constexpr static double rotateReverseLimit = 0;




constexpr static double main_KF = 0.05;
constexpr static double main_KD = 0.0;
constexpr static double main_KI = 0.0;
constexpr static double main_KP = 0.1;

constexpr static double MAIN_MOTION_CRUISE_VELOCITY = 4000;
constexpr static double MAIN_MOTION_ACCELERATION = MAIN_MOTION_CRUISE_VELOCITY * 1;
constexpr static double MAIN_MOTION_CRUISE_VELOCITY = 15000;
constexpr static double MAIN_MOTION_ACCELERATION = MAIN_MOTION_CRUISE_VELOCITY * 5;



Expand Down

0 comments on commit 85bebfd

Please sign in to comment.