Skip to content

Commit a3e1dda

Browse files
r4steredDrew Williams
andauthored
Fixed cpp sim apriltag layout and cleaned up cpp sim example (#1190)
* Fixed cpp sim apriltag layout and cleaned up cpp sim example * changed layout for photoncamerasim --------- Co-authored-by: Drew Williams <[email protected]>
1 parent 939283d commit a3e1dda

File tree

3 files changed

+34
-36
lines changed

3 files changed

+34
-36
lines changed

photon-lib/src/main/native/include/photon/simulation/PhotonCameraSim.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -435,7 +435,7 @@ class PhotonCameraSim {
435435
double minTargetAreaPercent;
436436

437437
frc::AprilTagFieldLayout tagLayout{
438-
frc::LoadAprilTagLayoutField(frc::AprilTagField::k2023ChargedUp)};
438+
frc::LoadAprilTagLayoutField(frc::AprilTagField::k2024Crescendo)};
439439

440440
cs::CvSource videoSimRaw;
441441
cv::Mat videoSimFrameRaw{};

photonlib-cpp-examples/swervedriveposeestsim/src/main/include/Constants.h

Lines changed: 30 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -35,48 +35,48 @@
3535

3636
namespace constants {
3737
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{
4040
frc::Translation3d{0.5_m, 0.0_m, 0.5_m},
4141
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)};
4444

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};
4747
} // namespace Vision
4848
namespace Swerve {
4949

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 *
5858
std::numbers::pi};
5959

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;
6262

63-
static constexpr units::meter_t kDriveDistPerPulse =
63+
inline constexpr units::meter_t kDriveDistPerPulse =
6464
kWheelCircumference / 1024.0 / kDriveGearRatio;
65-
static constexpr units::radian_t kSteerRadPerPulse =
65+
inline constexpr units::radian_t kSteerRadPerPulse =
6666
units::radian_t{2 * std::numbers::pi} / 1024.0;
6767

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;
7171

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;
7575

76-
static const frc::SimpleMotorFeedforward<units::meters> kDriveFF{
76+
inline const frc::SimpleMotorFeedforward<units::meters> kDriveFF{
7777
0.25_V, 2.5_V / 1_mps, 0.3_V / 1_mps_sq};
7878

79-
static const frc::SimpleMotorFeedforward<units::radians> kSteerFF{
79+
inline const frc::SimpleMotorFeedforward<units::radians> kSteerFF{
8080
0.5_V, 0.25_V / 1_rad_per_s, 0.01_V / 1_rad_per_s_sq};
8181

8282
struct ModuleConstants {
@@ -106,13 +106,13 @@ struct ModuleConstants {
106106
centerOffset(frc::Translation2d{xOffset, yOffset}) {}
107107
};
108108

109-
static const ModuleConstants FL_CONSTANTS{
109+
inline const ModuleConstants FL_CONSTANTS{
110110
1, 0, 0, 1, 1, 2, 3, 0, kTrackLength / 2, kTrackWidth / 2};
111-
static const ModuleConstants FR_CONSTANTS{
111+
inline const ModuleConstants FR_CONSTANTS{
112112
2, 2, 4, 5, 3, 6, 7, 0, kTrackLength / 2, -kTrackWidth / 2};
113-
static const ModuleConstants BL_CONSTANTS{
113+
inline const ModuleConstants BL_CONSTANTS{
114114
3, 4, 8, 9, 5, 10, 11, 0, -kTrackLength / 2, kTrackWidth / 2};
115-
static const ModuleConstants BR_CONSTANTS{
115+
inline const ModuleConstants BR_CONSTANTS{
116116
4, 6, 12, 13, 7, 14, 15, 0, -kTrackLength / 2, -kTrackWidth / 2};
117117
} // namespace Swerve
118118
} // namespace constants

photonlib-cpp-examples/swervedriveposeestsim/src/main/include/Vision.h

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ class Vision {
6161
cameraSim = std::make_shared<photon::PhotonCameraSim>(camera.get(),
6262
*cameraProp.get());
6363

64-
visionSim->AddCamera(cameraSim.get(), robotToCam);
64+
visionSim->AddCamera(cameraSim.get(), constants::Vision::kRobotToCam);
6565
cameraSim->EnableDrawWireframe(true);
6666
}
6767
}
@@ -138,12 +138,10 @@ class Vision {
138138
frc::Field2d& GetSimDebugField() { return visionSim->GetDebugField(); }
139139

140140
private:
141-
frc::Transform3d robotToCam{frc::Translation3d{0.5_m, 0.5_m, 0.5_m},
142-
frc::Rotation3d{}};
143141
photon::PhotonPoseEstimator photonEstimator{
144-
LoadAprilTagLayoutField(frc::AprilTagField::k2023ChargedUp),
142+
constants::Vision::kTagLayout,
145143
photon::PoseStrategy::MULTI_TAG_PNP_ON_COPROCESSOR,
146-
photon::PhotonCamera{"photonvision"}, robotToCam};
144+
photon::PhotonCamera{"photonvision"}, constants::Vision::kRobotToCam};
147145
std::shared_ptr<photon::PhotonCamera> camera{photonEstimator.GetCamera()};
148146
std::unique_ptr<photon::VisionSystemSim> visionSim;
149147
std::unique_ptr<photon::SimCameraProperties> cameraProp;

0 commit comments

Comments
 (0)