26 #define PCL_NO_PRECOMPILE 
   28 #include <pcl/registration/transformation_estimation_svd.h> 
   33 #include <std_msgs/Empty.h> 
   34 #include <std_msgs/Int32.h> 
   39 #include <velo2cam_calibration/ClusterCentroids.h> 
   70 std::vector<std::vector<std::tuple<int, int, pcl::PointCloud<pcl::PointXYZ>,
 
   71                                    std::vector<pcl::PointXYZ>>>>
 
   73 std::vector<std::vector<std::tuple<int, int, pcl::PointCloud<pcl::PointXYZ>,
 
   74                                    std::vector<pcl::PointXYZ>>>>
 
   93     const velo2cam_calibration::ClusterCentroids::ConstPtr sensor1_centroids);
 
   95     velo2cam_calibration::ClusterCentroids::ConstPtr sensor2_centroids);
 
  102   std::vector<pcl::PointXYZ> local_sensor1_vector, local_sensor2_vector;
 
  103   pcl::PointCloud<pcl::PointXYZ>::Ptr local_sensor1_cloud(
 
  104       new pcl::PointCloud<pcl::PointXYZ>),
 
  105       local_sensor2_cloud(
new pcl::PointCloud<pcl::PointXYZ>);
 
  106   pcl::PointCloud<pcl::PointXYZ> local_l_cloud, local_c_cloud;
 
  108   int used_sensor2, used_sensor1;
 
  120   int total_sensor1, total_sensor2;
 
  128         ROS_INFO(
"Target position: %d, Last sensor2: %d, last sensor1: %d",
 
  132       auto it1 = std::find_if(
 
  135               const std::tuple<
int, 
int, pcl::PointCloud<pcl::PointXYZ>,
 
  136                                std::vector<pcl::PointXYZ>> &e) {
 
  137             return std::get<0>(e) == seek_iter;
 
  144       local_sensor1_vector.insert(
 
  145           local_sensor1_vector.end(), std::get<3>(*it1).begin(),
 
  146           std::get<3>(*it1).end());  
 
  147       *local_sensor1_cloud +=
 
  149       used_sensor1 = std::get<1>(*it1);
 
  150       total_sensor1 = std::get<0>(*it1);
 
  153       auto it2 = std::find_if(
 
  156               const std::tuple<
int, 
int, pcl::PointCloud<pcl::PointXYZ>,
 
  157                                std::vector<pcl::PointXYZ>> &e) {
 
  158             return std::get<0>(e) == seek_iter;
 
  165       local_sensor2_vector.insert(
 
  166           local_sensor2_vector.end(), std::get<3>(*it2).begin(),
 
  167           std::get<3>(*it2).end());  
 
  168       *local_sensor2_cloud +=
 
  170       used_sensor2 = std::get<1>(*it2);
 
  171       total_sensor2 = std::get<0>(*it2);
 
  173     ROS_INFO(
"Synchronizing cluster centroids");
 
  178       local_sensor1_vector.insert(
 
  179           local_sensor1_vector.end(),
 
  183       *local_sensor1_cloud += std::get<2>(
 
  188       local_sensor2_vector.insert(
 
  189           local_sensor2_vector.end(),
 
  193       *local_sensor2_cloud += std::get<2>(
 
  199     sensor_msgs::PointCloud2 ros_cloud;
 
  210   pcl::PointCloud<pcl::PointXYZ>::Ptr sorted_centers1(
 
  211       new pcl::PointCloud<pcl::PointXYZ>());
 
  212   pcl::PointCloud<pcl::PointXYZ>::Ptr sorted_centers2(
 
  213       new pcl::PointCloud<pcl::PointXYZ>());
 
  215   for (
int i = 0; i < local_sensor1_vector.size(); ++i) {
 
  216     sorted_centers1->push_back(local_sensor1_vector[i]);
 
  217     sorted_centers2->push_back(local_sensor2_vector[i]);
 
  220   Eigen::Matrix4f final_transformation;
 
  221   const pcl::registration::TransformationEstimationSVD<pcl::PointXYZ,
 
  224   trans_est_svd.estimateRigidTransformation(*sorted_centers1, *sorted_centers2,
 
  225                                             final_transformation);
 
  228   tf3d.
setValue(final_transformation(0, 0), final_transformation(0, 1),
 
  229                 final_transformation(0, 2), final_transformation(1, 0),
 
  230                 final_transformation(1, 1), final_transformation(1, 2),
 
  231                 final_transformation(2, 0), final_transformation(2, 1),
 
  232                 final_transformation(2, 2));
 
  238   origin.setValue(final_transformation(0, 3), final_transformation(1, 3),
 
  239                   final_transformation(2, 3));
 
  246                                             sensor1_final_transformation_frame,
 
  247                                             sensor2_final_transformation_frame);
 
  251   double roll, pitch, yaw;
 
  252   double xt = 
inverse.getOrigin().getX(), yt = 
inverse.getOrigin().getY(),
 
  253          zt = 
inverse.getOrigin().getZ();
 
  254   inverse.getBasis().getRPY(roll, pitch, yaw);
 
  257     savefile << seek_iter << 
", " << xt << 
", " << yt << 
", " << zt << 
", " 
  258              << roll << 
", " << pitch << 
", " << yaw << 
", " << used_sensor1
 
  259              << 
", " << used_sensor2 << 
", " << total_sensor1 << 
", " 
  260              << total_sensor2 << endl;
 
  263   cout << setprecision(4) << std::fixed;
 
  264   cout << 
"Calibration finished succesfully." << endl;
 
  265   cout << 
"Extrinsic parameters:" << endl;
 
  266   cout << 
"x = " << xt << 
"\ty = " << yt << 
"\tz = " << zt << endl;
 
  267   cout << 
"roll = " << roll << 
"\tpitch = " << pitch << 
"\tyaw = " << yaw << endl;
 
  274     const velo2cam_calibration::ClusterCentroids::ConstPtr sensor1_centroids) {
 
  279          << 
"/10" << 
'\r' << flush;
 
  287            << 
" received. Is the warmup done? [Y/n]" << endl;
 
  289       getline(cin, answer);
 
  290       if (answer == 
"y" || answer == 
"Y" || answer == 
"") {
 
  294           cout << 
"Filters for sensor 1 are adjusted now. Please, proceed with " 
  298           cout << 
"Warmup phase completed. Starting calibration phase." << endl;
 
  299           std_msgs::Empty myMsg;
 
  325     std::ostringstream sstream;
 
  329     pcl::PointCloud<pcl::PointXYZ>::Ptr xy_sensor1_cloud(
 
  330         new pcl::PointCloud<pcl::PointXYZ>());
 
  332     fromROSMsg(sensor1_centroids->cloud, *xy_sensor1_cloud);
 
  342       ROS_WARN(
"TF exception:\n%s", ex.what());
 
  347     double roll, pitch, yaw;
 
  348     inverse.getBasis().getRPY(roll, pitch, yaw);
 
  361     sensor_msgs::PointCloud2 colour_cloud;
 
  363     colour_cloud.header.frame_id =
 
  369       std::tuple<
int, 
int, pcl::PointCloud<pcl::PointXYZ>,
 
  370                  std::vector<pcl::PointXYZ>>(
 
  371           sensor1_centroids->total_iterations,
 
  382            << 
"[" << (*it).x << 
" " << (*it).y << 
" " << (*it).z << 
"]" << endl;
 
  419         cout << 
"Target iterations reached. Do you need another target " 
  422         getline(cin, answer);
 
  424       if (answer == 
"n" || answer == 
"N" || answer == 
"") {
 
  430         cout << 
"Please, move the target to its new position and adjust the " 
  431                 "filters for each sensor before the calibration starts." 
  434         std_msgs::Empty myMsg;
 
  462     velo2cam_calibration::ClusterCentroids::ConstPtr sensor2_centroids) {
 
  467          << 
"/10" << 
'\r' << flush;
 
  475            << 
" received. Is the warmup done? (you can also reset this " 
  479       getline(cin, answer);
 
  480       if (answer == 
"y" || answer == 
"Y" || answer == 
"") {
 
  484           cout << 
"Filters for sensor 2 are adjusted now. Please, proceed with " 
  488           cout << 
"Warmup phase completed. Starting calibration phase." << endl;
 
  489           std_msgs::Empty myMsg;
 
  492       } 
else if (answer == 
"r" ||
 
  503         cout << 
"Please, adjust the filters for each sensor before the " 
  504                 "calibration starts." 
  525     std::ostringstream sstream;
 
  529     pcl::PointCloud<pcl::PointXYZ>::Ptr xy_sensor2_cloud(
 
  530         new pcl::PointCloud<pcl::PointXYZ>());
 
  532     fromROSMsg(sensor2_centroids->cloud, *xy_sensor2_cloud);
 
  542       ROS_WARN(
"TF exception:\n%s", ex.what());
 
  547     double roll, pitch, yaw;
 
  548     inverse.getBasis().getRPY(roll, pitch, yaw);
 
  562     sensor_msgs::PointCloud2 colour_cloud;
 
  564     colour_cloud.header.frame_id =
 
  570       std::tuple<
int, 
int, pcl::PointCloud<pcl::PointXYZ>,
 
  571                  std::vector<pcl::PointXYZ>>(
 
  572           sensor2_centroids->total_iterations,
 
  583            << 
"[" << (*it).x << 
" " << (*it).y << 
" " << (*it).z << 
"]" << endl;
 
  620         cout << 
"Target iterations reached. Do you need another target " 
  623         getline(cin, answer);
 
  625       if (answer == 
"n" || answer == 
"N" || answer == 
"") {
 
  631         cout << 
"Please, move the target to its new position and adjust the " 
  632                 "filters for each sensor before the calibration starts." 
  635         std_msgs::Empty myMsg;
 
  662 int main(
int argc, 
char **argv) {
 
  663   ros::init(argc, argv, 
"velo2cam_calibration");
 
  677   nh_->
param<
string>(
"csv_name", csv_name,
 
  682       pcl::PointCloud<pcl::PointXYZ>::Ptr(
new pcl::PointCloud<pcl::PointXYZ>);
 
  684       pcl::PointCloud<pcl::PointXYZI>::Ptr(
new pcl::PointCloud<pcl::PointXYZI>);
 
  687       pcl::PointCloud<pcl::PointXYZ>::Ptr(
new pcl::PointCloud<pcl::PointXYZ>);
 
  689       pcl::PointCloud<pcl::PointXYZI>::Ptr(
new pcl::PointCloud<pcl::PointXYZI>);
 
  698         nh_->
advertise<sensor_msgs::PointCloud2>(
"clusters_sensor2", 1);
 
  700         nh_->
advertise<sensor_msgs::PointCloud2>(
"clusters_sensor1", 1);
 
  703         nh_->
advertise<sensor_msgs::PointCloud2>(
"colour_sensor2", 1);
 
  705         nh_->
advertise<sensor_msgs::PointCloud2>(
"colour_sensor1", 1);
 
  715     os << getenv(
"HOME") << 
"/v2c_experiments/" << csv_name;
 
  719       savefile << 
"it, x, y, z, r, p, y, used_sen1, used_sen2, total_sen1, " 
  730     cout << 
"Please, adjust the filters for each sensor before the calibration " 
  753   timeinfo = localtime(&rawtime);
 
  755   strftime(buffer, 80, 
"%Y-%m-%d-%H-%M-%S", timeinfo);
 
  756   std::string str(buffer);
 
  760   double roll, pitch, yaw;
 
  761   double xt = 
inverse.getOrigin().getX(), yt = 
inverse.getOrigin().getY(),
 
  762          zt = 
inverse.getOrigin().getZ();
 
  763   inverse.getBasis().getRPY(roll, pitch, yaw);
 
  766   string backuppath = path + 
"/launch/calibrated_tf_" + str + 
".launch";
 
  767   path = path + 
"/launch/calibrated_tf.launch";
 
  770        << 
"Creating .launch file with calibrated TF in: " << endl
 
  771        << path.c_str() << endl;
 
  774   TiXmlDeclaration *decl = 
new TiXmlDeclaration(
"1.0", 
"utf-8", 
"");
 
  775   doc.LinkEndChild(decl);
 
  776   TiXmlElement *root = 
new TiXmlElement(
"launch");
 
  777   doc.LinkEndChild(root);
 
  779   TiXmlElement *arg = 
new TiXmlElement(
"arg");
 
  780   arg->SetAttribute(
"name", 
"stdout");
 
  781   arg->SetAttribute(
"default", 
"screen");
 
  782   root->LinkEndChild(arg);
 
  787     std::ostringstream sensor2_rot_stream_pub;
 
  788     sensor2_rot_stream_pub << 
"0 0 0 -1.57079632679 0 -1.57079632679 " 
  791     string sensor2_rotation = sensor2_rot_stream_pub.str();
 
  793     TiXmlElement *sensor2_rotation_node = 
new TiXmlElement(
"node");
 
  794     sensor2_rotation_node->SetAttribute(
"pkg", 
"tf");
 
  795     sensor2_rotation_node->SetAttribute(
"type", 
"static_transform_publisher");
 
  796     sensor2_rotation_node->SetAttribute(
"name", 
"sensor2_rot_tf");
 
  797     sensor2_rotation_node->SetAttribute(
"args", sensor2_rotation);
 
  798     root->LinkEndChild(sensor2_rotation_node);
 
  804     std::ostringstream sensor1_rot_stream_pub;
 
  805     sensor1_rot_stream_pub << 
"0 0 0 -1.57079632679 0 -1.57079632679 " 
  808     string sensor1_rotation = sensor1_rot_stream_pub.str();
 
  810     TiXmlElement *sensor1_rotation_node = 
new TiXmlElement(
"node");
 
  811     sensor1_rotation_node->SetAttribute(
"pkg", 
"tf");
 
  812     sensor1_rotation_node->SetAttribute(
"type", 
"static_transform_publisher");
 
  813     sensor1_rotation_node->SetAttribute(
"name", 
"sensor1_rot_tf");
 
  814     sensor1_rotation_node->SetAttribute(
"args", sensor1_rotation);
 
  815     root->LinkEndChild(sensor1_rotation_node);
 
  818   std::ostringstream sstream;
 
  819   sstream << xt << 
" " << yt << 
" " << zt << 
" " << yaw << 
" " << pitch << 
" " 
  820           << roll << 
" " << sensor2_final_transformation_frame << 
" " 
  821           << sensor1_final_transformation_frame << 
" 100";
 
  822   string tf_args = sstream.str();
 
  824   TiXmlElement *node = 
new TiXmlElement(
"node");
 
  825   node->SetAttribute(
"pkg", 
"tf");
 
  826   node->SetAttribute(
"type", 
"static_transform_publisher");
 
  827   node->SetAttribute(
"name", 
"velo2cam_tf");
 
  828   node->SetAttribute(
"args", tf_args);
 
  829   root->LinkEndChild(node);
 
  833   doc.SaveFile(backuppath);
 
  835   if (
DEBUG) cout << 
"Calibration process finished." << endl;