13#include <netinet/in.h>
14#include <sys/socket.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>
37#include "networktables/NetworkTable.h"
38#include "networktables/NetworkTableEntry.h"
39#include "networktables/NetworkTableInstance.h"
40#include "networktables/NetworkTableValue.h"
51 inline frc::Pose3d
toPose3D(
const std::vector<double>& inData) {
52 if (inData.size() < 6) {
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))));
63 inline frc::Pose2d
toPose2D(
const std::vector<double>& inData) {
64 if (inData.size() < 6) {
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))));
72 return nt::NetworkTableInstance::GetDefault().GetTable(
sanitizeName(tableName));
96 const std::string& entryName,
97 const std::span<const double>& vals) {
101 inline double getTX(
const std::string& limelightName =
"") {
105 inline double getTV(
const std::string& limelightName =
"") {
109 inline double getTY(
const std::string& limelightName =
"") {
113 inline double getTA(
const std::string& limelightName =
"") {
125 inline std::string
getJSONDump(
const std::string& limelightName =
"") {
129 inline std::vector<double>
getBotpose(
const std::string& limelightName =
"") {
161 inline std::vector<double>
getTargetColor(
const std::string& limelightName =
"") {
214 const std::string& limelightName,
double cropXMin,
double cropXMax,
double cropYMin,
double cropYMax) {
215 double cropWindow[4]{cropXMin, cropXMax, cropYMin, cropYMax};
229 std::vector<double> entries = {yaw, yawRate, pitch, pitchRate, roll, rollRate};
234 std::vector<double> validIDsDouble(validIDs.begin(), validIDs.end());
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};
247 inline void setPythonScriptData(
const std::string& limelightName,
const std::vector<double>& outgoingPythonData) {
249 limelightName,
"llrobot", std::span{outgoingPythonData.begin(), outgoingPythonData.size()});
259 if (inData.size() <
static_cast<size_t>(position + 1)) {
262 return inData[position];
318 std::vector<double> poseArray = poseEntry.GetDoubleArray(std::span<double>{});
319 frc::Pose2d pose =
toPose2D(poseArray);
328 units::time::second_t timestamp =
329 units::time::second_t((poseEntry.GetLastChange() / 1000000.0) - (latency / 1000.0));
331 std::vector<RawFiducial> rawFiducials;
332 int valsPerFiducial = 7;
333 size_t expectedTotalVals = 11 + valsPerFiducial * tagCount;
335 if (poseArray.size() == expectedTotalVals) {
336 for (
int i = 0; i < tagCount; i++) {
337 int baseIndex = 11 + (i * valsPerFiducial);
345 rawFiducials.emplace_back(
id, txnc, tync, ta, distToCamera, distToRobot, ambiguity);
349 return PoseEstimate(pose, timestamp, latency, tagCount, tagSpan, tagDist, tagArea, rawFiducials);
520 static int sockfd = -1;
521 static struct sockaddr_in servaddr, cliaddr;
524 sockfd = socket(AF_INET, SOCK_DGRAM, 0);
526 std::cerr <<
"Socket creation failed" << std::endl;
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);
537 if (setsockopt(sockfd, SOL_SOCKET, SO_BROADCAST, &broadcast,
sizeof(broadcast)) < 0) {
538 std::cerr <<
"Error in setting Broadcast option" << std::endl;
545 if (fcntl(sockfd, F_SETFL, O_NONBLOCK) < 0) {
546 std::cerr <<
"Error setting socket to non-blocking" << std::endl;
552 const char* msg =
"LLPhoneHome";
553 sendto(sockfd, msg, std::strlen(msg), 0, (
const struct sockaddr*)&servaddr,
sizeof(servaddr));
556 char receiveData[1024];
557 socklen_t len =
sizeof(cliaddr);
559 ssize_t n = recvfrom(sockfd,
reinterpret_cast<char*
>(receiveData), 1024, 0, (
struct sockaddr*)&cliaddr, &len);
561 receiveData[n] =
'\0';
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;
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);
586 template <
typename T,
typename KeyType>
587 T
SafeJSONAccess(
const wpi::json& jsonData,
const KeyType& key,
const T& defaultValue) {
589 return jsonData.at(key).template get<T>();
590 }
catch (wpi::json::exception& e) {
597 std::vector<double> defaultValueVector(6, 0.0);
618 SafeJSONAccess<std::vector<std::vector<double>>>(j,
internal::_key_corners, std::vector<std::vector<double>>{});
622 std::vector<double> defaultValueVector(6, 0.0);
644 SafeJSONAccess<std::vector<std::vector<double>>>(j,
internal::_key_corners, std::vector<std::vector<double>>{});
657 SafeJSONAccess<std::vector<std::vector<double>>>(j,
internal::_key_corners, std::vector<std::vector<double>>{});
670 SafeJSONAccess<std::vector<std::vector<double>>>(j,
internal::_key_corners, std::vector<std::vector<double>>{});
678 t.
valid = SafeJSONAccess<double>(j,
"v", 0.0);
680 std::vector<double> defaultVector{};
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>{});
701 auto start = std::chrono::high_resolution_clock::now();
702 std::string jsonString =
getJSONDump(limelightName);
705 data = wpi::json::parse(jsonString);
706 }
catch (
const std::exception& e) {
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);
717 std::cout <<
"lljson: " << millis << std::endl;
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
~SingleTargetingResultClass()=default
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
SingleTargetingResultClass()=default
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