|
35 | 35 |
|
36 | 36 | namespace constants {
|
37 | 37 | namespace Vision {
|
38 |
| -static constexpr std::string_view kCameraName{"YOUR CAMERA NAME"}; |
39 |
| -static const frc::Transform3d kRobotToCam{ |
| 38 | +inline constexpr std::string_view kCameraName{"YOUR CAMERA NAME"}; |
| 39 | +inline const frc::Transform3d kRobotToCam{ |
40 | 40 | frc::Translation3d{0.5_m, 0.0_m, 0.5_m},
|
41 | 41 | frc::Rotation3d{0_rad, 0_rad, 0_rad}};
|
42 |
| -static const frc::AprilTagFieldLayout kTagLayout{ |
43 |
| - frc::LoadAprilTagLayoutField(frc::AprilTagField::k2023ChargedUp)}; |
| 42 | +inline const frc::AprilTagFieldLayout kTagLayout{ |
| 43 | + frc::LoadAprilTagLayoutField(frc::AprilTagField::k2024Crescendo)}; |
44 | 44 |
|
45 |
| -static const Eigen::Matrix<double, 3, 1> kSingleTagStdDevs{4, 4, 8}; |
46 |
| -static const Eigen::Matrix<double, 3, 1> kMultiTagStdDevs{0.5, 0.5, 1}; |
| 45 | +inline const Eigen::Matrix<double, 3, 1> kSingleTagStdDevs{4, 4, 8}; |
| 46 | +inline const Eigen::Matrix<double, 3, 1> kMultiTagStdDevs{0.5, 0.5, 1}; |
47 | 47 | } // namespace Vision
|
48 | 48 | namespace Swerve {
|
49 | 49 |
|
50 |
| -static constexpr units::meter_t kTrackWidth{18.5_in}; |
51 |
| -static constexpr units::meter_t kTrackLength{18.5_in}; |
52 |
| -static constexpr units::meter_t kRobotWidth{25_in + 3.25_in * 2}; |
53 |
| -static constexpr units::meter_t kRobotLength{25_in + 3.25_in * 2}; |
54 |
| -static constexpr units::meters_per_second_t kMaxLinearSpeed{15.5_fps}; |
55 |
| -static constexpr units::radians_per_second_t kMaxAngularSpeed{720_deg_per_s}; |
56 |
| -static constexpr units::meter_t kWheelDiameter{4_in}; |
57 |
| -static constexpr units::meter_t kWheelCircumference{kWheelDiameter * |
| 50 | +inline constexpr units::meter_t kTrackWidth{18.5_in}; |
| 51 | +inline constexpr units::meter_t kTrackLength{18.5_in}; |
| 52 | +inline constexpr units::meter_t kRobotWidth{25_in + 3.25_in * 2}; |
| 53 | +inline constexpr units::meter_t kRobotLength{25_in + 3.25_in * 2}; |
| 54 | +inline constexpr units::meters_per_second_t kMaxLinearSpeed{15.5_fps}; |
| 55 | +inline constexpr units::radians_per_second_t kMaxAngularSpeed{720_deg_per_s}; |
| 56 | +inline constexpr units::meter_t kWheelDiameter{4_in}; |
| 57 | +inline constexpr units::meter_t kWheelCircumference{kWheelDiameter * |
58 | 58 | std::numbers::pi};
|
59 | 59 |
|
60 |
| -static constexpr double kDriveGearRatio = 6.75; |
61 |
| -static constexpr double kSteerGearRatio = 12.8; |
| 60 | +inline constexpr double kDriveGearRatio = 6.75; |
| 61 | +inline constexpr double kSteerGearRatio = 12.8; |
62 | 62 |
|
63 |
| -static constexpr units::meter_t kDriveDistPerPulse = |
| 63 | +inline constexpr units::meter_t kDriveDistPerPulse = |
64 | 64 | kWheelCircumference / 1024.0 / kDriveGearRatio;
|
65 |
| -static constexpr units::radian_t kSteerRadPerPulse = |
| 65 | +inline constexpr units::radian_t kSteerRadPerPulse = |
66 | 66 | units::radian_t{2 * std::numbers::pi} / 1024.0;
|
67 | 67 |
|
68 |
| -static constexpr double kDriveKP = 1.0; |
69 |
| -static constexpr double kDriveKI = 0.0; |
70 |
| -static constexpr double kDriveKD = 0.0; |
| 68 | +inline constexpr double kDriveKP = 1.0; |
| 69 | +inline constexpr double kDriveKI = 0.0; |
| 70 | +inline constexpr double kDriveKD = 0.0; |
71 | 71 |
|
72 |
| -static constexpr double kSteerKP = 20.0; |
73 |
| -static constexpr double kSteerKI = 0.0; |
74 |
| -static constexpr double kSteerKD = 0.25; |
| 72 | +inline constexpr double kSteerKP = 20.0; |
| 73 | +inline constexpr double kSteerKI = 0.0; |
| 74 | +inline constexpr double kSteerKD = 0.25; |
75 | 75 |
|
76 |
| -static const frc::SimpleMotorFeedforward<units::meters> kDriveFF{ |
| 76 | +inline const frc::SimpleMotorFeedforward<units::meters> kDriveFF{ |
77 | 77 | 0.25_V, 2.5_V / 1_mps, 0.3_V / 1_mps_sq};
|
78 | 78 |
|
79 |
| -static const frc::SimpleMotorFeedforward<units::radians> kSteerFF{ |
| 79 | +inline const frc::SimpleMotorFeedforward<units::radians> kSteerFF{ |
80 | 80 | 0.5_V, 0.25_V / 1_rad_per_s, 0.01_V / 1_rad_per_s_sq};
|
81 | 81 |
|
82 | 82 | struct ModuleConstants {
|
@@ -106,13 +106,13 @@ struct ModuleConstants {
|
106 | 106 | centerOffset(frc::Translation2d{xOffset, yOffset}) {}
|
107 | 107 | };
|
108 | 108 |
|
109 |
| -static const ModuleConstants FL_CONSTANTS{ |
| 109 | +inline const ModuleConstants FL_CONSTANTS{ |
110 | 110 | 1, 0, 0, 1, 1, 2, 3, 0, kTrackLength / 2, kTrackWidth / 2};
|
111 |
| -static const ModuleConstants FR_CONSTANTS{ |
| 111 | +inline const ModuleConstants FR_CONSTANTS{ |
112 | 112 | 2, 2, 4, 5, 3, 6, 7, 0, kTrackLength / 2, -kTrackWidth / 2};
|
113 |
| -static const ModuleConstants BL_CONSTANTS{ |
| 113 | +inline const ModuleConstants BL_CONSTANTS{ |
114 | 114 | 3, 4, 8, 9, 5, 10, 11, 0, -kTrackLength / 2, kTrackWidth / 2};
|
115 |
| -static const ModuleConstants BR_CONSTANTS{ |
| 115 | +inline const ModuleConstants BR_CONSTANTS{ |
116 | 116 | 4, 6, 12, 13, 7, 14, 15, 0, -kTrackLength / 2, -kTrackWidth / 2};
|
117 | 117 | } // namespace Swerve
|
118 | 118 | } // namespace constants
|
0 commit comments