aruco_detect.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017-20, Ubiquity Robotics Inc., Austin Hendrix
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * 2. Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  *
14  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
15  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
17  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
18  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
20  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
21  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
22  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
23  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
24  * POSSIBILITY OF SUCH DAMAGE.
25  *
26  * The views and conclusions contained in the software and documentation are
27  * those of the authors and should not be interpreted as representing official
28  * policies, either expressed or implied, of the FreeBSD Project.
29  *
30  */
31 
32 #include <assert.h>
33 #include <sys/time.h>
34 #include <unistd.h>
35 #include <math.h>
36 
37 #include <ros/ros.h>
38 #include <tf/transform_datatypes.h>
40 #include <tf2_ros/buffer.h>
44 #include <visualization_msgs/Marker.h>
46 #include <cv_bridge/cv_bridge.h>
48 #include <dynamic_reconfigure/server.h>
49 #include <std_srvs/SetBool.h>
50 #include <std_msgs/String.h>
51 
52 #include "fiducial_msgs/Fiducial.h"
53 #include "fiducial_msgs/FiducialArray.h"
54 #include "fiducial_msgs/FiducialTransform.h"
55 #include "fiducial_msgs/FiducialTransformArray.h"
56 #include "aruco_detect/DetectorParamsConfig.h"
57 
58 #include <vision_msgs/Detection2D.h>
59 #include <vision_msgs/Detection2DArray.h>
60 #include <vision_msgs/ObjectHypothesisWithPose.h>
61 
62 #include <opencv2/highgui.hpp>
63 #include <opencv2/aruco.hpp>
64 #include <opencv2/calib3d.hpp>
65 
66 #include <list>
67 #include <string>
68 #include <boost/algorithm/string.hpp>
69 #include <boost/shared_ptr.hpp>
70 
71 using namespace std;
72 using namespace cv;
73 
75 
77  private:
80 
87 
89 
90  // if set, we publish the images that contain fiducials
93  bool vis_msgs;
94  bool verbose;
95 
96  double fiducial_len;
97 
101  vector <vector <Point2f> > corners;
102  vector <int> ids;
104 
105  cv::Mat cameraMatrix;
107  int frameNum;
108  std::string frameId;
109  std::vector<int> ignoreIds;
110  std::map<int, double> fiducialLens;
113 
115 
116  // log spam prevention
118 
119  cv::Ptr<aruco::DetectorParameters> detectorParams;
120  cv::Ptr<aruco::Dictionary> dictionary;
121 
122  void handleIgnoreString(const std::string& str);
123 
124  void estimatePoseSingleMarkers(float markerLength,
125  const cv::Mat &cameraMatrix,
126  const cv::Mat &distCoeffs,
127  vector<Vec3d>& rvecs, vector<Vec3d>& tvecs,
128  vector<double>& reprojectionError);
129 
130 
131  void ignoreCallback(const std_msgs::String &msg);
132  void imageCallback(const sensor_msgs::ImageConstPtr &msg);
133  void poseEstimateCallback(const FiducialArrayConstPtr &msg);
134  void camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg);
135  void configCallback(aruco_detect::DetectorParamsConfig &config, uint32_t level);
136 
137  bool enableDetectionsCallback(std_srvs::SetBool::Request &req,
138  std_srvs::SetBool::Response &res);
139 
140  dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig> configServer;
141  dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig>::CallbackType callbackType;
142 
143  public:
144  FiducialsNode();
145 };
146 
147 
151 static void getSingleMarkerObjectPoints(float markerLength, vector<Point3f>& objPoints) {
152 
153  CV_Assert(markerLength > 0);
154 
155  // set coordinate system in the middle of the marker, with Z pointing out
156  objPoints.clear();
157  objPoints.push_back(Vec3f(-markerLength / 2.f, markerLength / 2.f, 0));
158  objPoints.push_back(Vec3f( markerLength / 2.f, markerLength / 2.f, 0));
159  objPoints.push_back(Vec3f( markerLength / 2.f,-markerLength / 2.f, 0));
160  objPoints.push_back(Vec3f(-markerLength / 2.f,-markerLength / 2.f, 0));
161 }
162 
163 // Euclidean distance between two points
164 static double dist(const cv::Point2f &p1, const cv::Point2f &p2)
165 {
166  double x1 = p1.x;
167  double y1 = p1.y;
168  double x2 = p2.x;
169  double y2 = p2.y;
170 
171  double dx = x1 - x2;
172  double dy = y1 - y2;
173 
174  return sqrt(dx*dx + dy*dy);
175 }
176 
177 // Compute area in image of a fiducial, using Heron's formula
178 // to find the area of two triangles
179 static double calcFiducialArea(const std::vector<cv::Point2f> &pts)
180 {
181  const Point2f &p0 = pts.at(0);
182  const Point2f &p1 = pts.at(1);
183  const Point2f &p2 = pts.at(2);
184  const Point2f &p3 = pts.at(3);
185 
186  double a1 = dist(p0, p1);
187  double b1 = dist(p0, p3);
188  double c1 = dist(p1, p3);
189 
190  double a2 = dist(p1, p2);
191  double b2 = dist(p2, p3);
192  double c2 = c1;
193 
194  double s1 = (a1 + b1 + c1) / 2.0;
195  double s2 = (a2 + b2 + c2) / 2.0;
196 
197  a1 = sqrt(s1*(s1-a1)*(s1-b1)*(s1-c1));
198  a2 = sqrt(s2*(s2-a2)*(s2-b2)*(s2-c2));
199  return a1+a2;
200 }
201 
202 // estimate reprojection error
203 static double getReprojectionError(const vector<Point3f> &objectPoints,
204  const vector<Point2f> &imagePoints,
205  const Mat &cameraMatrix, const Mat &distCoeffs,
206  const Vec3d &rvec, const Vec3d &tvec) {
207 
208  vector<Point2f> projectedPoints;
209 
210  cv::projectPoints(objectPoints, rvec, tvec, cameraMatrix,
211  distCoeffs, projectedPoints);
212 
213  // calculate RMS image error
214  double totalError = 0.0;
215  for (unsigned int i=0; i<objectPoints.size(); i++) {
216  double error = dist(imagePoints[i], projectedPoints[i]);
217  totalError += error*error;
218  }
219  double rerror = totalError/(double)objectPoints.size();
220  return rerror;
221 }
222 
224  const cv::Mat &cameraMatrix,
225  const cv::Mat &distCoeffs,
226  vector<Vec3d>& rvecs, vector<Vec3d>& tvecs,
227  vector<double>& reprojectionError) {
228 
229  CV_Assert(markerLength > 0);
230 
231  vector<Point3f> markerObjPoints;
232  int nMarkers = (int)corners.size();
233  rvecs.reserve(nMarkers);
234  tvecs.reserve(nMarkers);
235  reprojectionError.reserve(nMarkers);
236 
237  // for each marker, calculate its pose
238  for (int i = 0; i < nMarkers; i++) {
239  double fiducialSize = markerLength;
240 
241  std::map<int, double>::iterator it = fiducialLens.find(ids[i]);
242  if (it != fiducialLens.end()) {
243  fiducialSize = it->second;
244  }
245 
246  getSingleMarkerObjectPoints(fiducialSize, markerObjPoints);
247  cv::solvePnP(markerObjPoints, corners[i], cameraMatrix, distCoeffs,
248  rvecs[i], tvecs[i]);
249 
250  reprojectionError[i] =
251  getReprojectionError(markerObjPoints, corners[i],
252  cameraMatrix, distCoeffs,
253  rvecs[i], tvecs[i]);
254  }
255 }
256 
257 void FiducialsNode::configCallback(aruco_detect::DetectorParamsConfig & config, uint32_t level)
258 {
259  /* Don't load initial config, since it will overwrite the rosparam settings */
260  if (level == 0xFFFFFFFF) {
261  return;
262  }
263 
264  detectorParams->adaptiveThreshConstant = config.adaptiveThreshConstant;
265  detectorParams->adaptiveThreshWinSizeMin = config.adaptiveThreshWinSizeMin;
266  detectorParams->adaptiveThreshWinSizeMax = config.adaptiveThreshWinSizeMax;
267  detectorParams->adaptiveThreshWinSizeStep = config.adaptiveThreshWinSizeStep;
268  detectorParams->cornerRefinementMaxIterations = config.cornerRefinementMaxIterations;
269  detectorParams->cornerRefinementMinAccuracy = config.cornerRefinementMinAccuracy;
270  detectorParams->cornerRefinementWinSize = config.cornerRefinementWinSize;
271 #if CV_MINOR_VERSION==2 and CV_MAJOR_VERSION==3
272  detectorParams->doCornerRefinement = config.doCornerRefinement;
273 #else
274  if (config.doCornerRefinement) {
275  if (config.cornerRefinementSubpix) {
276  detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
277  }
278  else {
279  detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_CONTOUR;
280  }
281  }
282  else {
283  detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_NONE;
284  }
285 #endif
286  detectorParams->errorCorrectionRate = config.errorCorrectionRate;
287  detectorParams->minCornerDistanceRate = config.minCornerDistanceRate;
288  detectorParams->markerBorderBits = config.markerBorderBits;
289  detectorParams->maxErroneousBitsInBorderRate = config.maxErroneousBitsInBorderRate;
290  detectorParams->minDistanceToBorder = config.minDistanceToBorder;
291  detectorParams->minMarkerDistanceRate = config.minMarkerDistanceRate;
292  detectorParams->minMarkerPerimeterRate = config.minMarkerPerimeterRate;
293  detectorParams->maxMarkerPerimeterRate = config.maxMarkerPerimeterRate;
294  detectorParams->minOtsuStdDev = config.minOtsuStdDev;
295  detectorParams->perspectiveRemoveIgnoredMarginPerCell = config.perspectiveRemoveIgnoredMarginPerCell;
296  detectorParams->perspectiveRemovePixelPerCell = config.perspectiveRemovePixelPerCell;
297  detectorParams->polygonalApproxAccuracyRate = config.polygonalApproxAccuracyRate;
298 }
299 
300 void FiducialsNode::ignoreCallback(const std_msgs::String& msg)
301 {
302  ignoreIds.clear();
303  pnh.setParam("ignore_fiducials", msg.data);
304  handleIgnoreString(msg.data);
305 }
306 
307 void FiducialsNode::camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg)
308 {
309  if (haveCamInfo) {
310  return;
311  }
312 
313  if (msg->K != boost::array<double, 9>({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0})) {
314  for (int i=0; i<3; i++) {
315  for (int j=0; j<3; j++) {
316  cameraMatrix.at<double>(i, j) = msg->K[i*3+j];
317  }
318  }
319 
320  for (int i=0; i<5; i++) {
321  distortionCoeffs.at<double>(0,i) = msg->D[i];
322  }
323 
324  haveCamInfo = true;
325  frameId = msg->header.frame_id;
326  }
327  else {
328  ROS_WARN("%s", "CameraInfo message has invalid intrinsics, K matrix all zeros");
329  }
330 }
331 
332 void FiducialsNode::imageCallback(const sensor_msgs::ImageConstPtr & msg)
333 {
334  if (enable_detections == false) {
335  return; //return without doing anything
336  }
337 
338  if(verbose){
339  ROS_INFO("Got image %d", msg->header.seq);
340  }
341 
342  fiducial_msgs::FiducialArray fva;
343  fva.header.stamp = msg->header.stamp;
344  fva.header.frame_id = frameId;
345  fva.image_seq = msg->header.seq;
346 
347  try {
349 
350  aruco::detectMarkers(cv_ptr->image, dictionary, corners, ids, detectorParams);
351 
352  int detected_count = (int)ids.size();
353  if(verbose || detected_count != prev_detected_count){
354  prev_detected_count = detected_count;
355  ROS_INFO("Detected %d markers", detected_count);
356  }
357 
358  for (size_t i=0; i<ids.size(); i++) {
359  if (std::count(ignoreIds.begin(), ignoreIds.end(), ids[i]) != 0) {
360  if(verbose){
361  ROS_INFO("Ignoring id %d", ids[i]);
362  }
363  continue;
364  }
365  fiducial_msgs::Fiducial fid;
366  fid.fiducial_id = ids[i];
367 
368  fid.x0 = corners[i][0].x;
369  fid.y0 = corners[i][0].y;
370  fid.x1 = corners[i][1].x;
371  fid.y1 = corners[i][1].y;
372  fid.x2 = corners[i][2].x;
373  fid.y2 = corners[i][2].y;
374  fid.x3 = corners[i][3].x;
375  fid.y3 = corners[i][3].y;
376  fva.fiducials.push_back(fid);
377  }
378 
379  vertices_pub.publish(fva);
380 
381  if(ids.size() > 0) {
382  aruco::drawDetectedMarkers(cv_ptr->image, corners, ids);
383  }
384 
385  if (publish_images) {
386  image_pub.publish(cv_ptr->toImageMsg());
387  }
388  }
389  catch(cv_bridge::Exception & e) {
390  ROS_ERROR("cv_bridge exception: %s", e.what());
391  }
392  catch(cv::Exception & e) {
393  ROS_ERROR("cv exception: %s", e.what());
394  }
395 }
396 
398 {
399  vector <Vec3d> rvecs, tvecs;
400 
401  vision_msgs::Detection2DArray vma;
402  fiducial_msgs::FiducialTransformArray fta;
403  if (vis_msgs) {
404  vma.header.stamp = msg->header.stamp;
405  vma.header.frame_id = frameId;
406  vma.header.seq = msg->header.seq;
407  }
408  else {
409  fta.header.stamp = msg->header.stamp;
410  fta.header.frame_id = frameId;
411  fta.image_seq = msg->header.seq;
412  }
413  frameNum++;
414 
415  if (doPoseEstimation) {
416  try {
417  if (!haveCamInfo) {
418  if (frameNum > 5) {
419  ROS_ERROR("No camera intrinsics");
420  }
421  return;
422  }
423 
424  vector <double>reprojectionError;
425  estimatePoseSingleMarkers((float)fiducial_len,
426  cameraMatrix, distortionCoeffs,
427  rvecs, tvecs,
428  reprojectionError);
429 
430  for (size_t i=0; i<ids.size(); i++) {
431  aruco::drawAxis(cv_ptr->image, cameraMatrix, distortionCoeffs,
432  rvecs[i], tvecs[i], (float)fiducial_len);
433  if(verbose){
434  ROS_INFO("Detected id %d T %.2f %.2f %.2f R %.2f %.2f %.2f", ids[i],
435  tvecs[i][0], tvecs[i][1], tvecs[i][2],
436  rvecs[i][0], rvecs[i][1], rvecs[i][2]);
437 
438  }
439 
440  if (std::count(ignoreIds.begin(), ignoreIds.end(), ids[i]) != 0) {
441  if(verbose){
442  ROS_INFO("Ignoring id %d", ids[i]);
443  }
444  continue;
445  }
446 
447  double angle = norm(rvecs[i]);
448  Vec3d axis = rvecs[i] / angle;
449 
450  if(verbose){
451  ROS_INFO("angle %f axis %f %f %f",
452  angle, axis[0], axis[1], axis[2]);
453  }
454 
455  double object_error =
456  (reprojectionError[i] / dist(corners[i][0], corners[i][2])) *
457  (norm(tvecs[i]) / fiducial_len);
458 
459  // Standard ROS vision_msgs
460  fiducial_msgs::FiducialTransform ft;
461  tf2::Quaternion q;
462  if (vis_msgs) {
463  vision_msgs::Detection2D vm;
464  vision_msgs::ObjectHypothesisWithPose vmh;
465  vmh.id = ids[i];
466  vmh.score = exp(-2 * object_error); // [0, infinity] -> [1,0]
467  vmh.pose.pose.position.x = tvecs[i][0];
468  vmh.pose.pose.position.y = tvecs[i][1];
469  vmh.pose.pose.position.z = tvecs[i][2];
470  q.setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
471  vmh.pose.pose.orientation.w = q.w();
472  vmh.pose.pose.orientation.x = q.x();
473  vmh.pose.pose.orientation.y = q.y();
474  vmh.pose.pose.orientation.z = q.z();
475 
476  vm.results.push_back(vmh);
477  vma.detections.push_back(vm);
478  }
479  else {
480  ft.fiducial_id = ids[i];
481 
482  ft.transform.translation.x = tvecs[i][0];
483  ft.transform.translation.y = tvecs[i][1];
484  ft.transform.translation.z = tvecs[i][2];
485  q.setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
486  ft.transform.rotation.w = q.w();
487  ft.transform.rotation.x = q.x();
488  ft.transform.rotation.y = q.y();
489  ft.transform.rotation.z = q.z();
490  ft.fiducial_area = calcFiducialArea(corners[i]);
491  ft.image_error = reprojectionError[i];
492  // Convert image_error (in pixels) to object_error (in meters)
493  ft.object_error =
494  (reprojectionError[i] / dist(corners[i][0], corners[i][2])) *
495  (norm(tvecs[i]) / fiducial_len);
496 
497  fta.transforms.push_back(ft);
498  }
499 
500  // Publish tf for the fiducial relative to the camera
501  if (publishFiducialTf) {
502  if (vis_msgs) {
503  geometry_msgs::TransformStamped ts;
504  ts.transform.translation.x = tvecs[i][0];
505  ts.transform.translation.y = tvecs[i][1];
506  ts.transform.translation.z = tvecs[i][2];
507  ts.transform.rotation.w = q.w();
508  ts.transform.rotation.x = q.x();
509  ts.transform.rotation.y = q.y();
510  ts.transform.rotation.z = q.z();
511  ts.header.frame_id = frameId;
512  ts.header.stamp = msg->header.stamp;
513  ts.child_frame_id = "fiducial_" + std::to_string(ids[i]);
514  broadcaster.sendTransform(ts);
515  }
516  else {
517  geometry_msgs::TransformStamped ts;
518  ts.transform = ft.transform;
519  ts.header.frame_id = frameId;
520  ts.header.stamp = msg->header.stamp;
521  ts.child_frame_id = "fiducial_" + std::to_string(ft.fiducial_id);
522  broadcaster.sendTransform(ts);
523  }
524  }
525  }
526  }
527  catch(cv_bridge::Exception & e) {
528  ROS_ERROR("cv_bridge exception: %s", e.what());
529  }
530  catch(cv::Exception & e) {
531  ROS_ERROR("cv exception: %s", e.what());
532  }
533  }
534  if (vis_msgs)
535  pose_pub.publish(vma);
536  else
537  pose_pub.publish(fta);
538 }
539 
540 void FiducialsNode::handleIgnoreString(const std::string& str)
541 {
542  /*
543  ignogre fiducials can take comma separated list of individual
544  fiducial ids or ranges, eg "1,4,8,9-12,30-40"
545  */
546  std::vector<std::string> strs;
547  boost::split(strs, str, boost::is_any_of(","));
548  for (const string& element : strs) {
549  if (element == "") {
550  continue;
551  }
552  std::vector<std::string> range;
553  boost::split(range, element, boost::is_any_of("-"));
554  if (range.size() == 2) {
555  int start = std::stoi(range[0]);
556  int end = std::stoi(range[1]);
557  ROS_INFO("Ignoring fiducial id range %d to %d", start, end);
558  for (int j=start; j<=end; j++) {
559  ignoreIds.push_back(j);
560  }
561  }
562  else if (range.size() == 1) {
563  int fid = std::stoi(range[0]);
564  ROS_INFO("Ignoring fiducial id %d", fid);
565  ignoreIds.push_back(fid);
566  }
567  else {
568  ROS_ERROR("Malformed ignore_fiducials: %s", element.c_str());
569  }
570  }
571 }
572 
573 bool FiducialsNode::enableDetectionsCallback(std_srvs::SetBool::Request &req,
574  std_srvs::SetBool::Response &res)
575 {
576  enable_detections = req.data;
577  if (enable_detections){
578  res.message = "Enabled aruco detections.";
579  ROS_INFO("Enabled aruco detections.");
580  }
581  else {
582  res.message = "Disabled aruco detections.";
583  ROS_INFO("Disabled aruco detections.");
584  }
585 
586  res.success = true;
587  return true;
588 }
589 
590 
591 FiducialsNode::FiducialsNode() : nh(), pnh("~"), it(nh)
592 {
593  frameNum = 0;
594  prev_detected_count = -1;
595 
596  // Camera intrinsics
597  cameraMatrix = cv::Mat::zeros(3, 3, CV_64F);
598 
599  // distortion coefficients
600  distortionCoeffs = cv::Mat::zeros(1, 5, CV_64F);
601 
602  haveCamInfo = false;
603  enable_detections = true;
604 
605  int dicno;
606 
607  detectorParams = new aruco::DetectorParameters();
608 
609  pnh.param<bool>("publish_images", publish_images, false);
610  pnh.param<double>("fiducial_len", fiducial_len, 0.14);
611  pnh.param<int>("dictionary", dicno, 7);
612  pnh.param<bool>("do_pose_estimation", doPoseEstimation, true);
613  pnh.param<bool>("publish_fiducial_tf", publishFiducialTf, true);
614  pnh.param<bool>("vis_msgs", vis_msgs, false);
615  pnh.param<bool>("verbose", verbose, false);
616 
617  std::string str;
618  std::vector<std::string> strs;
619 
620  pnh.param<string>("ignore_fiducials", str, "");
621  handleIgnoreString(str);
622 
623  /*
624  fiducial size can take comma separated list of size: id or size: range,
625  e.g. "200.0: 12, 300.0: 200-300"
626  */
627  pnh.param<string>("fiducial_len_override", str, "");
628  boost::split(strs, str, boost::is_any_of(","));
629  for (const string& element : strs) {
630  if (element == "") {
631  continue;
632  }
633  std::vector<std::string> parts;
634  boost::split(parts, element, boost::is_any_of(":"));
635  if (parts.size() == 2) {
636  double len = std::stod(parts[1]);
637  std::vector<std::string> range;
638  boost::split(range, element, boost::is_any_of("-"));
639  if (range.size() == 2) {
640  int start = std::stoi(range[0]);
641  int end = std::stoi(range[1]);
642  ROS_INFO("Setting fiducial id range %d - %d length to %f",
643  start, end, len);
644  for (int j=start; j<=end; j++) {
645  fiducialLens[j] = len;
646  }
647  }
648  else if (range.size() == 1){
649  int fid = std::stoi(range[0]);
650  ROS_INFO("Setting fiducial id %d length to %f", fid, len);
651  fiducialLens[fid] = len;
652  }
653  else {
654  ROS_ERROR("Malformed fiducial_len_override: %s", element.c_str());
655  }
656  }
657  else {
658  ROS_ERROR("Malformed fiducial_len_override: %s", element.c_str());
659  }
660  }
661 
662  image_pub = it.advertise("/fiducial_images", 1);
663 
664  vertices_pub = nh.advertise<fiducial_msgs::FiducialArray>("fiducial_vertices", 1);
665 
666  if (vis_msgs)
667  pose_pub = nh.advertise<vision_msgs::Detection2DArray>("fiducial_transforms", 1);
668  else
669  pose_pub = nh.advertise<fiducial_msgs::FiducialTransformArray>("fiducial_transforms", 1);
670 
671  dictionary = aruco::getPredefinedDictionary(dicno);
672 
673  img_sub = it.subscribe("camera", 1,
675 
676  vertices_sub = nh.subscribe("fiducial_vertices", 1,
678  caminfo_sub = nh.subscribe("camera_info", 1,
680 
681  ignore_sub = nh.subscribe("ignore_fiducials", 1,
683 
684  service_enable_detections = nh.advertiseService("enable_detections",
686 
687  callbackType = boost::bind(&FiducialsNode::configCallback, this, _1, _2);
688  configServer.setCallback(callbackType);
689 
690  pnh.param<double>("adaptiveThreshConstant", detectorParams->adaptiveThreshConstant, 7);
691  pnh.param<int>("adaptiveThreshWinSizeMax", detectorParams->adaptiveThreshWinSizeMax, 53); /* defailt 23 */
692  pnh.param<int>("adaptiveThreshWinSizeMin", detectorParams->adaptiveThreshWinSizeMin, 3);
693  pnh.param<int>("adaptiveThreshWinSizeStep", detectorParams->adaptiveThreshWinSizeStep, 4); /* default 10 */
694  pnh.param<int>("cornerRefinementMaxIterations", detectorParams->cornerRefinementMaxIterations, 30);
695  pnh.param<double>("cornerRefinementMinAccuracy", detectorParams->cornerRefinementMinAccuracy, 0.01); /* default 0.1 */
696  pnh.param<int>("cornerRefinementWinSize", detectorParams->cornerRefinementWinSize, 5);
697 #if CV_MINOR_VERSION==2 and CV_MAJOR_VERSION==3
698  pnh.param<bool>("doCornerRefinement",detectorParams->doCornerRefinement, true); /* default false */
699 #else
700  bool doCornerRefinement = true;
701  pnh.param<bool>("doCornerRefinement", doCornerRefinement, true);
702  if (doCornerRefinement) {
703  bool cornerRefinementSubPix = true;
704  pnh.param<bool>("cornerRefinementSubPix", cornerRefinementSubPix, true);
705  if (cornerRefinementSubPix) {
706  detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
707  }
708  else {
709  detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_CONTOUR;
710  }
711  }
712  else {
713  detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_NONE;
714  }
715 #endif
716  pnh.param<double>("errorCorrectionRate", detectorParams->errorCorrectionRate , 0.6);
717  pnh.param<double>("minCornerDistanceRate", detectorParams->minCornerDistanceRate , 0.05);
718  pnh.param<int>("markerBorderBits", detectorParams->markerBorderBits, 1);
719  pnh.param<double>("maxErroneousBitsInBorderRate", detectorParams->maxErroneousBitsInBorderRate, 0.04);
720  pnh.param<int>("minDistanceToBorder", detectorParams->minDistanceToBorder, 3);
721  pnh.param<double>("minMarkerDistanceRate", detectorParams->minMarkerDistanceRate, 0.05);
722  pnh.param<double>("minMarkerPerimeterRate", detectorParams->minMarkerPerimeterRate, 0.1); /* default 0.3 */
723  pnh.param<double>("maxMarkerPerimeterRate", detectorParams->maxMarkerPerimeterRate, 4.0);
724  pnh.param<double>("minOtsuStdDev", detectorParams->minOtsuStdDev, 5.0);
725  pnh.param<double>("perspectiveRemoveIgnoredMarginPerCell", detectorParams->perspectiveRemoveIgnoredMarginPerCell, 0.13);
726  pnh.param<int>("perspectiveRemovePixelPerCell", detectorParams->perspectiveRemovePixelPerCell, 8);
727  pnh.param<double>("polygonalApproxAccuracyRate", detectorParams->polygonalApproxAccuracyRate, 0.01); /* default 0.05 */
728 
729  ROS_INFO("Aruco detection ready");
730 }
731 
732 int main(int argc, char ** argv) {
733  ros::init(argc, argv, "aruco_detect");
734 
735  FiducialsNode* fd_node = new FiducialsNode();
736 
737  ros::spin();
738 
739  return 0;
740 }
void ignoreCallback(const std_msgs::String &msg)
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber caminfo_sub
image_transport::Subscriber img_sub
cv::Ptr< aruco::DetectorParameters > detectorParams
dynamic_reconfigure::Server< aruco_detect::DetectorParamsConfig >::CallbackType callbackType
ROSCPP_DECL void start()
dynamic_reconfigure::Server< aruco_detect::DetectorParamsConfig > configServer
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
f
ros::ServiceServer service_enable_detections
void configCallback(aruco_detect::DetectorParamsConfig &config, uint32_t level)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string frameId
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
std::map< int, double > fiducialLens
cv::Mat distortionCoeffs
std::string * frameId(M &m)
vector< int > ids
ros::NodeHandle nh
ros::Subscriber vertices_sub
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::ImageTransport it
cv::Ptr< aruco::Dictionary > dictionary
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
std::vector< int > ignoreIds
int main(int argc, char **argv)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ros::Subscriber ignore_sub
void handleIgnoreString(const std::string &str)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
static double getReprojectionError(const vector< Point3f > &objectPoints, const vector< Point2f > &imagePoints, const Mat &cameraMatrix, const Mat &distCoeffs, const Vec3d &rvec, const Vec3d &tvec)
double fiducial_len
#define ROS_INFO(...)
cv_bridge::CvImagePtr cv_ptr
boost::shared_ptr< fiducial_msgs::FiducialArray const > FiducialArrayConstPtr
ros::Publisher pose_pub
void poseEstimateCallback(const FiducialArrayConstPtr &msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ros::NodeHandle pnh
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
vector< vector< Point2f > > corners
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
void setRotation(const Vector3 &axis, const tf2Scalar &angle)
bool enable_detections
image_transport::Publisher image_pub
static double calcFiducialArea(const std::vector< cv::Point2f > &pts)
void estimatePoseSingleMarkers(float markerLength, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, vector< Vec3d > &rvecs, vector< Vec3d > &tvecs, vector< double > &reprojectionError)
void camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
cv::Mat cameraMatrix
static void getSingleMarkerObjectPoints(float markerLength, vector< Point3f > &objPoints)
Return object points for the system centered in a single marker, given the marker length...
tf2_ros::TransformBroadcaster broadcaster
#define ROS_ERROR(...)
bool enableDetectionsCallback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::Publisher vertices_pub
static double dist(const cv::Point2f &p1, const cv::Point2f &p2)


aruco_detect
Author(s): Jim Vaughan
autogenerated on Mon Feb 28 2022 22:23:31