28 #include <dynamic_reconfigure/server.h> 
   32 #include <pcl/point_cloud.h> 
   33 #include <pcl/point_types.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> 
   44 #include <opencv2/aruco.hpp> 
   45 #include <opencv2/opencv.hpp> 
   69                          const Mat distCoeffs) {
 
   71   vector<Point3f> input{pt_cv};
 
   72   vector<Point2f> projectedPoints;
 
   73   projectedPoints.resize(
 
   75   projectPoints(input, Mat::zeros(3, 1, CV_64FC1), Mat::zeros(3, 1, CV_64FC1),
 
   76                 intrinsics, distCoeffs, projectedPoints);
 
   77   return projectedPoints[0];
 
   81   double x = 0, y = 0, z = 0;
 
   83   for (pcl::PointCloud<pcl::PointXYZ>::iterator pt =
 
   85        pt < cumulative_cloud->points.end(); pt++) {
 
   86     x += (pt->x) / npoints;
 
   87     y += (pt->y) / npoints;
 
   88     z += (pt->z) / npoints;
 
   90   return Eigen::Vector3f(x, y, z);
 
   94                            Eigen::Vector3f means) {
 
   95   double x = 0, y = 0, z = 0;
 
   97   vector<Eigen::Vector3f> points;
 
   99   for (pcl::PointCloud<pcl::PointXYZ>::iterator pt =
 
  101        pt < cumulative_cloud->points.end(); pt++) {
 
  102     Eigen::Vector3f p(pt->x, pt->y, pt->z);
 
  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]);
 
  114       covarianceMatrix(i, j) /= npoints - 1;
 
  116   return covarianceMatrix;
 
  120                    const sensor_msgs::CameraInfoConstPtr &left_info) {
 
  127     ROS_ERROR(
"cv_bridge exception: %s", e.what());
 
  130   cv::Mat image = cv_img_ptr->image;
 
  132   image.copyTo(imageCopy);
 
  133   sensor_msgs::CameraInfoPtr cinfo(
new sensor_msgs::CameraInfo(*left_info));
 
  137   Mat cameraMatrix(3, 3, CV_32F);
 
  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];
 
  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];
 
  169   std::vector<std::vector<cv::Point3f>> boardCorners;
 
  171   vector<cv::Point3f> boardCircleCenters;
 
  176   boardCorners.resize(4);
 
  177   for (
int i = 0; i < 4; ++i) {
 
  179         (i % 3) == 0 ? -1 : 1;  
 
  184     float x_center = x_qr_center * width;
 
  185     float y_center = y_qr_center * height;
 
  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;  
 
  193       int y_qr = (j < 2) ? 1 : -1;  
 
  197       boardCorners[i].push_back(pt3d);
 
  201   std::vector<int> boardIds{1, 2, 4, 3};  
 
  202   cv::Ptr<cv::aruco::Board> board =
 
  203       cv::aruco::Board::create(boardCorners, 
dictionary, boardIds);
 
  205   cv::Ptr<cv::aruco::DetectorParameters> parameters =
 
  206       cv::aruco::DetectorParameters::create();
 
  210 #if (CV_MAJOR_VERSION == 3 && CV_MINOR_VERSION <= 2) || CV_MAJOR_VERSION < 3 
  211   parameters->doCornerRefinement = 
true;
 
  213   parameters->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
 
  217   std::vector<int> ids;
 
  218   std::vector<std::vector<cv::Point2f>> corners;
 
  219   cv::aruco::detectMarkers(image, 
dictionary, corners, ids, parameters);
 
  222   if (ids.size() > 0) cv::aruco::drawDetectedMarkers(imageCopy, corners, ids);
 
  224   cv::Vec3d rvec(0, 0, 0), tvec(0, 0, 0);  
 
  229     vector<Vec3d> rvecs, tvecs;
 
  230     Vec3f rvec_sin, rvec_cos;
 
  231     cv::aruco::estimatePoseSingleMarkers(corners, 
marker_size_, cameraMatrix,
 
  232                                          distCoeffs, rvecs, tvecs);
 
  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];
 
  240       cv::Point3f pt_cv(x, y, z);
 
  244       cv::aruco::drawAxis(imageCopy, cameraMatrix, distCoeffs, rvecs[i],
 
  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]);
 
  260     tvec = tvec / int(ids.size());
 
  261     rvec_sin = rvec_sin / int(ids.size());  
 
  262     rvec_cos = rvec_cos / int(ids.size());  
 
  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]);
 
  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>);
 
  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);
 
  277     int valid = cv::aruco::estimatePoseBoard(corners, ids, board, cameraMatrix,
 
  278                                              distCoeffs, rvec, tvec, 
true);
 
  281     cv::aruco::drawAxis(imageCopy, cameraMatrix, distCoeffs, rvec, tvec, 0.2);
 
  284     cv::Mat R(3, 3, cv::DataType<float>::type);
 
  285     cv::Rodrigues(rvec, R);
 
  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];
 
  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));
 
  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;
 
  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);
 
  314       circle(imageCopy, uv, 10, Scalar(0, 255, 0), -1);
 
  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);
 
  340     std::vector<std::vector<int>> groups;
 
  342     double groups_scores[groups.size()];  
 
  343     for (
int i = 0; i < groups.size(); ++i) {
 
  344       std::vector<pcl::PointXYZ> candidates;
 
  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);
 
  357       groups_scores[i] = square_candidate.
is_valid()
 
  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) {
 
  368             "[Mono] More than one set of candidates fit target's geometry. " 
  369             "Please, make sure your parameters are well set. Exiting callback");
 
  372       if (groups_scores[i] > best_candidate_score) {
 
  373         best_candidate_score = groups_scores[i];
 
  374         best_candidate_idx = i;
 
  378     if (best_candidate_idx == -1) {
 
  381           "[Mono] Unable to find a candidate set that matches target's " 
  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]));
 
  392     for (
int i = 0; i < centers_cloud->size(); i++) {
 
  402       std::vector<pcl::PointXYZ> 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 << 
", ";
 
  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;
 
  416         circle(imageCopy, uv_circle1, 2, Scalar(255, 0, 255), -1);
 
  421     pcl::PointCloud<pcl::PointXYZ>::Ptr clusters_cloud(
 
  422         new pcl::PointCloud<pcl::PointXYZ>);
 
  424       copyPointCloud(*centers_cloud, *clusters_cloud);
 
  436       sensor_msgs::PointCloud2 ros_pointcloud;
 
  438       ros_pointcloud.header = msg->header;
 
  443       sensor_msgs::PointCloud2 centers_pointcloud;
 
  445       centers_pointcloud.header = msg->header;
 
  450       velo2cam_calibration::ClusterCentroids to_send;
 
  451       to_send.header = msg->header;
 
  454       to_send.cloud = centers_pointcloud;
 
  458         std::vector<pcl::PointXYZ> 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 << 
", ";
 
  469       sensor_msgs::PointCloud2 cumulative_pointcloud;
 
  471       cumulative_pointcloud.header = msg->header;
 
  479     ROS_WARN(
"%lu marker(s) found, %d expected. Skipping frame...", ids.size(),
 
  484     cv::namedWindow(
"out", WINDOW_NORMAL);
 
  485     cv::imshow(
"out", imageCopy);
 
  510     ROS_INFO(
"Warm up done, pattern detection started");
 
  512     ROS_INFO(
"Detection stopped. Warm up mode activated");
 
  516 int main(
int argc, 
char **argv) {
 
  517   ros::init(argc, argv, 
"mono_qr_pattern");
 
  522   dictionary = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);
 
  525       pcl::PointCloud<pcl::PointXYZ>::Ptr(
new pcl::PointCloud<pcl::PointXYZ>);
 
  530         nh_.
advertise<sensor_msgs::PointCloud2>(
"centers_pts_cloud", 1);
 
  532         nh_.
advertise<sensor_msgs::PointCloud2>(
"cumulative_cloud", 1);
 
  535       nh_.
advertise<velo2cam_calibration::ClusterCentroids>(
"centers_cloud", 1);
 
  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");
 
  560       nh_, cinfo_topic, 1);
 
  563       sync(image_sub, cinfo_sub, 10);
 
  567   dynamic_reconfigure::Server<velo2cam_calibration::MonocularConfig> server;
 
  568   dynamic_reconfigure::Server<
 
  569       velo2cam_calibration::MonocularConfig>::CallbackType 
f;
 
  571   server.setCallback(
f);
 
  584     os << getenv(
"HOME") << 
"/v2c_experiments/" << csv_name;
 
  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" 
  597   cv::destroyAllWindows();