Skip to content

Commit

Permalink
testing on robot (#26)
Browse files Browse the repository at this point in the history
Harsh & Lucas configured and tuned launcher for L2 and some base testing on L1
  • Loading branch information
nick-mcgill authored Mar 8, 2025
1 parent 86c21dc commit 1ca0a94
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 14 deletions.
9 changes: 9 additions & 0 deletions src/main/cpp/ControllerInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,15 @@ void ControllerInterface::UpdateLauncherInput(RobotControlData &controlData){
controlData.coralInput.setFlywheelToL1Speed = m_pilot.GetAButton();
controlData.coralInput.setFlywheelToL2Speed = m_pilot.GetBButton();
controlData.coralInput.disableFlywheels = m_pilot.GetYButton();

if (m_pilot.GetXButton())
{
controlData.coralInput.indexerSpeeds = 0.7f;
}
else
{
controlData.coralInput.indexerSpeeds = 0.0f;
}
}

void ControllerInterface::UpdateSmartplannerInput(RobotControlData &controlData)
Expand Down
10 changes: 5 additions & 5 deletions src/main/cpp/InputManager/CoralLauncherManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,18 @@ void CoralLauncherManager::HandleInput(RobotControlData &robotControlData){
}

if(m_setFlywheelToL1Speed){
m_CoralLauncher.SetWheelSpeeds(1.0,1.0); //configure speeds
m_CoralLauncher.SetWheelSpeeds(300.0, 500.0); //configure speeds
}
if(m_setFlywheelToL2Speed){
m_CoralLauncher.SetWheelSpeeds(1.0,1.0); //config speeds
m_CoralLauncher.SetWheelSpeeds(1050.0, 1050.0); //config speeds
}
if(m_setFlywheelToZeroSpeed){
m_CoralLauncher.SetWheelSpeeds(0.0,0.0);
}
m_CoralLauncher.SetIndexerSpeeds(robotControlData.coralInput.indexerSpeeds);
if(m_CoralLauncher.BeamBreakStatus()){
m_CoralLauncher.SetWheelSpeeds(0,0);
}
// if(m_CoralLauncher.BeamBreakStatus()){
// m_CoralLauncher.SetWheelSpeeds(0,0);
// }
robotControlData.coralOutput.isBeamBroken = m_CoralLauncher.BeamBreakStatus();
robotControlData.coralOutput.leftSpeed = m_CoralLauncher.GetLeftWheelSpeed();
robotControlData.coralOutput.rightSpeed = m_CoralLauncher.GetRightWheelSpeed();
Expand Down
4 changes: 2 additions & 2 deletions src/main/include/HAL/AlgaeRemoverHAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ class AlgaeRemover
private:
void SetAngle(double angle);

rev::spark::SparkMax m_armMotor{40, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_removerMotor{41, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_armMotor{100, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_removerMotor{101, rev::spark::SparkMax::MotorType::kBrushless};
double m_removerSpeed;
frc::Timer m_Timer = frc::Timer();
int m_algaeRemoverState = 0;
Expand Down
10 changes: 5 additions & 5 deletions src/main/include/HAL/CoralLauncherHAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@ class CoralLauncher
bool AreFlywheelsAtDesiredSpeed();
bool BeamBreakStatus();
private:
rev::spark::SparkMax m_rightMotor{30, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_leftMotor{31, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_indexer1{32, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_indexer2{33, rev::spark::SparkMax::MotorType::kBrushless};
frc::DigitalInput m_beam_break{34}; //moved from CoralLauncherManager; move back if needed
rev::spark::SparkMax m_rightMotor{43, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_leftMotor{42, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_indexer1{40, rev::spark::SparkMax::MotorType::kBrushless};
rev::spark::SparkMax m_indexer2{41, rev::spark::SparkMax::MotorType::kBrushless};
frc::DigitalInput m_beam_break{0}; //moved from CoralLauncherManager; move back if needed
double m_desiredRightSpeed;
double m_desiredLeftSpeed;
const double SMALL_NUM = 0.001; //change variable name accordingly; make a more suitable name
Expand Down
4 changes: 2 additions & 2 deletions src/main/include/MechanismConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@ namespace ratbot
const double F = 0.0;
const double VEL_CONV_FACTOR = 1.0;
const double CURRENT_LIM = 30.0;
const bool INVERTED = false;
const bool INVERTED = true;
rev::spark::SparkBaseConfig::IdleMode IDLE_MODE = rev::spark::SparkBaseConfig::IdleMode::kCoast;
}

namespace Indexer
{
const double CURRENT_LIM = 20.0;
const bool INVERTED = false;
const bool INVERTED = true;
rev::spark::SparkBaseConfig::IdleMode IDLE_MODE = rev::spark::SparkBaseConfig::IdleMode::kCoast;
}
}
Expand Down

0 comments on commit 1ca0a94

Please sign in to comment.