Skip to content

Commit

Permalink
new table
Browse files Browse the repository at this point in the history
  • Loading branch information
r4stered committed Oct 23, 2024
1 parent 243e829 commit 22f757a
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 12 deletions.
15 changes: 9 additions & 6 deletions src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,15 @@ void Robot::RobotInit() {
consts::SWERVE_ODOM_LOOP_PERIOD, 2_ms);

m_container.GetShooterSubsystem().SetupLUTs({
{65_in, {1200_rpm, 3500_rpm}},
{78_in, {2500_rpm, 2500_rpm}},
{102_in, {3000_rpm, 1900_rpm}},
{114_in, {3400_rpm, 1900_rpm}},
{127_in, {5000_rpm, 1600_rpm}},
{143_in, {5000_rpm, 1200_rpm}},
{48.13379_in, {1200_rpm, 3200_rpm}},
{59.13379_in, {1500_rpm, 1333.333_rpm}},
{71.73379_in, {2200_rpm, 1294.118_rpm}},
{84.43379_in, {2700_rpm, 1538.86_rpm}},
{95.73379_in, {3000_rpm, 1344.916_rpm}},
{107.9338_in, {2900_rpm, 1359.704_rpm}},
{120.3338_in, {2800_rpm, 1268.679_rpm}},
{133.1338_in, {2800_rpm, 1155.414_rpm}},
{144.2338_in, {2700_rpm, 1231.622_rpm}},
});
}

Expand Down
6 changes: 1 addition & 5 deletions src/main/cpp/subsystems/SwerveSubsystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void SwerveSubsystem::Periodic() {
swerveDrive.UpdateNTEntries();
frc::SmartDashboard::PutNumber("Distance to Speaker Center", GetDistanceToSpeaker(SpeakerSide::CENTER).convert<units::inches>().value());
frc::SmartDashboard::PutNumber("Distance to Speaker Amp", GetDistanceToSpeaker(SpeakerSide::AMP_SIDE).convert<units::inches>().value());
frc::SmartDashboard::PutNumber("Distance to Speaker Center", GetDistanceToSpeaker(SpeakerSide::SOURCE).convert<units::inches>().value());
frc::SmartDashboard::PutNumber("Distance to Speaker Source", GetDistanceToSpeaker(SpeakerSide::SOURCE).convert<units::inches>().value());
}

void SwerveSubsystem::SimulationPeriodic() {
Expand Down Expand Up @@ -193,17 +193,13 @@ frc2::CommandPtr SwerveSubsystem::FaceSpeaker(
}
}

fmt::print("speaker location: {}, {}\n", speakerLocation.X(), speakerLocation.Y());

frc::Translation2d diff = robotPosition - speakerLocation;

units::radian_t angleToSpeaker = units::math::atan2(diff.Y(), diff.X());


angleToSpeaker = angleToSpeaker + 180_deg;

fmt::print("speaker goal: {}\n", angleToSpeaker.convert<units::degrees>());

thetaController.SetGoal(angleToSpeaker);

units::radians_per_second_t thetaSpeed{
Expand Down
2 changes: 1 addition & 1 deletion src/main/include/constants/ShooterConstants.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ struct ShooterSpeeds {
};

inline constexpr ShooterSpeeds AMP_SPEEDS{850_rpm, 2000_rpm};
inline constexpr ShooterSpeeds SUBWOOFER_SPEEDS{5000_rpm, 5000_rpm};
inline constexpr ShooterSpeeds SUBWOOFER_SPEEDS{1200_rpm, 3200_rpm};
inline constexpr ShooterSpeeds PASS_SPEEDS{5000_rpm, 5000_rpm};

struct MeterHash {
Expand Down

0 comments on commit 22f757a

Please sign in to comment.