2024-Robot
Robot code for 2024 FRC season by Argos, FRC team #1756
Loading...
Searching...
No Matches
LimelightHelpers.h
Go to the documentation of this file.
1
4
5#pragma once
6
10
11#ifndef _WIN32
12#include <arpa/inet.h>
13#include <netinet/in.h>
14#include <sys/socket.h>
15#include <unistd.h>
16
17#endif
18
19// #include <curl/curl.h>
20#include <fcntl.h>
21#include <frc/geometry/Pose2d.h>
22#include <frc/geometry/Pose3d.h>
23#include <frc/geometry/Rotation2d.h>
24#include <frc/geometry/Rotation3d.h>
25#include <frc/geometry/Translation2d.h>
26#include <frc/geometry/Translation3d.h>
27#include <wpinet/PortForwarder.h>
28
29#include <chrono>
30#include <cstring>
31#include <iostream>
32#include <memory>
33#include <numbers>
34#include <string>
35#include <vector>
36
37#include "networktables/NetworkTable.h"
38#include "networktables/NetworkTableEntry.h"
39#include "networktables/NetworkTableInstance.h"
40#include "networktables/NetworkTableValue.h"
41#include "wpi/json.h"
42
44 inline std::string sanitizeName(const std::string& name) {
45 if (name == "") {
46 return "limelight";
47 }
48 return name;
49 }
50
51 inline frc::Pose3d toPose3D(const std::vector<double>& inData) {
52 if (inData.size() < 6) {
53 return frc::Pose3d();
54 }
55 return frc::Pose3d(
56 frc::Translation3d(
57 units::length::meter_t(inData[0]), units::length::meter_t(inData[1]), units::length::meter_t(inData[2])),
58 frc::Rotation3d(units::angle::radian_t(inData[3] * (std::numbers::pi / 180.0)),
59 units::angle::radian_t(inData[4] * (std::numbers::pi / 180.0)),
60 units::angle::radian_t(inData[5] * (std::numbers::pi / 180.0))));
61 }
62
63 inline frc::Pose2d toPose2D(const std::vector<double>& inData) {
64 if (inData.size() < 6) {
65 return frc::Pose2d();
66 }
67 return frc::Pose2d(frc::Translation2d(units::length::meter_t(inData[0]), units::length::meter_t(inData[1])),
68 frc::Rotation2d(units::angle::radian_t(inData[5] * (std::numbers::pi / 180.0))));
69 }
70
71 inline std::shared_ptr<nt::NetworkTable> getLimelightNTTable(const std::string& tableName) {
72 return nt::NetworkTableInstance::GetDefault().GetTable(sanitizeName(tableName));
73 }
74
75 inline nt::NetworkTableEntry getLimelightNTTableEntry(const std::string& tableName, const std::string& entryName) {
76 return getLimelightNTTable(tableName)->GetEntry(entryName);
77 }
78
79 inline double getLimelightNTDouble(const std::string& tableName, const std::string& entryName) {
80 return getLimelightNTTableEntry(tableName, entryName).GetDouble(0.0);
81 }
82
83 inline std::vector<double> getLimelightNTDoubleArray(const std::string& tableName, const std::string& entryName) {
84 return getLimelightNTTableEntry(tableName, entryName).GetDoubleArray(std::span<double>{});
85 }
86
87 inline std::string getLimelightNTString(const std::string& tableName, const std::string& entryName) {
88 return getLimelightNTTableEntry(tableName, entryName).GetString("");
89 }
90
91 inline void setLimelightNTDouble(const std::string& tableName, const std::string entryName, double val) {
92 getLimelightNTTableEntry(tableName, entryName).SetDouble(val);
93 }
94
95 inline void setLimelightNTDoubleArray(const std::string& tableName,
96 const std::string& entryName,
97 const std::span<const double>& vals) {
98 getLimelightNTTableEntry(tableName, entryName).SetDoubleArray(vals);
99 }
100
101 inline double getTX(const std::string& limelightName = "") {
102 return getLimelightNTDouble(limelightName, "tx");
103 }
104
105 inline double getTV(const std::string& limelightName = "") {
106 return getLimelightNTDouble(limelightName, "tv");
107 }
108
109 inline double getTY(const std::string& limelightName = "") {
110 return getLimelightNTDouble(limelightName, "ty");
111 }
112
113 inline double getTA(const std::string& limelightName = "") {
114 return getLimelightNTDouble(limelightName, "ta");
115 }
116
117 inline double getLatency_Pipeline(const std::string& limelightName = "") {
118 return getLimelightNTDouble(limelightName, "tl");
119 }
120
121 inline double getLatency_Capture(const std::string& limelightName = "") {
122 return getLimelightNTDouble(limelightName, "cl");
123 }
124
125 inline std::string getJSONDump(const std::string& limelightName = "") {
126 return getLimelightNTString(limelightName, "json");
127 }
128
129 inline std::vector<double> getBotpose(const std::string& limelightName = "") {
130 return getLimelightNTDoubleArray(limelightName, "botpose");
131 }
132
133 inline std::vector<double> getBotpose_wpiRed(const std::string& limelightName = "") {
134 return getLimelightNTDoubleArray(limelightName, "botpose_wpired");
135 }
136
137 inline std::vector<double> getBotpose_wpiBlue(const std::string& limelightName = "") {
138 return getLimelightNTDoubleArray(limelightName, "botpose_wpiblue");
139 }
140
141 inline std::vector<double> getBotpose_TargetSpace(const std::string& limelightName = "") {
142 return getLimelightNTDoubleArray(limelightName, "botpose_targetspace");
143 }
144
145 inline std::vector<double> getCameraPose_TargetSpace(const std::string& limelightName = "") {
146 return getLimelightNTDoubleArray(limelightName, "camerapose_targetspace");
147 }
148
149 inline std::vector<double> getCameraPose_RobotSpace(const std::string& limelightName = "") {
150 return getLimelightNTDoubleArray(limelightName, "camerapose_robotspace");
151 }
152
153 inline std::vector<double> getTargetPose_CameraSpace(const std::string& limelightName = "") {
154 return getLimelightNTDoubleArray(limelightName, "targetpose_cameraspace");
155 }
156
157 inline std::vector<double> getTargetPose_RobotSpace(const std::string& limelightName = "") {
158 return getLimelightNTDoubleArray(limelightName, "targetpose_robotspace");
159 }
160
161 inline std::vector<double> getTargetColor(const std::string& limelightName = "") {
162 return getLimelightNTDoubleArray(limelightName, "tc");
163 }
164
165 inline double getFiducialID(const std::string& limelightName = "") {
166 return getLimelightNTDouble(limelightName, "tid");
167 }
168
169 inline std::string getNeuralClassID(const std::string& limelightName = "") {
170 return getLimelightNTString(limelightName, "tclass");
171 }
172
173 inline void setPipelineIndex(const std::string& limelightName, int index) {
174 setLimelightNTDouble(limelightName, "pipeline", index);
175 }
176
177 inline void setPriorityTagID(const std::string& limelightName, int ID) {
178 setLimelightNTDouble(limelightName, "priorityid", ID);
179 }
180
181 inline void setLEDMode_PipelineControl(const std::string& limelightName = "") {
182 setLimelightNTDouble(limelightName, "ledMode", 0);
183 }
184
185 inline void setLEDMode_ForceOff(const std::string& limelightName = "") {
186 setLimelightNTDouble(limelightName, "ledMode", 1);
187 }
188
189 inline void setLEDMode_ForceBlink(const std::string& limelightName = "") {
190 setLimelightNTDouble(limelightName, "ledMode", 2);
191 }
192
193 inline void setLEDMode_ForceOn(const std::string& limelightName = "") {
194 setLimelightNTDouble(limelightName, "ledMode", 3);
195 }
196
197 inline void setStreamMode_Standard(const std::string& limelightName = "") {
198 setLimelightNTDouble(limelightName, "stream", 0);
199 }
200
201 inline void setStreamMode_PiPMain(const std::string& limelightName = "") {
202 setLimelightNTDouble(limelightName, "stream", 1);
203 }
204
205 inline void setStreamMode_PiPSecondary(const std::string& limelightName = "") {
206 setLimelightNTDouble(limelightName, "stream", 2);
207 }
208
213 inline void setCropWindow(
214 const std::string& limelightName, double cropXMin, double cropXMax, double cropYMin, double cropYMax) {
215 double cropWindow[4]{cropXMin, cropXMax, cropYMin, cropYMax};
216 setLimelightNTDoubleArray(limelightName, "crop", cropWindow);
217 }
218
222 inline void SetRobotOrientation(const std::string& limelightName,
223 double yaw,
224 double yawRate,
225 double pitch,
226 double pitchRate,
227 double roll,
228 double rollRate) {
229 std::vector<double> entries = {yaw, yawRate, pitch, pitchRate, roll, rollRate};
230 setLimelightNTDoubleArray(limelightName, "robot_orientation_set", entries);
231 }
232
233 inline void SetFiducialIDFiltersOverride(const std::string& limelightName, const std::vector<int>& validIDs) {
234 std::vector<double> validIDsDouble(validIDs.begin(), validIDs.end());
235 setLimelightNTDoubleArray(limelightName, "fiducial_id_filters_set", validIDsDouble);
236 }
237
242 const std::string& limelightName, double forward, double side, double up, double roll, double pitch, double yaw) {
243 double entries[6] = {forward, side, up, roll, pitch, yaw};
244 setLimelightNTDoubleArray(limelightName, "camerapose_robotspace_set", entries);
245 }
246
247 inline void setPythonScriptData(const std::string& limelightName, const std::vector<double>& outgoingPythonData) {
249 limelightName, "llrobot", std::span{outgoingPythonData.begin(), outgoingPythonData.size()});
250 }
251
252 inline std::vector<double> getPythonScriptData(const std::string& limelightName = "") {
253 return getLimelightNTDoubleArray(limelightName, "llpython");
254 }
255
256 // Take async snapshot
257
258 inline double extractBotPoseEntry(const std::vector<double>& inData, int position) {
259 if (inData.size() < static_cast<size_t>(position + 1)) {
260 return 0.0;
261 }
262 return inData[position];
263 }
264
266 public:
267 int id{0};
268 double txnc{0.0};
269 double tync{0.0};
270 double ta{0.0};
271 double distToCamera{0.0};
272 double distToRobot{0.0};
273 double ambiguity{0.0};
274
275 RawFiducial(int id, double txnc, double tync, double ta, double distToCamera, double distToRobot, double ambiguity)
276 : id(id)
277 , txnc(txnc)
278 , tync(tync)
279 , ta(ta)
282 , ambiguity(ambiguity) {}
283 };
284
286 public:
287 frc::Pose2d pose;
288 units::time::second_t timestampSeconds{0.0};
289 double latency{0.0};
290 int tagCount{0};
291 double tagSpan{0.0};
292 double avgTagDist{0.0};
293 double avgTagArea{0.0};
294 std::vector<RawFiducial> rawFiducials;
295
296 PoseEstimate() = default;
297
298 PoseEstimate(const frc::Pose2d& pose,
299 units::time::second_t timestampSeconds,
300 double latency,
301 int tagCount,
302 double tagSpan,
303 double avgTagDist,
304 double avgTagArea,
305 const std::vector<RawFiducial>& rawFiducials)
306 : pose(pose)
314 };
315
316 inline PoseEstimate getBotPoseEstimate(const std::string& limelightName, const std::string& entryName) {
317 nt::NetworkTableEntry poseEntry = getLimelightNTTableEntry(limelightName, entryName);
318 std::vector<double> poseArray = poseEntry.GetDoubleArray(std::span<double>{});
319 frc::Pose2d pose = toPose2D(poseArray);
320
321 double latency = extractBotPoseEntry(poseArray, 6);
322 int tagCount = static_cast<int>(extractBotPoseEntry(poseArray, 7));
323 double tagSpan = extractBotPoseEntry(poseArray, 8);
324 double tagDist = extractBotPoseEntry(poseArray, 9);
325 double tagArea = extractBotPoseEntry(poseArray, 10);
326
327 // getLastChange: microseconds; latency: milliseconds
328 units::time::second_t timestamp =
329 units::time::second_t((poseEntry.GetLastChange() / 1000000.0) - (latency / 1000.0));
330
331 std::vector<RawFiducial> rawFiducials;
332 int valsPerFiducial = 7;
333 size_t expectedTotalVals = 11 + valsPerFiducial * tagCount;
334
335 if (poseArray.size() == expectedTotalVals) {
336 for (int i = 0; i < tagCount; i++) {
337 int baseIndex = 11 + (i * valsPerFiducial);
338 int id = static_cast<int>(extractBotPoseEntry(poseArray, baseIndex));
339 double txnc = extractBotPoseEntry(poseArray, baseIndex + 1);
340 double tync = extractBotPoseEntry(poseArray, baseIndex + 2);
341 double ta = extractBotPoseEntry(poseArray, baseIndex + 3);
342 double distToCamera = extractBotPoseEntry(poseArray, baseIndex + 4);
343 double distToRobot = extractBotPoseEntry(poseArray, baseIndex + 5);
344 double ambiguity = extractBotPoseEntry(poseArray, baseIndex + 6);
345 rawFiducials.emplace_back(id, txnc, tync, ta, distToCamera, distToRobot, ambiguity);
346 }
347 }
348
349 return PoseEstimate(pose, timestamp, latency, tagCount, tagSpan, tagDist, tagArea, rawFiducials);
350 }
351
352 inline PoseEstimate getBotPoseEstimate_wpiBlue(const std::string& limelightName = "") {
353 return getBotPoseEstimate(limelightName, "botpose_wpiblue");
354 }
355
356 inline PoseEstimate getBotPoseEstimate_wpiRed(const std::string& limelightName = "") {
357 return getBotPoseEstimate(limelightName, "botpose_wpired");
358 }
359
360 inline PoseEstimate getBotPoseEstimate_wpiBlue_MegaTag2(const std::string& limelightName = "") {
361 return getBotPoseEstimate(limelightName, "botpose_orb_wpiblue");
362 }
363
364 inline PoseEstimate getBotPoseEstimate_wpiRed_MegaTag2(const std::string& limelightName = "") {
365 return getBotPoseEstimate(limelightName, "botpose_orb_wpired");
366 }
367
368 inline const double INVALID_TARGET = 0.0;
402
408
416
426
436
438 public:
441 std::vector<RetroreflectiveResultClass> RetroResults;
442 std::vector<FiducialResultClass> FiducialResults;
443 std::vector<DetectionResultClass> DetectionResults;
444 std::vector<ClassificationResultClass> ClassificationResults;
445 double m_timeStamp{-1.0};
448 double m_latencyJSON{0};
449 double m_pipelineIndex{-1.0};
450 int valid{0};
451 std::vector<double> botPose{6, 0.0};
452 std::vector<double> botPose_wpired{6, 0.0};
453 std::vector<double> botPose_wpiblue{6, 0.0};
454 void Clear() {
455 RetroResults.clear();
456 FiducialResults.clear();
457 DetectionResults.clear();
458 ClassificationResults.clear();
459 botPose.clear();
460 botPose_wpired.clear();
461 botPose_wpiblue.clear();
462 m_timeStamp = -1.0;
464
465 m_pipelineIndex = -1.0;
466 }
467 };
468
475
476 namespace internal {
477 inline const std::string _key_timestamp{"ts"};
478 inline const std::string _key_latency_pipeline{"tl"};
479 inline const std::string _key_latency_capture{"cl"};
480
481 inline const std::string _key_pipelineIndex{"pID"};
482 inline const std::string _key_TargetXDegrees{"txdr"};
483 inline const std::string _key_TargetYDegrees{"tydr"};
484 inline const std::string _key_TargetXNormalized{"txnr"};
485 inline const std::string _key_TargetYNormalized{"tynr"};
486 inline const std::string _key_TargetXPixels{"txp"};
487 inline const std::string _key_TargetYPixels{"typ"};
488
489 inline const std::string _key_TargetXDegreesCrosshair{"tx"};
490 inline const std::string _key_TargetYDegreesCrosshair{"ty"};
491 inline const std::string _key_TargetXNormalizedCrosshair{"txn"};
492 inline const std::string _key_TargetYNormalizedCrosshair{"tyn"};
493 inline const std::string _key_TargetAreaNormalized{"ta"};
494 inline const std::string _key_TargetAreaPixels{"tap"};
495 inline const std::string _key_className{"class"};
496 inline const std::string _key_classID{"classID"};
497 inline const std::string _key_confidence{"conf"};
498 inline const std::string _key_fiducialID{"fID"};
499 inline const std::string _key_corners{"pts"};
500 inline const std::string _key_transformCAMERAPOSE_TARGETSPACE{"t6c_ts"};
501 inline const std::string _key_transformCAMERAPOSE_ROBOTSPACE{"t6c_rs"};
502
503 inline const std::string _key_transformTARGETPOSE_CAMERASPACE{"t6t_cs"};
504 inline const std::string _key_transformROBOTPOSE_TARGETSPACE{"t6r_ts"};
505 inline const std::string _key_transformTARGETPOSE_ROBOTSPACE{"t6t_rs"};
506
507 inline const std::string _key_botpose{"botpose"};
508 inline const std::string _key_botpose_wpiblue{"botpose_wpiblue"};
509 inline const std::string _key_botpose_wpired{"botpose_wpired"};
510
511 inline const std::string _key_transformROBOTPOSE_FIELDSPACE{"t6r_fs"};
512 inline const std::string _key_skew{"skew"};
513 inline const std::string _key_ffamily{"fam"};
514 inline const std::string _key_colorRGB{"cRGB"};
515 inline const std::string _key_colorHSV{"cHSV"};
516 } // namespace internal
517
518#ifndef _WIN32
519 inline void PhoneHome() {
520 static int sockfd = -1;
521 static struct sockaddr_in servaddr, cliaddr;
522
523 if (sockfd == -1) {
524 sockfd = socket(AF_INET, SOCK_DGRAM, 0);
525 if (sockfd < 0) {
526 std::cerr << "Socket creation failed" << std::endl;
527 return;
528 }
529
530 std::memset(&servaddr, 0, sizeof(servaddr));
531 servaddr.sin_family = AF_INET;
532 servaddr.sin_addr.s_addr = inet_addr("255.255.255.255");
533 servaddr.sin_port = htons(5809);
534
535 // Set socket for broadcast
536 int broadcast = 1;
537 if (setsockopt(sockfd, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)) < 0) {
538 std::cerr << "Error in setting Broadcast option" << std::endl;
539 close(sockfd);
540 sockfd = -1;
541 return;
542 }
543
544 // Set socket to non-blocking
545 if (fcntl(sockfd, F_SETFL, O_NONBLOCK) < 0) {
546 std::cerr << "Error setting socket to non-blocking" << std::endl;
547 close(sockfd);
548 sockfd = -1;
549 return;
550 }
551
552 const char* msg = "LLPhoneHome";
553 sendto(sockfd, msg, std::strlen(msg), 0, (const struct sockaddr*)&servaddr, sizeof(servaddr));
554 }
555
556 char receiveData[1024];
557 socklen_t len = sizeof(cliaddr);
558
559 ssize_t n = recvfrom(sockfd, reinterpret_cast<char*>(receiveData), 1024, 0, (struct sockaddr*)&cliaddr, &len);
560 if (n > 0) {
561 receiveData[n] = '\0'; // Null-terminate the received string
562 std::string received(receiveData, n);
563 std::cout << "Received response: " << received << std::endl;
564 } else if (n < 0 && errno != EWOULDBLOCK && errno != EAGAIN) {
565 std::cerr << "Error receiving data" << std::endl;
566 close(sockfd);
567 sockfd = -1;
568 }
569 }
570#endif
571
572 inline void SetupPortForwarding(const std::string& limelightName) {
573 auto& portForwarder = wpi::PortForwarder::GetInstance();
574 portForwarder.Add(5800, sanitizeName(limelightName), 5800);
575 portForwarder.Add(5801, sanitizeName(limelightName), 5801);
576 portForwarder.Add(5802, sanitizeName(limelightName), 5802);
577 portForwarder.Add(5803, sanitizeName(limelightName), 5803);
578 portForwarder.Add(5804, sanitizeName(limelightName), 5804);
579 portForwarder.Add(5805, sanitizeName(limelightName), 5805);
580 portForwarder.Add(5806, sanitizeName(limelightName), 5806);
581 portForwarder.Add(5807, sanitizeName(limelightName), 5807);
582 portForwarder.Add(5808, sanitizeName(limelightName), 5808);
583 portForwarder.Add(5809, sanitizeName(limelightName), 5809);
584 }
585
586 template <typename T, typename KeyType>
587 T SafeJSONAccess(const wpi::json& jsonData, const KeyType& key, const T& defaultValue) {
588 try {
589 return jsonData.at(key).template get<T>();
590 } catch (wpi::json::exception& e) {
591 return defaultValue;
592 } catch (...) {
593 return defaultValue;
594 }
595 }
596 inline void from_json(const wpi::json& j, RetroreflectiveResultClass& t) {
597 std::vector<double> defaultValueVector(6, 0.0);
599 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformCAMERAPOSE_TARGETSPACE, defaultValueVector);
601 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformCAMERAPOSE_ROBOTSPACE, defaultValueVector);
602
604 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformTARGETPOSE_CAMERASPACE, defaultValueVector);
606 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformTARGETPOSE_ROBOTSPACE, defaultValueVector);
608 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformROBOTPOSE_TARGETSPACE, defaultValueVector);
610 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformROBOTPOSE_FIELDSPACE, defaultValueVector);
611
612 t.m_TargetXPixels = SafeJSONAccess<double>(j, internal::_key_TargetXPixels, 0.0);
613 t.m_TargetYPixels = SafeJSONAccess<double>(j, internal::_key_TargetYPixels, 0.0);
616 t.m_TargetAreaNormalized = SafeJSONAccess<double>(j, internal::_key_TargetAreaNormalized, 0.0);
618 SafeJSONAccess<std::vector<std::vector<double>>>(j, internal::_key_corners, std::vector<std::vector<double>>{});
619 }
620
621 inline void from_json(const wpi::json& j, FiducialResultClass& t) {
622 std::vector<double> defaultValueVector(6, 0.0);
623 t.m_family = SafeJSONAccess<std::string>(j, internal::_key_ffamily, "");
624 t.m_fiducialID = SafeJSONAccess<double>(j, internal::_key_fiducialID, 0.0);
626 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformCAMERAPOSE_TARGETSPACE, defaultValueVector);
628 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformCAMERAPOSE_ROBOTSPACE, defaultValueVector);
630 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformTARGETPOSE_CAMERASPACE, defaultValueVector);
632 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformTARGETPOSE_ROBOTSPACE, defaultValueVector);
634 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformROBOTPOSE_TARGETSPACE, defaultValueVector);
636 SafeJSONAccess<std::vector<double>>(j, internal::_key_transformROBOTPOSE_FIELDSPACE, defaultValueVector);
637
638 t.m_TargetXPixels = SafeJSONAccess<double>(j, internal::_key_TargetXPixels, 0.0);
639 t.m_TargetYPixels = SafeJSONAccess<double>(j, internal::_key_TargetYPixels, 0.0);
642 t.m_TargetAreaNormalized = SafeJSONAccess<double>(j, internal::_key_TargetAreaNormalized, 0.0);
644 SafeJSONAccess<std::vector<std::vector<double>>>(j, internal::_key_corners, std::vector<std::vector<double>>{});
645 }
646
647 inline void from_json(const wpi::json& j, DetectionResultClass& t) {
648 t.m_confidence = SafeJSONAccess<double>(j, internal::_key_confidence, 0.0);
649 t.m_classID = SafeJSONAccess<double>(j, internal::_key_classID, 0.0);
650 t.m_className = SafeJSONAccess<std::string>(j, internal::_key_className, "");
651 t.m_TargetXPixels = SafeJSONAccess<double>(j, internal::_key_TargetXPixels, 0.0);
652 t.m_TargetYPixels = SafeJSONAccess<double>(j, internal::_key_TargetYPixels, 0.0);
655 t.m_TargetAreaNormalized = SafeJSONAccess<double>(j, internal::_key_TargetAreaNormalized, 0.0);
657 SafeJSONAccess<std::vector<std::vector<double>>>(j, internal::_key_corners, std::vector<std::vector<double>>{});
658 }
659
660 inline void from_json(const wpi::json& j, ClassificationResultClass& t) {
661 t.m_confidence = SafeJSONAccess<double>(j, internal::_key_confidence, 0.0);
662 t.m_classID = SafeJSONAccess<double>(j, internal::_key_classID, 0.0);
663 t.m_className = SafeJSONAccess<std::string>(j, internal::_key_className, "");
664 t.m_TargetXPixels = SafeJSONAccess<double>(j, internal::_key_TargetXPixels, 0.0);
665 t.m_TargetYPixels = SafeJSONAccess<double>(j, internal::_key_TargetYPixels, 0.0);
668 t.m_TargetAreaNormalized = SafeJSONAccess<double>(j, internal::_key_TargetAreaNormalized, 0.0);
670 SafeJSONAccess<std::vector<std::vector<double>>>(j, internal::_key_corners, std::vector<std::vector<double>>{});
671 }
672
673 inline void from_json(const wpi::json& j, VisionResultsClass& t) {
674 t.m_timeStamp = SafeJSONAccess<double>(j, internal::_key_timestamp, 0.0);
675 t.m_latencyPipeline = SafeJSONAccess<double>(j, internal::_key_latency_pipeline, 0.0);
676 t.m_latencyCapture = SafeJSONAccess<double>(j, internal::_key_latency_capture, 0.0);
677 t.m_pipelineIndex = SafeJSONAccess<double>(j, internal::_key_pipelineIndex, 0.0);
678 t.valid = SafeJSONAccess<double>(j, "v", 0.0);
679
680 std::vector<double> defaultVector{};
681 t.botPose = SafeJSONAccess<std::vector<double>>(j, internal::_key_botpose, defaultVector);
682 t.botPose_wpired = SafeJSONAccess<std::vector<double>>(j, internal::_key_botpose_wpired, defaultVector);
683 t.botPose_wpiblue = SafeJSONAccess<std::vector<double>>(j, internal::_key_botpose_wpiblue, defaultVector);
684
685 t.RetroResults =
686 SafeJSONAccess<std::vector<RetroreflectiveResultClass>>(j, "Retro", std::vector<RetroreflectiveResultClass>{});
688 SafeJSONAccess<std::vector<FiducialResultClass>>(j, "Fiducial", std::vector<FiducialResultClass>{});
690 SafeJSONAccess<std::vector<DetectionResultClass>>(j, "Detector", std::vector<DetectionResultClass>{});
692 SafeJSONAccess<std::vector<ClassificationResultClass>>(j, "Detector", std::vector<ClassificationResultClass>{});
693 }
694
695 inline void from_json(const wpi::json& j, LimelightResultsClass& t) {
697 SafeJSONAccess<LimelightHelpers::VisionResultsClass>(j, "Results", LimelightHelpers::VisionResultsClass{});
698 }
699
700 inline LimelightResultsClass getLatestResults(const std::string& limelightName = "", bool profile = false) {
701 auto start = std::chrono::high_resolution_clock::now();
702 std::string jsonString = getJSONDump(limelightName);
703 wpi::json data;
704 try {
705 data = wpi::json::parse(jsonString);
706 } catch (const std::exception& e) {
707 return LimelightResultsClass();
708 }
709
710 auto end = std::chrono::high_resolution_clock::now();
711 double nanos = std::chrono::duration_cast<std::chrono::nanoseconds>(end - start).count();
712 double millis = (nanos * 0.000001);
713 try {
715 out.targetingResults.m_latencyJSON = millis;
716 if (profile) {
717 std::cout << "lljson: " << millis << std::endl;
718 }
719 return out;
720 } catch (...) {
721 return LimelightResultsClass();
722 }
723 }
724} // namespace LimelightHelpers
Definition LimelightHelpers.h:427
ClassificationResultClass()
Definition LimelightHelpers.h:429
int m_classID
Definition LimelightHelpers.h:432
std::string m_className
Definition LimelightHelpers.h:433
double m_confidence
Definition LimelightHelpers.h:434
~ClassificationResultClass()
Definition LimelightHelpers.h:430
Definition LimelightHelpers.h:417
int m_classID
Definition LimelightHelpers.h:422
std::string m_className
Definition LimelightHelpers.h:423
DetectionResultClass()
Definition LimelightHelpers.h:419
~DetectionResultClass()
Definition LimelightHelpers.h:420
double m_confidence
Definition LimelightHelpers.h:424
Definition LimelightHelpers.h:409
FiducialResultClass()
Definition LimelightHelpers.h:411
std::string m_family
Definition LimelightHelpers.h:414
int m_fiducialID
Definition LimelightHelpers.h:413
~FiducialResultClass()
Definition LimelightHelpers.h:412
Definition LimelightHelpers.h:469
LimelightResultsClass()
Definition LimelightHelpers.h:471
VisionResultsClass targetingResults
Definition LimelightHelpers.h:473
~LimelightResultsClass()
Definition LimelightHelpers.h:472
Definition LimelightHelpers.h:285
double latency
Definition LimelightHelpers.h:289
double avgTagDist
Definition LimelightHelpers.h:292
int tagCount
Definition LimelightHelpers.h:290
frc::Pose2d pose
Definition LimelightHelpers.h:287
double avgTagArea
Definition LimelightHelpers.h:293
std::vector< RawFiducial > rawFiducials
Definition LimelightHelpers.h:294
PoseEstimate(const frc::Pose2d &pose, units::time::second_t timestampSeconds, double latency, int tagCount, double tagSpan, double avgTagDist, double avgTagArea, const std::vector< RawFiducial > &rawFiducials)
Definition LimelightHelpers.h:298
double tagSpan
Definition LimelightHelpers.h:291
units::time::second_t timestampSeconds
Definition LimelightHelpers.h:288
Definition LimelightHelpers.h:265
double ambiguity
Definition LimelightHelpers.h:273
RawFiducial(int id, double txnc, double tync, double ta, double distToCamera, double distToRobot, double ambiguity)
Definition LimelightHelpers.h:275
int id
Definition LimelightHelpers.h:267
double txnc
Definition LimelightHelpers.h:268
double tync
Definition LimelightHelpers.h:269
double distToCamera
Definition LimelightHelpers.h:271
double ta
Definition LimelightHelpers.h:270
double distToRobot
Definition LimelightHelpers.h:272
Definition LimelightHelpers.h:403
RetroreflectiveResultClass()
Definition LimelightHelpers.h:405
~RetroreflectiveResultClass()
Definition LimelightHelpers.h:406
Definition LimelightHelpers.h:369
std::vector< double > m_TargetTransform6DROBOTSPACE
Definition LimelightHelpers.h:397
double m_pipelineIndex
Definition LimelightHelpers.h:392
double m_TargetAreaNormalizedPercentage
Definition LimelightHelpers.h:387
double m_TargetYDegreesCrosshairAdjusted
Definition LimelightHelpers.h:383
double m_TargetYNormalizedCrosshairAdjusted
Definition LimelightHelpers.h:380
double m_TargetXDegreesCrosshairAdjusted
Definition LimelightHelpers.h:382
std::vector< double > m_CAMERATransform6DTARGETSPACE
Definition LimelightHelpers.h:395
double m_TargetXNormalized
Definition LimelightHelpers.h:376
double m_TargetAreaNormalized
Definition LimelightHelpers.h:386
double m_TargetYNormalized
Definition LimelightHelpers.h:377
std::vector< double > m_ROBOTTransform6DFIELDSPACE
Definition LimelightHelpers.h:399
double m_TargetXNormalizedCrosshairAdjusted
Definition LimelightHelpers.h:379
std::vector< double > m_CAMERATransform6DROBOTSPACE
Definition LimelightHelpers.h:400
double m_TargetXPixels
Definition LimelightHelpers.h:373
std::vector< double > m_ROBOTTransform6DTARGETSPACE
Definition LimelightHelpers.h:398
double m_timeStamp
Definition LimelightHelpers.h:390
std::vector< std::vector< double > > m_TargetCorners
Definition LimelightHelpers.h:393
std::vector< double > m_TargetTransform6DCAMERASPACE
Definition LimelightHelpers.h:396
double m_TargetYPixels
Definition LimelightHelpers.h:374
double m_TargetAreaPixels
Definition LimelightHelpers.h:385
double m_latency
Definition LimelightHelpers.h:391
Definition LimelightHelpers.h:437
std::vector< double > botPose_wpired
Definition LimelightHelpers.h:452
double m_latencyJSON
Definition LimelightHelpers.h:448
std::vector< ClassificationResultClass > ClassificationResults
Definition LimelightHelpers.h:444
double m_latencyPipeline
Definition LimelightHelpers.h:446
std::vector< double > botPose_wpiblue
Definition LimelightHelpers.h:453
std::vector< double > botPose
Definition LimelightHelpers.h:451
int valid
Definition LimelightHelpers.h:450
double m_latencyCapture
Definition LimelightHelpers.h:447
~VisionResultsClass()
Definition LimelightHelpers.h:440
VisionResultsClass()
Definition LimelightHelpers.h:439
double m_timeStamp
Definition LimelightHelpers.h:445
void Clear()
Definition LimelightHelpers.h:454
std::vector< RetroreflectiveResultClass > RetroResults
Definition LimelightHelpers.h:441
std::vector< FiducialResultClass > FiducialResults
Definition LimelightHelpers.h:442
std::vector< DetectionResultClass > DetectionResults
Definition LimelightHelpers.h:443
double m_pipelineIndex
Definition LimelightHelpers.h:449
const std::string _key_transformTARGETPOSE_ROBOTSPACE
Definition LimelightHelpers.h:505
const std::string _key_TargetYNormalizedCrosshair
Definition LimelightHelpers.h:492
const std::string _key_TargetAreaNormalized
Definition LimelightHelpers.h:493
const std::string _key_pipelineIndex
Definition LimelightHelpers.h:481
const std::string _key_latency_pipeline
Definition LimelightHelpers.h:478
const std::string _key_TargetXPixels
Definition LimelightHelpers.h:486
const std::string _key_TargetYDegreesCrosshair
Definition LimelightHelpers.h:490
const std::string _key_TargetAreaPixels
Definition LimelightHelpers.h:494
const std::string _key_TargetYPixels
Definition LimelightHelpers.h:487
const std::string _key_TargetXDegreesCrosshair
Definition LimelightHelpers.h:489
const std::string _key_skew
Definition LimelightHelpers.h:512
const std::string _key_timestamp
Definition LimelightHelpers.h:477
const std::string _key_transformCAMERAPOSE_ROBOTSPACE
Definition LimelightHelpers.h:501
const std::string _key_corners
Definition LimelightHelpers.h:499
const std::string _key_botpose_wpired
Definition LimelightHelpers.h:509
const std::string _key_TargetXNormalized
Definition LimelightHelpers.h:484
const std::string _key_transformTARGETPOSE_CAMERASPACE
Definition LimelightHelpers.h:503
const std::string _key_TargetYNormalized
Definition LimelightHelpers.h:485
const std::string _key_latency_capture
Definition LimelightHelpers.h:479
const std::string _key_transformROBOTPOSE_TARGETSPACE
Definition LimelightHelpers.h:504
const std::string _key_confidence
Definition LimelightHelpers.h:497
const std::string _key_TargetXDegrees
Definition LimelightHelpers.h:482
const std::string _key_TargetXNormalizedCrosshair
Definition LimelightHelpers.h:491
const std::string _key_botpose_wpiblue
Definition LimelightHelpers.h:508
const std::string _key_ffamily
Definition LimelightHelpers.h:513
const std::string _key_colorHSV
Definition LimelightHelpers.h:515
const std::string _key_className
Definition LimelightHelpers.h:495
const std::string _key_classID
Definition LimelightHelpers.h:496
const std::string _key_transformCAMERAPOSE_TARGETSPACE
Definition LimelightHelpers.h:500
const std::string _key_transformROBOTPOSE_FIELDSPACE
Definition LimelightHelpers.h:511
const std::string _key_fiducialID
Definition LimelightHelpers.h:498
const std::string _key_botpose
Definition LimelightHelpers.h:507
const std::string _key_TargetYDegrees
Definition LimelightHelpers.h:483
const std::string _key_colorRGB
Definition LimelightHelpers.h:514
Definition LimelightHelpers.h:43
std::vector< double > getCameraPose_TargetSpace(const std::string &limelightName="")
Definition LimelightHelpers.h:145
void setPipelineIndex(const std::string &limelightName, int index)
Definition LimelightHelpers.h:173
double getLatency_Pipeline(const std::string &limelightName="")
Definition LimelightHelpers.h:117
nt::NetworkTableEntry getLimelightNTTableEntry(const std::string &tableName, const std::string &entryName)
Definition LimelightHelpers.h:75
void SetupPortForwarding(const std::string &limelightName)
Definition LimelightHelpers.h:572
double getTY(const std::string &limelightName="")
Definition LimelightHelpers.h:109
PoseEstimate getBotPoseEstimate(const std::string &limelightName, const std::string &entryName)
Definition LimelightHelpers.h:316
std::vector< double > getBotpose_wpiRed(const std::string &limelightName="")
Definition LimelightHelpers.h:133
std::vector< double > getBotpose_wpiBlue(const std::string &limelightName="")
Definition LimelightHelpers.h:137
PoseEstimate getBotPoseEstimate_wpiRed(const std::string &limelightName="")
Definition LimelightHelpers.h:356
T SafeJSONAccess(const wpi::json &jsonData, const KeyType &key, const T &defaultValue)
Definition LimelightHelpers.h:587
void setLEDMode_ForceBlink(const std::string &limelightName="")
Definition LimelightHelpers.h:189
LimelightResultsClass getLatestResults(const std::string &limelightName="", bool profile=false)
Definition LimelightHelpers.h:700
std::vector< double > getCameraPose_RobotSpace(const std::string &limelightName="")
Definition LimelightHelpers.h:149
void SetRobotOrientation(const std::string &limelightName, double yaw, double yawRate, double pitch, double pitchRate, double roll, double rollRate)
Definition LimelightHelpers.h:222
PoseEstimate getBotPoseEstimate_wpiBlue_MegaTag2(const std::string &limelightName="")
Definition LimelightHelpers.h:360
double getTX(const std::string &limelightName="")
Definition LimelightHelpers.h:101
void setLimelightNTDoubleArray(const std::string &tableName, const std::string &entryName, const std::span< const double > &vals)
Definition LimelightHelpers.h:95
std::vector< double > getLimelightNTDoubleArray(const std::string &tableName, const std::string &entryName)
Definition LimelightHelpers.h:83
PoseEstimate getBotPoseEstimate_wpiBlue(const std::string &limelightName="")
Definition LimelightHelpers.h:352
std::shared_ptr< nt::NetworkTable > getLimelightNTTable(const std::string &tableName)
Definition LimelightHelpers.h:71
double getLimelightNTDouble(const std::string &tableName, const std::string &entryName)
Definition LimelightHelpers.h:79
std::vector< double > getBotpose(const std::string &limelightName="")
Definition LimelightHelpers.h:129
frc::Pose2d toPose2D(const std::vector< double > &inData)
Definition LimelightHelpers.h:63
const double INVALID_TARGET
Definition LimelightHelpers.h:368
void setStreamMode_PiPMain(const std::string &limelightName="")
Definition LimelightHelpers.h:201
void setLimelightNTDouble(const std::string &tableName, const std::string entryName, double val)
Definition LimelightHelpers.h:91
void setPythonScriptData(const std::string &limelightName, const std::vector< double > &outgoingPythonData)
Definition LimelightHelpers.h:247
double getFiducialID(const std::string &limelightName="")
Definition LimelightHelpers.h:165
void from_json(const wpi::json &j, RetroreflectiveResultClass &t)
Definition LimelightHelpers.h:596
void setCameraPose_RobotSpace(const std::string &limelightName, double forward, double side, double up, double roll, double pitch, double yaw)
Definition LimelightHelpers.h:241
void setLEDMode_ForceOn(const std::string &limelightName="")
Definition LimelightHelpers.h:193
std::vector< double > getTargetPose_RobotSpace(const std::string &limelightName="")
Definition LimelightHelpers.h:157
PoseEstimate getBotPoseEstimate_wpiRed_MegaTag2(const std::string &limelightName="")
Definition LimelightHelpers.h:364
double getLatency_Capture(const std::string &limelightName="")
Definition LimelightHelpers.h:121
std::string getLimelightNTString(const std::string &tableName, const std::string &entryName)
Definition LimelightHelpers.h:87
void setStreamMode_Standard(const std::string &limelightName="")
Definition LimelightHelpers.h:197
std::string sanitizeName(const std::string &name)
Definition LimelightHelpers.h:44
void setStreamMode_PiPSecondary(const std::string &limelightName="")
Definition LimelightHelpers.h:205
std::string getNeuralClassID(const std::string &limelightName="")
Definition LimelightHelpers.h:169
std::vector< double > getPythonScriptData(const std::string &limelightName="")
Definition LimelightHelpers.h:252
frc::Pose3d toPose3D(const std::vector< double > &inData)
Definition LimelightHelpers.h:51
void setLEDMode_PipelineControl(const std::string &limelightName="")
Definition LimelightHelpers.h:181
std::vector< double > getBotpose_TargetSpace(const std::string &limelightName="")
Definition LimelightHelpers.h:141
double getTV(const std::string &limelightName="")
Definition LimelightHelpers.h:105
void SetFiducialIDFiltersOverride(const std::string &limelightName, const std::vector< int > &validIDs)
Definition LimelightHelpers.h:233
std::vector< double > getTargetPose_CameraSpace(const std::string &limelightName="")
Definition LimelightHelpers.h:153
void PhoneHome()
Definition LimelightHelpers.h:519
void setCropWindow(const std::string &limelightName, double cropXMin, double cropXMax, double cropYMin, double cropYMax)
Definition LimelightHelpers.h:213
double getTA(const std::string &limelightName="")
Definition LimelightHelpers.h:113
void setLEDMode_ForceOff(const std::string &limelightName="")
Definition LimelightHelpers.h:185
void setPriorityTagID(const std::string &limelightName, int ID)
Definition LimelightHelpers.h:177
std::vector< double > getTargetColor(const std::string &limelightName="")
Definition LimelightHelpers.h:161
std::string getJSONDump(const std::string &limelightName="")
Definition LimelightHelpers.h:125
double extractBotPoseEntry(const std::vector< double > &inData, int position)
Definition LimelightHelpers.h:258