mono_qr_pattern.cpp
Go to the documentation of this file.
1 /*
2  velo2cam_calibration - Automatic calibration algorithm for extrinsic
3  parameters of a stereo camera and a velodyne Copyright (C) 2017-2021 Jorge
4  Beltran, Carlos Guindel
5 
6  This file is part of velo2cam_calibration.
7 
8  velo2cam_calibration is free software: you can redistribute it and/or modify
9  it under the terms of the GNU General Public License as published by
10  the Free Software Foundation, either version 2 of the License, or
11  (at your option) any later version.
12 
13  velo2cam_calibration is distributed in the hope that it will be useful,
14  but WITHOUT ANY WARRANTY; without even the implied warranty of
15  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  GNU General Public License for more details.
17 
18  You should have received a copy of the GNU General Public License
19  along with velo2cam_calibration. If not, see <http://www.gnu.org/licenses/>.
20 */
21 
22 /*
23  mono_qr_pattern: Find the circle centers in the color image by making use of
24  the ArUco markers
25 */
26 
27 #include <cv_bridge/cv_bridge.h>
28 #include <dynamic_reconfigure/server.h>
32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
35 #include <ros/ros.h>
36 #include <sensor_msgs/CameraInfo.h>
37 #include <sensor_msgs/Image.h>
38 #include <sensor_msgs/PointCloud2.h>
39 #include <std_msgs/Empty.h>
40 #include <velo2cam_calibration/ClusterCentroids.h>
41 #include <velo2cam_calibration/MonocularConfig.h>
42 #include <velo2cam_utils.h>
43 
44 #include <opencv2/aruco.hpp>
45 #include <opencv2/opencv.hpp>
46 
47 using namespace std;
48 using namespace cv;
49 
50 pcl::PointCloud<pcl::PointXYZ>::Ptr cumulative_cloud;
51 cv::Ptr<cv::aruco::Dictionary> dictionary;
53 
54 // ROS params
61 
62 bool WARMUP_DONE = false;
63 
66 std::ofstream savefile;
67 
68 Point2f projectPointDist(cv::Point3f pt_cv, const Mat intrinsics,
69  const Mat distCoeffs) {
70  // Project a 3D point taking into account distortion
71  vector<Point3f> input{pt_cv};
72  vector<Point2f> projectedPoints;
73  projectedPoints.resize(
74  1); // TODO: Do it batched? (cv::circle is not batched anyway)
75  projectPoints(input, Mat::zeros(3, 1, CV_64FC1), Mat::zeros(3, 1, CV_64FC1),
76  intrinsics, distCoeffs, projectedPoints);
77  return projectedPoints[0];
78 }
79 
80 Eigen::Vector3f mean(pcl::PointCloud<pcl::PointXYZ>::Ptr cumulative_cloud) {
81  double x = 0, y = 0, z = 0;
82  int npoints = cumulative_cloud->points.size();
83  for (pcl::PointCloud<pcl::PointXYZ>::iterator pt =
84  cumulative_cloud->points.begin();
85  pt < cumulative_cloud->points.end(); pt++) {
86  x += (pt->x) / npoints;
87  y += (pt->y) / npoints;
88  z += (pt->z) / npoints;
89  }
90  return Eigen::Vector3f(x, y, z);
91 }
92 
93 Eigen::Matrix3f covariance(pcl::PointCloud<pcl::PointXYZ>::Ptr cumulative_cloud,
94  Eigen::Vector3f means) {
95  double x = 0, y = 0, z = 0;
96  int npoints = cumulative_cloud->points.size();
97  vector<Eigen::Vector3f> points;
98 
99  for (pcl::PointCloud<pcl::PointXYZ>::iterator pt =
100  cumulative_cloud->points.begin();
101  pt < cumulative_cloud->points.end(); pt++) {
102  Eigen::Vector3f p(pt->x, pt->y, pt->z);
103  points.push_back(p);
104  }
105 
106  Eigen::Matrix3f covarianceMatrix(3, 3);
107  for (int i = 0; i < 3; i++)
108  for (int j = 0; j < 3; j++) {
109  covarianceMatrix(i, j) = 0.0;
110  for (int k = 0; k < npoints; k++) {
111  covarianceMatrix(i, j) +=
112  (means[i] - points[k][i]) * (means[j] - points[k][j]);
113  }
114  covarianceMatrix(i, j) /= npoints - 1;
115  }
116  return covarianceMatrix;
117 }
118 
119 void imageCallback(const sensor_msgs::ImageConstPtr &msg,
120  const sensor_msgs::CameraInfoConstPtr &left_info) {
121  frames_proc_++;
122 
123  cv_bridge::CvImageConstPtr cv_img_ptr;
124  try {
125  cv_img_ptr = cv_bridge::toCvShare(msg);
126  } catch (cv_bridge::Exception &e) {
127  ROS_ERROR("cv_bridge exception: %s", e.what());
128  return;
129  }
130  cv::Mat image = cv_img_ptr->image;
131  cv::Mat imageCopy;
132  image.copyTo(imageCopy);
133  sensor_msgs::CameraInfoPtr cinfo(new sensor_msgs::CameraInfo(*left_info));
135 
136  // TODO Not needed at each frame -> Move it to separate callback
137  Mat cameraMatrix(3, 3, CV_32F);
138  // Note that camera matrix is K, not P; both are interchangeable only
139  // if D is zero
140  cameraMatrix.at<float>(0, 0) = cinfo->K[0];
141  cameraMatrix.at<float>(0, 1) = cinfo->K[1];
142  cameraMatrix.at<float>(0, 2) = cinfo->K[2];
143  cameraMatrix.at<float>(1, 0) = cinfo->K[3];
144  cameraMatrix.at<float>(1, 1) = cinfo->K[4];
145  cameraMatrix.at<float>(1, 2) = cinfo->K[5];
146  cameraMatrix.at<float>(2, 0) = cinfo->K[6];
147  cameraMatrix.at<float>(2, 1) = cinfo->K[7];
148  cameraMatrix.at<float>(2, 2) = cinfo->K[8];
149 
150  Mat distCoeffs(1, cinfo->D.size(), CV_32F);
151  for (int i = 0; i < cinfo->D.size(); i++)
152  distCoeffs.at<float>(0, i) = cinfo->D[i];
153  // TODO End of block to move
154 
155  // Create vector of markers corners. 4 markers * 4 corners
156  // Markers order:
157  // 0-------1
158  // | |
159  // | C |
160  // | |
161  // 3-------2
162 
163  // WARNING: IDs are in different order:
164  // Marker 0 -> aRuCo ID: 1
165  // Marker 1 -> aRuCo ID: 2
166  // Marker 2 -> aRuCo ID: 4
167  // Marker 3 -> aRuCo ID: 3
168 
169  std::vector<std::vector<cv::Point3f>> boardCorners;
170 std:
171  vector<cv::Point3f> boardCircleCenters;
172  float width = delta_width_qr_center_;
173  float height = delta_height_qr_center_;
174  float circle_width = delta_width_circles_ / 2.;
175  float circle_height = delta_height_circles_ / 2.;
176  boardCorners.resize(4);
177  for (int i = 0; i < 4; ++i) {
178  int x_qr_center =
179  (i % 3) == 0 ? -1 : 1; // x distances are substracted for QRs on the
180  // left, added otherwise
181  int y_qr_center =
182  (i < 2) ? 1 : -1; // y distances are added for QRs above target's
183  // center, substracted otherwise
184  float x_center = x_qr_center * width;
185  float y_center = y_qr_center * height;
186 
187  cv::Point3f circleCenter3d(x_qr_center * circle_width,
188  y_qr_center * circle_height, 0);
189  boardCircleCenters.push_back(circleCenter3d);
190  for (int j = 0; j < 4; ++j) {
191  int x_qr = (j % 3) == 0 ? -1 : 1; // x distances are added for QRs 0 and
192  // 3, substracted otherwise
193  int y_qr = (j < 2) ? 1 : -1; // y distances are added for QRs 0 and 1,
194  // substracted otherwise
195  cv::Point3f pt3d(x_center + x_qr * marker_size_ / 2.,
196  y_center + y_qr * marker_size_ / 2., 0);
197  boardCorners[i].push_back(pt3d);
198  }
199  }
200 
201  std::vector<int> boardIds{1, 2, 4, 3}; // IDs order as explained above
202  cv::Ptr<cv::aruco::Board> board =
203  cv::aruco::Board::create(boardCorners, dictionary, boardIds);
204 
205  cv::Ptr<cv::aruco::DetectorParameters> parameters =
206  cv::aruco::DetectorParameters::create();
207  // set tp use corner refinement for accuracy, values obtained
208  // for pixel coordinates are more accurate than the neaterst pixel
209 
210 #if (CV_MAJOR_VERSION == 3 && CV_MINOR_VERSION <= 2) || CV_MAJOR_VERSION < 3
211  parameters->doCornerRefinement = true;
212 #else
213  parameters->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
214 #endif
215 
216  // Detect markers
217  std::vector<int> ids;
218  std::vector<std::vector<cv::Point2f>> corners;
219  cv::aruco::detectMarkers(image, dictionary, corners, ids, parameters);
220 
221  // Draw detections if at least one marker detected
222  if (ids.size() > 0) cv::aruco::drawDetectedMarkers(imageCopy, corners, ids);
223 
224  cv::Vec3d rvec(0, 0, 0), tvec(0, 0, 0); // Vectors to store initial guess
225 
226  // Compute initial guess as average of individual markers poses
227  if (ids.size() >= min_detected_markers_ && ids.size() <= TARGET_NUM_CIRCLES) {
228  // Estimate 3D position of the markers
229  vector<Vec3d> rvecs, tvecs;
230  Vec3f rvec_sin, rvec_cos;
231  cv::aruco::estimatePoseSingleMarkers(corners, marker_size_, cameraMatrix,
232  distCoeffs, rvecs, tvecs);
233 
234  // Draw markers' axis and centers in color image (Debug purposes)
235  for (int i = 0; i < ids.size(); i++) {
236  double x = tvecs[i][0];
237  double y = tvecs[i][1];
238  double z = tvecs[i][2];
239 
240  cv::Point3f pt_cv(x, y, z);
241  cv::Point2f uv;
242  uv = projectPointDist(pt_cv, cameraMatrix, distCoeffs);
243 
244  cv::aruco::drawAxis(imageCopy, cameraMatrix, distCoeffs, rvecs[i],
245  tvecs[i], 0.1);
246 
247  // Accumulate pose for initial guess
248  tvec[0] += tvecs[i][0];
249  tvec[1] += tvecs[i][1];
250  tvec[2] += tvecs[i][2];
251  rvec_sin[0] += sin(rvecs[i][0]);
252  rvec_sin[1] += sin(rvecs[i][1]);
253  rvec_sin[2] += sin(rvecs[i][2]);
254  rvec_cos[0] += cos(rvecs[i][0]);
255  rvec_cos[1] += cos(rvecs[i][1]);
256  rvec_cos[2] += cos(rvecs[i][2]);
257  }
258 
259  // Compute average pose. Rotation computed as atan2(sin/cos)
260  tvec = tvec / int(ids.size());
261  rvec_sin = rvec_sin / int(ids.size()); // Average sin
262  rvec_cos = rvec_cos / int(ids.size()); // Average cos
263  rvec[0] = atan2(rvec_sin[0], rvec_cos[0]);
264  rvec[1] = atan2(rvec_sin[1], rvec_cos[1]);
265  rvec[2] = atan2(rvec_sin[2], rvec_cos[2]);
266 
267  pcl::PointCloud<pcl::PointXYZ>::Ptr centers_cloud(
268  new pcl::PointCloud<pcl::PointXYZ>);
269  pcl::PointCloud<pcl::PointXYZ>::Ptr candidates_cloud(
270  new pcl::PointCloud<pcl::PointXYZ>);
271 
272 // Estimate 3D position of the board using detected markers
273 #if (CV_MAJOR_VERSION == 3 && CV_MINOR_VERSION <= 2) || CV_MAJOR_VERSION < 3
274  int valid = cv::aruco::estimatePoseBoard(corners, ids, board, cameraMatrix,
275  distCoeffs, rvec, tvec);
276 #else
277  int valid = cv::aruco::estimatePoseBoard(corners, ids, board, cameraMatrix,
278  distCoeffs, rvec, tvec, true);
279 #endif
280 
281  cv::aruco::drawAxis(imageCopy, cameraMatrix, distCoeffs, rvec, tvec, 0.2);
282 
283  // Build transformation matrix to calibration target axis
284  cv::Mat R(3, 3, cv::DataType<float>::type);
285  cv::Rodrigues(rvec, R);
286 
287  cv::Mat t = cv::Mat::zeros(3, 1, CV_32F);
288  t.at<float>(0) = tvec[0];
289  t.at<float>(1) = tvec[1];
290  t.at<float>(2) = tvec[2];
291 
292  cv::Mat board_transform = cv::Mat::eye(3, 4, CV_32F);
293  R.copyTo(board_transform.rowRange(0, 3).colRange(0, 3));
294  t.copyTo(board_transform.rowRange(0, 3).col(3));
295 
296  // Compute coordintates of circle centers
297  for (int i = 0; i < boardCircleCenters.size(); ++i) {
298  cv::Mat mat = cv::Mat::zeros(4, 1, CV_32F);
299  mat.at<float>(0, 0) = boardCircleCenters[i].x;
300  mat.at<float>(1, 0) = boardCircleCenters[i].y;
301  mat.at<float>(2, 0) = boardCircleCenters[i].z;
302  mat.at<float>(3, 0) = 1.0;
303 
304  // Transform center to target coords
305  cv::Mat mat_qr = board_transform * mat;
306  cv::Point3f center3d;
307  center3d.x = mat_qr.at<float>(0, 0);
308  center3d.y = mat_qr.at<float>(1, 0);
309  center3d.z = mat_qr.at<float>(2, 0);
310 
311  // Draw center (DEBUG)
312  cv::Point2f uv;
313  uv = projectPointDist(center3d, cameraMatrix, distCoeffs);
314  circle(imageCopy, uv, 10, Scalar(0, 255, 0), -1);
315 
316  // Add center to list
317  pcl::PointXYZ qr_center;
318  qr_center.x = center3d.x;
319  qr_center.y = center3d.y;
320  qr_center.z = center3d.z;
321  candidates_cloud->push_back(qr_center);
322  }
323 
340  std::vector<std::vector<int>> groups;
341  comb(candidates_cloud->size(), TARGET_NUM_CIRCLES, groups);
342  double groups_scores[groups.size()]; // -1: invalid; 0-1 normalized score
343  for (int i = 0; i < groups.size(); ++i) {
344  std::vector<pcl::PointXYZ> candidates;
345  // Build candidates set
346  for (int j = 0; j < groups[i].size(); ++j) {
347  pcl::PointXYZ center;
348  center.x = candidates_cloud->at(groups[i][j]).x;
349  center.y = candidates_cloud->at(groups[i][j]).y;
350  center.z = candidates_cloud->at(groups[i][j]).z;
351  candidates.push_back(center);
352  }
353 
354  // Compute candidates score
355  Square square_candidate(candidates, delta_width_circles_,
357  groups_scores[i] = square_candidate.is_valid()
358  ? 1.0
359  : -1; // -1 when it's not valid, 1 otherwise
360  }
361 
362  int best_candidate_idx = -1;
363  double best_candidate_score = -1;
364  for (int i = 0; i < groups.size(); ++i) {
365  if (best_candidate_score == 1 && groups_scores[i] == 1) {
366  // Exit 4: Several candidates fit target's geometry
367  ROS_ERROR(
368  "[Mono] More than one set of candidates fit target's geometry. "
369  "Please, make sure your parameters are well set. Exiting callback");
370  return;
371  }
372  if (groups_scores[i] > best_candidate_score) {
373  best_candidate_score = groups_scores[i];
374  best_candidate_idx = i;
375  }
376  }
377 
378  if (best_candidate_idx == -1) {
379  // Exit: No candidates fit target's geometry
380  ROS_WARN(
381  "[Mono] Unable to find a candidate set that matches target's "
382  "geometry");
383  return;
384  }
385 
386  for (int j = 0; j < groups[best_candidate_idx].size(); ++j) {
387  centers_cloud->push_back(
388  candidates_cloud->at(groups[best_candidate_idx][j]));
389  }
390 
391  // Add centers to cumulative for further clustering
392  for (int i = 0; i < centers_cloud->size(); i++) {
393  cumulative_cloud->push_back(centers_cloud->at(i));
394  }
395  frames_used_++;
396  if (DEBUG){
397  ROS_INFO("[Mono] %d/%d frames: %ld pts in cloud", frames_used_,
398  frames_proc_, cumulative_cloud->points.size());
399  }
400 
401  if (save_to_file_) {
402  std::vector<pcl::PointXYZ> sorted_centers;
403  sortPatternCenters(centers_cloud, sorted_centers);
404  for (std::vector<pcl::PointXYZ>::iterator it = sorted_centers.begin();
405  it < sorted_centers.end(); ++it) {
406  savefile << it->x << ", " << it->y << ", " << it->z << ", ";
407  }
408  }
409 
410  if (DEBUG) { // Draw centers
411  for (int i = 0; i < centers_cloud->size(); i++) {
412  cv::Point3f pt_circle1(centers_cloud->at(i).x, centers_cloud->at(i).y,
413  centers_cloud->at(i).z);
414  cv::Point2f uv_circle1;
415  uv_circle1 = projectPointDist(pt_circle1, cameraMatrix, distCoeffs);
416  circle(imageCopy, uv_circle1, 2, Scalar(255, 0, 255), -1);
417  }
418  }
419 
420  // Compute centers clusters
421  pcl::PointCloud<pcl::PointXYZ>::Ptr clusters_cloud(
422  new pcl::PointCloud<pcl::PointXYZ>);
423  if (!WARMUP_DONE) { // Compute clusters from detections in the latest frame
424  copyPointCloud(*centers_cloud, *clusters_cloud);
425  } else { // Use cumulative information from previous frames
427  min_cluster_factor_ * frames_used_, frames_used_);
428  if (clusters_cloud->points.size() > TARGET_NUM_CIRCLES) {
430  3.0 * frames_used_ / 4.0, frames_used_);
431  }
432  }
433 
434  // Publish pointcloud messages
435  if (DEBUG) {
436  sensor_msgs::PointCloud2 ros_pointcloud;
437  pcl::toROSMsg(*centers_cloud, ros_pointcloud); // circles_cloud
438  ros_pointcloud.header = msg->header;
439  qr_pub.publish(ros_pointcloud);
440  }
441 
442  if (clusters_cloud->points.size() == TARGET_NUM_CIRCLES) {
443  sensor_msgs::PointCloud2 centers_pointcloud;
444  pcl::toROSMsg(*clusters_cloud, centers_pointcloud);
445  centers_pointcloud.header = msg->header;
446  if (DEBUG) {
447  centers_cloud_pub.publish(centers_pointcloud);
448  }
449 
450  velo2cam_calibration::ClusterCentroids to_send;
451  to_send.header = msg->header;
452  to_send.cluster_iterations = frames_used_;
453  to_send.total_iterations = frames_proc_;
454  to_send.cloud = centers_pointcloud;
455  clusters_pub.publish(to_send);
456 
457  if (save_to_file_) {
458  std::vector<pcl::PointXYZ> sorted_centers;
459  sortPatternCenters(clusters_cloud, sorted_centers);
460  for (std::vector<pcl::PointXYZ>::iterator it = sorted_centers.begin();
461  it < sorted_centers.end(); ++it) {
462  savefile << it->x << ", " << it->y << ", " << it->z << ", ";
463  }
464  savefile << cumulative_cloud->width;
465  }
466  }
467 
468  if (DEBUG) {
469  sensor_msgs::PointCloud2 cumulative_pointcloud;
470  pcl::toROSMsg(*cumulative_cloud, cumulative_pointcloud);
471  cumulative_pointcloud.header = msg->header;
472  cumulative_pub.publish(cumulative_pointcloud);
473  }
474 
475  if (save_to_file_) {
476  savefile << endl;
477  }
478  } else { // Markers found != TARGET_NUM_CIRCLES
479  ROS_WARN("%lu marker(s) found, %d expected. Skipping frame...", ids.size(),
481  }
482 
483  if (DEBUG) {
484  cv::namedWindow("out", WINDOW_NORMAL);
485  cv::imshow("out", imageCopy);
486  cv::waitKey(1);
487  }
488 
489  // Clear cumulative cloud during warm-up phase
490  if (!WARMUP_DONE) {
491  cumulative_cloud->clear();
492  frames_proc_ = 0;
493  frames_used_ = 0;
494  }
495 }
496 
497 void param_callback(velo2cam_calibration::MonocularConfig &config,
498  uint32_t level) {
499  marker_size_ = config.marker_size;
500  ROS_INFO("New marker_size_: %f", marker_size_);
501  delta_width_qr_center_ = config.delta_width_qr_center;
502  ROS_INFO("New delta_width_qr_center_: %f", delta_width_qr_center_);
503  delta_height_qr_center_ = config.delta_height_qr_center;
504  ROS_INFO("New delta_height_qr_center_: %f", delta_height_qr_center_);
505 }
506 
507 void warmup_callback(const std_msgs::Empty::ConstPtr &msg) {
509  if (WARMUP_DONE) {
510  ROS_INFO("Warm up done, pattern detection started");
511  } else {
512  ROS_INFO("Detection stopped. Warm up mode activated");
513  }
514 }
515 
516 int main(int argc, char **argv) {
517  ros::init(argc, argv, "mono_qr_pattern");
518  ros::NodeHandle nh;
519  ros::NodeHandle nh_("~");
520 
521  // Initialize QR dictionary
522  dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);
523 
525  pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
526 
527  if (DEBUG) {
528  qr_pub = nh_.advertise<sensor_msgs::PointCloud2>("qr_cloud", 1);
529  centers_cloud_pub =
530  nh_.advertise<sensor_msgs::PointCloud2>("centers_pts_cloud", 1);
531  cumulative_pub =
532  nh_.advertise<sensor_msgs::PointCloud2>("cumulative_cloud", 1);
533  }
534  clusters_pub =
535  nh_.advertise<velo2cam_calibration::ClusterCentroids>("centers_cloud", 1);
536 
537  string csv_name;
538 
539  nh.param("delta_width_circles", delta_width_circles_, 0.5);
540  nh.param("delta_height_circles", delta_height_circles_, 0.4);
541  nh_.param("marker_size", marker_size_, 0.20);
542  nh_.param("delta_width_qr_center_", delta_width_qr_center_, 0.55);
543  nh_.param("delta_height_qr_center_", delta_height_qr_center_, 0.35);
544  nh_.param("min_detected_markers", min_detected_markers_, 3);
545  nh_.param("cluster_tolerance", cluster_tolerance_, 0.05);
546  nh_.param("min_cluster_factor", min_cluster_factor_, 2.0 / 3.0);
547  nh_.param("skip_warmup", skip_warmup_, false);
548  nh_.param("save_to_file", save_to_file_, false);
549  nh_.param("csv_name", csv_name, "mono_pattern_" + currentDateTime() + ".csv");
550 
551  string image_topic, cinfo_topic;
552  nh_.param<string>("image_topic", image_topic,
553  "/stereo_camera/left/image_rect_color");
554  nh_.param<string>("cinfo_topic", cinfo_topic,
555  "/stereo_camera/left/camera_info");
556 
557  message_filters::Subscriber<sensor_msgs::Image> image_sub(nh_, image_topic,
558  1);
560  nh_, cinfo_topic, 1);
561 
563  sync(image_sub, cinfo_sub, 10);
564  sync.registerCallback(boost::bind(&imageCallback, _1, _2));
565 
566  // ROS param callback
567  dynamic_reconfigure::Server<velo2cam_calibration::MonocularConfig> server;
568  dynamic_reconfigure::Server<
569  velo2cam_calibration::MonocularConfig>::CallbackType f;
570  f = boost::bind(param_callback, _1, _2);
571  server.setCallback(f);
572 
573  ros::Subscriber warmup_sub =
574  nh.subscribe("warmup_switch", 1, warmup_callback);
575 
576  if (skip_warmup_) {
577  ROS_WARN("Skipping warmup");
578  WARMUP_DONE = true;
579  }
580 
581  // Just for statistics
582  if (save_to_file_) {
583  ostringstream os;
584  os << getenv("HOME") << "/v2c_experiments/" << csv_name;
585  if (save_to_file_) {
586  if (DEBUG) ROS_INFO("Opening %s", os.str().c_str());
587  savefile.open(os.str().c_str());
588  savefile << "det1_x, det1_y, det1_z, det2_x, det2_y, det2_z, det3_x, "
589  "det3_y, det3_z, det4_x, det4_y, det4_z, cent1_x, cent1_y, "
590  "cent1_z, cent2_x, cent2_y, cent2_z, cent3_x, cent3_y, "
591  "cent3_z, cent4_x, cent4_y, cent4_z, it"
592  << endl;
593  }
594  }
595 
596  ros::spin();
597  cv::destroyAllWindows();
598  return 0;
599 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
double cluster_tolerance_
bool skip_warmup_
bool save_to_file_
double delta_width_qr_center_
cv::Ptr< cv::aruco::Dictionary > dictionary
void param_callback(velo2cam_calibration::MonocularConfig &config, uint32_t level)
f
int frames_proc_
double delta_height_qr_center_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool is_valid()
#define TARGET_NUM_CIRCLES
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void imageCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &left_info)
ros::NodeHandle * nh_
#define ROS_WARN(...)
int main(int argc, char **argv)
#define DEBUG
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
void warmup_callback(const std_msgs::Empty::ConstPtr &msg)
Connection registerCallback(C &callback)
double delta_width_circles_
Eigen::Matrix3f covariance(pcl::PointCloud< pcl::PointXYZ >::Ptr cumulative_cloud, Eigen::Vector3f means)
#define ROS_INFO(...)
double min_cluster_factor_
bool WARMUP_DONE
Eigen::Vector3f mean(pcl::PointCloud< pcl::PointXYZ >::Ptr cumulative_cloud)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int min_detected_markers_
ROSCPP_DECL void spin()
void getCenterClusters(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_in, pcl::PointCloud< pcl::PointXYZ >::Ptr centers_cloud, double cluster_tolerance=0.10, int min_cluster_size=15, int max_cluster_size=200, bool verbosity=true)
ros::Publisher centers_cloud_pub
Point2f projectPointDist(cv::Point3f pt_cv, const Mat intrinsics, const Mat distCoeffs)
void sortPatternCenters(pcl::PointCloud< pcl::PointXYZ >::Ptr pc, vector< pcl::PointXYZ > &v)
int frames_used_
ros::Publisher cumulative_pub
ros::Publisher qr_pub
const std::string currentDateTime()
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
double delta_height_circles_
ros::Publisher clusters_pub
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
pcl::PointCloud< pcl::PointXYZ >::Ptr cumulative_cloud
#define ROS_ERROR(...)
std::ofstream savefile
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double marker_size_
void comb(int N, int K, std::vector< std::vector< int >> &groups)


velo2cam_calibration
Author(s): Jorge Beltran , Carlos Guindel
autogenerated on Wed Mar 16 2022 02:33:29