Skip to content

Commit a174c0e

Browse files
committed
3d Pose orientation WORKING PROGRESS + Saum's Cool Sim Stuff! :)
1 parent 93d1550 commit a174c0e

File tree

7 files changed

+86
-11
lines changed

7 files changed

+86
-11
lines changed

simgui.json

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,8 @@
6262
"NetworkTables Info": {
6363
"Clients": {
6464
"open": true
65-
}
65+
},
66+
"visible": true
6667
},
6768
"Plot": {
6869
"Plot <0>": {
@@ -211,7 +212,7 @@
211212
0.0,
212213
0.8500000238418579
213214
],
214-
"height": 332
215+
"height": 0
215216
}
216217
]
217218
}
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
#include "subsystems/SubVision.h"
2+
#include "subsystems/SubDrivebase.h"
3+
#include "commands/VisionCommands.h"
4+
#include <frc/DriverStation.h>
5+
#include "RobotContainer.h"
6+
#include <frc/DriverStation.h>
7+
8+
namespace cmd {
9+
using namespace frc2::cmd;
10+
frc2::CommandPtr AddVisionMeasurement() {
11+
return Run(
12+
[] {
13+
auto estimatedPose = SubVision::GetInstance().GetPose();
14+
frc::SmartDashboard::PutBoolean("Vision/is teleop", frc::DriverStation::IsTeleop());
15+
frc::SmartDashboard::PutBoolean("Vision/has value", estimatedPose.has_value());
16+
if (estimatedPose.has_value() && frc::DriverStation::IsTeleop()) {
17+
auto estimatedPoseValue = estimatedPose.value();
18+
SubDrivebase::GetInstance().AddVisionMeasurement(
19+
estimatedPoseValue.estimatedPose.ToPose2d(), 0,
20+
estimatedPoseValue.timestamp);
21+
SubDrivebase::GetInstance().DisplayPose(
22+
"EstimatedPose", estimatedPoseValue.estimatedPose.ToPose2d());
23+
} else {
24+
SubDrivebase::GetInstance().DisplayPose("EstimatedPose", {});
25+
}
26+
},
27+
{&SubVision::GetInstance()});
28+
}
29+
}
30+

src/main/cpp/subsystems/SubDrivebase.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -136,6 +136,18 @@ void SubDrivebase::SimulationPeriodic() {
136136
_frontRight.UpdateSim(20_ms);
137137
_backLeft.UpdateSim(20_ms);
138138
_backRight.UpdateSim(20_ms);
139+
140+
auto fl = _frontLeft.GetPosition();
141+
auto fr = _frontRight.GetPosition();
142+
auto bl = _backLeft.GetPosition();
143+
auto br = _backRight.GetPosition();
144+
145+
_simPoseEstimator.Update(GetHeading(), {fl, fr, bl, br});
146+
DisplayPose("simRobotPose", _simPoseEstimator.GetEstimatedPosition());
147+
}
148+
149+
frc::Pose2d SubDrivebase::GetSimPose(){
150+
return _simPoseEstimator.GetEstimatedPosition();
139151
}
140152

141153
frc2::CommandPtr SubDrivebase::JoystickDrive(frc2::CommandXboxController &controller,

src/main/cpp/subsystems/SubVision.cpp

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
#include "subsystems/SubVision.h"
66
#include "subsystems/SubDrivebase.h"
77
#include <frc/DriverStation.h>
8+
#include "commands/VisionCommands.h"
89

910
SubVision::SubVision() {
1011
for (int i = 0; i <= 18; i++) {
@@ -15,6 +16,12 @@ SubVision::SubVision() {
1516
SubDrivebase::GetInstance().DisplayPose(fmt::format("tag{}", i), pose.value().ToPose2d());
1617
}
1718
}
19+
20+
SetDefaultCommand(cmd::AddVisionMeasurement());
21+
}
22+
23+
std::optional<photon::EstimatedRobotPose> SubVision::GetPose() {
24+
return _visionPoseEstimator.Update();
1825
}
1926

2027
// This method will be called once per scheduler run
@@ -26,7 +33,7 @@ void SubVision::Periodic() {
2633
}
2734

2835
void SubVision::SimulationPeriodic() {
29-
_visionSim.ProcessFrame(SubDrivebase::GetInstance().GetPose());
36+
_visionSim.ProcessFrame(SubDrivebase::GetInstance().GetSimPose());
3037
};
3138

3239
std::optional<photon::PhotonTrackedTarget> SubVision::GetSpeakerTarget() {
@@ -84,4 +91,5 @@ bool SubVision::IsFacingTarget(){
8491
} else {
8592
return false;
8693
}
87-
}
94+
95+
}
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
#include <frc/geometry/Pose3d.h>
2+
#include <frc2/command/Commands.h>
3+
4+
namespace cmd{
5+
frc2::CommandPtr AddVisionMeasurement();
6+
}

src/main/include/subsystems/SubDrivebase.h

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -143,4 +143,18 @@ class SubDrivebase : public frc2::SubsystemBase {
143143
.velocity(_frontRight.GetSpeed());
144144
},
145145
this}};
146-
};
146+
147+
//Saum's Cool Simulation stuff
148+
frc::SwerveDrivePoseEstimator<4> _simPoseEstimator{
149+
_kinematics,
150+
_gyro.GetRotation2d(),
151+
{frc::SwerveModulePosition{0_m, _frontLeft.GetAngle()},
152+
frc::SwerveModulePosition{0_m, _frontRight.GetAngle()},
153+
frc::SwerveModulePosition{0_m, _backLeft.GetAngle()},
154+
frc::SwerveModulePosition{0_m, _backRight.GetAngle()}},
155+
frc::Pose2d()};
156+
157+
public:
158+
frc::Pose2d GetSimPose();
159+
160+
};

src/main/include/subsystems/SubVision.h

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -37,23 +37,27 @@ class SubVision : public frc2::SubsystemBase {
3737
std::optional<photon::PhotonTrackedTarget> GetSpeakerTarget();
3838
std::optional<units::degree_t> GetSpeakerYaw();
3939
std::optional<units::degree_t> GetSpeakerPitch();
40+
std::optional<photon::EstimatedRobotPose> GetPose();
4041

4142
bool IsFacingTarget();
4243

4344
private:
4445
std::string CAM_NAME1 = "arducam";
4546

46-
frc::Transform3d _camToBot{{0_mm, -200_mm, -150_mm}, {}}; // arducam
47+
frc::Transform3d _camToBot{{0_mm, -200_mm, -150_mm}, {}}; // arducam FIX
4748

4849
frc::AprilTagFieldLayout _tagLayout = frc::AprilTagFieldLayout::LoadField(frc::AprilTagField::k2024Crescendo);
4950

50-
// photonlib::PhotonPoseEstimator _visionPoseEstimator{
51-
// _tagLayout,
52-
// photonlib::PoseStrategy::MULTI_TAG_PNP,
53-
// photonlib::PhotonCamera{CAM_NAME1},
54-
// _camToBot.Inverse()};
51+
photon::PhotonPoseEstimator _visionPoseEstimator{
52+
_tagLayout,
53+
photon::PoseStrategy::MULTI_TAG_PNP_ON_COPROCESSOR,
54+
photon::PhotonCamera{CAM_NAME1},
55+
_camToBot.Inverse()};
5556

5657

58+
59+
60+
5761

5862
photon::PhotonCamera camera{CAM_NAME1};
5963

0 commit comments

Comments
 (0)