35 #define BOOST_PARAMETER_MAX_ARITY 7 
   40 #include <boost/filesystem.hpp> 
   41 #include <boost/format.hpp> 
   42 #include <pcl/recognition/color_gradient_modality.h> 
   43 #include <pcl/recognition/surface_normal_modality.h> 
   44 #include <pcl/filters/extract_indices.h> 
   45 #include <pcl/io/pcd_io.h> 
   46 #include <jsk_topic_tools/rosparam_utils.h> 
   48 #include <boost/algorithm/string/predicate.hpp> 
   49 #include <pcl/common/transforms.h> 
   50 #include <pcl/range_image/range_image_planar.h> 
   54 #include <pcl/kdtree/kdtree_flann.h> 
   55 #include <yaml-cpp/yaml.h> 
   56 #include <pcl/common/common.h> 
   60 #if ( CV_MAJOR_VERSION >= 4) 
   61 #include <opencv2/imgproc/imgproc_c.h> 
   87       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
  101         "output/range_image", 1);
 
  103           "output/colored_range_image", 1);
 
  105         "output/sample_cloud", 1);
 
  108       = 
pnh_->advertiseService(
 
  112       = 
pnh_->advertiseService(
 
  129     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
  130     const PCLIndicesMsg::ConstPtr& indices_msg)
 
  133     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr 
cloud 
  134       (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  136     pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
 
  144     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
 
  147     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr 
cloud 
  148       (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  155     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
 
  162     std_srvs::Empty::Request& 
req,
 
  163     std_srvs::Empty::Response& 
res)
 
  173     const Eigen::Affine3f& transform,
 
  174     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud,
 
  176     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr colored_cloud,
 
  177     pcl::PointIndices& mask)
 
  181     double fx = 
model.fx();
 
  182     double fy = 
model.fy();
 
  183     double cx = 
model.cx();
 
  184     double cy = 
model.cy();
 
  185     Eigen::Affine3f viewpoint_transform = 
transform;
 
  186     Eigen::Affine3f object_transform = viewpoint_transform.inverse();
 
  187     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr 
cloud 
  188       (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  189     pcl::transformPointCloud<pcl::PointXYZRGBA>(
 
  190       *raw_cloud, *
cloud, object_transform);
 
  191     pcl::RangeImagePlanar range_image;
 
  192     Eigen::Affine3f dummytrans;
 
  193     dummytrans.setIdentity();
 
  194     range_image.createFromPointCloudWithFixedSize(
 
  196       cx, cy, fx, fy, dummytrans);
 
  197     cv::Mat mat(range_image.height, range_image.width, CV_32FC1);
 
  198     float *tmpf = (
float *)mat.ptr();
 
  199     for(
unsigned int i = 0; 
i < range_image.height * range_image.width; 
i++) {
 
  200       tmpf[
i] = range_image.points[
i].z;
 
  202     std_msgs::Header dummy_header;
 
  209     pcl::KdTreeFLANN<pcl::PointXYZRGBA>::Ptr
 
  210       kdtree (
new pcl::KdTreeFLANN<pcl::PointXYZRGBA>);
 
  211     kdtree->setInputCloud(
cloud);
 
  213     colored_cloud->width = range_image.width;
 
  214     colored_cloud->height = range_image.height;
 
  215     colored_cloud->is_dense = range_image.is_dense;
 
  216     pcl::PointXYZRGBA nan_point;
 
  217     nan_point.x = nan_point.y = nan_point.z
 
  218       = std::numeric_limits<float>::quiet_NaN();
 
  219     pcl::PointIndices::Ptr mask_indices (
new pcl::PointIndices);
 
  220     colored_cloud->points.resize(range_image.points.size());
 
  222     cv::Mat colored_image = cv::Mat::zeros(
 
  223       range_image.height, range_image.width, CV_8UC3);
 
  224     for (
size_t pi = 0; pi < range_image.points.size(); pi++) {
 
  225       if (std::isnan(range_image.points[pi].x) ||
 
  226           std::isnan(range_image.points[pi].y) ||
 
  227           std::isnan(range_image.points[pi].z)) {
 
  229         colored_cloud->points[pi] = nan_point;
 
  232         pcl::PointXYZRGBA input_point;
 
  233         input_point.x = range_image.points[pi].x;
 
  234         input_point.y = range_image.points[pi].y;
 
  235         input_point.z = range_image.points[pi].z;
 
  236         std::vector<int> indices;
 
  237         std::vector<float> distances;
 
  238         kdtree->nearestKSearch(input_point, 1, indices, distances);
 
  239         if (indices.size() > 0) {
 
  240           input_point.rgba = 
cloud->points[indices[0]].rgba;
 
  242         colored_image.at<cv::Vec3b>(pi / range_image.width,
 
  243                                     pi % range_image.width)
 
  244           = cv::Vec3b(
cloud->points[indices[0]].r,
 
  245                       cloud->points[indices[0]].g,
 
  246                       cloud->points[indices[0]].b);
 
  247         colored_cloud->points[pi] = input_point;
 
  250     for (
size_t pi = 0; pi < range_image.points.size(); pi++) {
 
  251       if (!std::isnan(range_image.points[pi].x) &&
 
  252           !std::isnan(range_image.points[pi].y) &&
 
  253           !std::isnan(range_image.points[pi].z)) {
 
  255         mask.indices.push_back(pi);
 
  263     sensor_msgs::PointCloud2 ros_sample_cloud;
 
  265     pcl::PointCloud<pcl::PointXYZRGB> rgb_cloud;
 
  268     ros_sample_cloud.header = dummy_header;
 
  280       NODELET_FATAL(
"we expect only one training pointcloud, but it has %lu pointclouds",
 
  299     std::vector<Eigen::Affine3f> transforms;
 
  313     pcl::RangeImagePlanar dummy_range_image;
 
  315     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud
 
  319     std::vector<pcl::ColorGradientModality<pcl::PointXYZRGBA> >
 
  321     std::vector<pcl::SurfaceNormalModality<pcl::PointXYZRGBA> >
 
  322       surface_norm_modalities (sampler.
sampleNum());
 
  323     std::vector<pcl::MaskMap> mask_maps (sampler.
sampleNum());
 
  324     std::vector<pcl::RegionXY> regions (sampler.
sampleNum());
 
  326     pcl::LINEMOD linemod;
 
  328     std::vector<Eigen::Affine3f> pose_in_order_of_training;
 
  330 #pragma omp parallel for 
  332     for (
size_t j = 0; j < sampler.
sampleNum(); j++) {
 
  334       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr 
cloud(
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  335       pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
 
  339       pcl::ColorGradientModality<pcl::PointXYZRGBA> color_modality;
 
  340       pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_norm_mod;
 
  341       pcl::MaskMap mask_map(
model.fullResolution().width,
 
  342                             model.fullResolution().height);
 
  343       pcl::RegionXY region;
 
  345                                   color_modality, surface_norm_mod,
 
  347       std::vector<pcl::QuantizableModality*> modalities(2);
 
  348       modalities[0] = &color_modality;
 
  349       modalities[1] = &surface_norm_mod;
 
  350       std::vector<pcl::MaskMap*> masks(2);
 
  351       masks[0] = &mask_map;
 
  352       masks[1] = &mask_map;
 
  354         boost::mutex::scoped_lock 
lock(train_mutex);
 
  357         linemod.createAndAddTemplate(modalities, masks, region);
 
  358         pose_in_order_of_training.push_back(transforms[j]);
 
  365     std::ofstream linemod_file;
 
  366     const std::string linemod_file_name = 
output_file_ + 
".linemod";
 
  367     NODELET_INFO(
"writing to %s", linemod_file_name.c_str());
 
  368     linemod_file.open(linemod_file_name.c_str(),
 
  369                       std::ofstream::out | std::ofstream::binary);
 
  370     linemod.serialize(linemod_file);
 
  371     linemod_file.close();
 
  372     const std::string pcd_file_name = 
output_file_ + 
".pcd";
 
  375     writer.writeBinaryCompressed(pcd_file_name, *raw_cloud);
 
  377     std::ofstream pose_file;
 
  378     const std::string pose_file_name = 
output_file_ + 
"_poses.yaml";
 
  380     pose_file.open(pose_file_name.c_str(), std::ofstream::out);
 
  381     pose_file << 
"template_poses: [" << std::endl;
 
  382     for (
size_t i = 0; 
i < pose_in_order_of_training.size(); 
i++) {
 
  383       Eigen::Affine3f 
pose = pose_in_order_of_training[
i];
 
  384       Eigen::Vector3f 
pos(
pose.translation());
 
  385       Eigen::Quaternionf 
rot(
pose.rotation());
 
  387                 << 
pos[0] << 
", " << 
pos[1] << 
", " << 
pos[2] << 
", " 
  388                 << 
rot.x() << 
", " << 
rot.y() << 
", " << 
rot.z() << 
", " << 
rot.w() << 
"]";
 
  389       if (
i != pose_in_order_of_training.size() - 1) {
 
  390         pose_file << 
", " << std::endl;
 
  393         pose_file << 
"]" << std::endl;
 
  401     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
 
  402     pcl::PointIndices::Ptr mask,
 
  403     pcl::ColorGradientModality<pcl::PointXYZRGBA>& color_grad_mod,
 
  404     pcl::SurfaceNormalModality<pcl::PointXYZRGBA>& surface_norm_mod,
 
  405     pcl::MaskMap& mask_map,
 
  406     pcl::RegionXY& region)
 
  408     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr masked_cloud
 
  409       (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  410     pcl::ExtractIndices<pcl::PointXYZRGBA> 
ex;
 
  411     ex.setKeepOrganized(
true);
 
  414     ex.filter(*masked_cloud);
 
  415     color_grad_mod.setInputCloud(masked_cloud);
 
  416     color_grad_mod.processInputData();
 
  417     surface_norm_mod.setInputCloud(
cloud);
 
  418     surface_norm_mod.processInputData();
 
  419     size_t min_x(masked_cloud->width), min_y(masked_cloud->height), max_x(0), max_y(0);
 
  420     for (
size_t j = 0; j < masked_cloud->height; ++j) {
 
  421       for (
size_t i = 0; 
i < masked_cloud->width; ++
i) {
 
  423           = masked_cloud->points[j * masked_cloud->width + 
i];
 
  424         if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
 
  427           max_x = std::max(max_x, 
i);
 
  429           max_y = std::max(max_y, j);
 
  436     region.x = 
static_cast<int>(min_x);
 
  437     region.y = 
static_cast<int>(min_y);
 
  438     region.width = 
static_cast<int>(max_x - min_x + 1);
 
  439     region.height = 
static_cast<int>(max_y - min_y + 1);
 
  444     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
 
  445     pcl::PointIndices::Ptr mask,
 
  446     std::string& tempstr,
 
  449     pcl::LINEMOD linemod;
 
  450     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr masked_cloud
 
  451       (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  452     pcl::ExtractIndices<pcl::PointXYZRGBA> 
ex;
 
  453     ex.setKeepOrganized(
true);
 
  456     ex.filter(*masked_cloud);
 
  457     pcl::ColorGradientModality<pcl::PointXYZRGBA> color_grad_mod;
 
  458     color_grad_mod.setInputCloud(masked_cloud);
 
  459     color_grad_mod.processInputData();
 
  460     pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_norm_mod;
 
  461     surface_norm_mod.setInputCloud(masked_cloud);
 
  462     surface_norm_mod.processInputData();
 
  463     std::vector<pcl::QuantizableModality*> modalities(2);
 
  464     modalities[0] = &color_grad_mod;
 
  465     modalities[1] = &surface_norm_mod;
 
  466     size_t min_x(masked_cloud->width), min_y(masked_cloud->height), max_x(0), max_y(0);
 
  467     pcl::MaskMap mask_map(masked_cloud->width, masked_cloud->height);
 
  468     for (
size_t j = 0; j < masked_cloud->height; ++j) {
 
  469       for (
size_t i = 0; 
i < masked_cloud->width; ++
i) {
 
  471           = masked_cloud->points[j * masked_cloud->width + 
i];
 
  472         if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
 
  475           max_x = std::max(max_x, 
i);
 
  477           max_y = std::max(max_y, j);
 
  484     std::vector<pcl::MaskMap*> masks(2);
 
  485     masks[0] = &mask_map;
 
  486     masks[1] = &mask_map;
 
  487     pcl::RegionXY region;
 
  488     region.x = 
static_cast<int>(min_x);
 
  489     region.y = 
static_cast<int>(min_y);
 
  490     region.width = 
static_cast<int>(max_x - min_x + 1);
 
  491     region.height = 
static_cast<int>(max_y - min_y + 1);
 
  492     linemod.createAndAddTemplate(modalities, masks, region);
 
  494     std::vector<std::string> ret;
 
  497       std::stringstream filename_stream;
 
  498       filename_stream << boost::format(
"%s/%05d_template.sqmmt") % tempstr % 
i;
 
  499       std::string 
filename = filename_stream.str();
 
  500       std::cerr << 
"writing " << 
filename << std::endl;
 
  501       std::ofstream file_stream;
 
  503                        std::ofstream::out | std::ofstream::binary);
 
  504       linemod.getTemplate(0).serialize(file_stream);
 
  510       std::stringstream filename_stream;
 
  511       filename_stream << boost::format(
"%s/%05d_template.pcd") % tempstr % 
i;
 
  512       std::string 
filename = filename_stream.str();
 
  513       std::cerr << 
"writing " << 
filename << std::endl;
 
  524     boost::filesystem::path temp = boost::filesystem::unique_path();
 
  525     boost::filesystem::create_directory(temp);
 
  526     std::string tempstr = temp.native();
 
  528     std::vector<std::string> all_files;
 
  544     std::stringstream command_stream;
 
  545     command_stream << 
"tar --format=ustar -cf " << output << 
" " << directory << 
"/*";
 
  546     NODELET_INFO(
"executing %s", command_stream.str().c_str());
 
  547     int ret = system(command_stream.str().c_str());
 
  551     std_srvs::Empty::Request& 
req,
 
  552     std_srvs::Empty::Response& 
res)
 
  566     DiagnosticNodelet::onInit();
 
  567     pnh_->param(
"template_file", 
template_file_, std::string(
"template"));
 
  575     std::ifstream pose_fin;
 
  576     pose_fin.open(pose_yaml.c_str(), std::ifstream::in);
 
  577     YAML::Parser 
parser(pose_fin);
 
  584     doc = YAML::LoadFile(pose_yaml);
 
  589     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
  590     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  593     srv_->setCallback (
f);
 
  595     pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output", 1);
 
  597     pub_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_, 
"output/pose", 1);
 
  599       *pnh_, 
"output/template", 1);
 
  616     const YAML::Node& template_pose_yaml = 
doc[
"template_poses"];
 
  617     for (
size_t i = 0; 
i < template_pose_yaml.size(); 
i++) {
 
  618       const YAML::Node& 
pose = template_pose_yaml[
i];
 
  622       pcl::PointCloud<pcl::PointXYZRGBA> transformed_cloud;
 
  623       pcl::transformPointCloud<pcl::PointXYZRGBA>(*
template_cloud_, transformed_cloud, trans);
 
  625       Eigen::Vector4f minpt, maxpt;
 
  626       pcl::getMinMax3D<pcl::PointXYZRGBA>(transformed_cloud, minpt, maxpt);
 
  643     std::ifstream linemod_in;
 
  644     linemod_in.open(linemod_file.c_str(), std::ifstream::in);
 
  650 #if __cplusplus >= 201103L 
  651 #define pcl_isfinite(x) std::isfinite(x) 
  655     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
 
  656     const pcl::SparseQuantizedMultiModTemplate& linemod_template,
 
  657     const pcl::LINEMODDetection& linemod_detection,
 
  658     Eigen::Vector3f& center)
 
  660     const size_t start_x = std::max(linemod_detection.x, 0);
 
  661     const size_t start_y = std::max(linemod_detection.y, 0);
 
  663       static_cast<size_t> (start_x + linemod_template.region.width * linemod_detection.scale),
 
  664       static_cast<size_t> (
cloud->width));
 
  666       static_cast<size_t> (start_y + linemod_template.region.height * linemod_detection.scale),
 
  667       static_cast<size_t> (
cloud->height));
 
  669     for (
size_t row_index = start_y; row_index < end_y; ++row_index) {
 
  670       for (
size_t col_index = start_x; col_index < end_x; ++col_index) {
 
  671         const pcl::PointXYZRGBA & 
point = (*cloud) (col_index, row_index);
 
  672         if (pcl_isfinite (
point.x) &&
 
  673             pcl_isfinite (
point.y) &&
 
  674             pcl_isfinite (
point.z)) {
 
  675           center = center + 
point.getVector3fMap();
 
  684     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
 
  687     vital_checker_->poke();
 
  689     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
 
  690       cloud (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  697     std::vector<pcl::LINEMODDetection> linemod_detections;
 
  698     std::vector<pcl::QuantizableModality*> modalities;
 
  701     linemod_.detectTemplatesSemiScaleInvariant(modalities, linemod_detections,
 
  702                                                0.6944444
f, 1.44
f, 1.2
f);
 
  703     NODELET_INFO(
"detected %lu result", linemod_detections.size());
 
  705     if (linemod_detections.size() > 0) {
 
  706       double max_score = 0;
 
  707       size_t max_template_id = 0;
 
  708       double max_scale = 0;
 
  709       pcl::LINEMODDetection linemod_detection;
 
  710       for (
size_t i = 0; 
i < linemod_detections.size(); 
i++) {
 
  711         const pcl::LINEMODDetection& detection = linemod_detections[
i];
 
  712         if (max_score < detection.score) {
 
  713           linemod_detection = detection;
 
  714           max_score = detection.score;
 
  718       const pcl::SparseQuantizedMultiModTemplate& linemod_template = 
 
  719         linemod_.getTemplate(linemod_detection.template_id);
 
  720       Eigen::Vector3f center(0, 0, 0);
 
  722         cloud, linemod_template, linemod_detection, center);
 
  724       cv::Mat detect_mask = cv::Mat::zeros(
cloud->height, 
cloud->width, CV_8UC1);
 
  725       int scaled_template_width
 
  726         = linemod_template.region.width * linemod_detection.scale;
 
  727       int scaled_template_height
 
  728         = linemod_template.region.height * linemod_detection.scale;
 
  731         cv::Point(linemod_detection.x, linemod_detection.y),
 
  732         cv::Point(linemod_detection.x + scaled_template_width,
 
  733                   linemod_detection.y + scaled_template_height),
 
  734         cv::Scalar(255), CV_FILLED);
 
  739       jsk_recognition_msgs::BoundingBox bbox = 
template_bboxes_[linemod_detection.template_id];
 
  740       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr 
 
  741         result (
new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  742       pcl::transformPointCloud<pcl::PointXYZRGBA>(
 
  744       Eigen::Vector4f minpt, maxpt;
 
  745       pcl::getMinMax3D<pcl::PointXYZRGBA>(*
result, minpt, maxpt);
 
  746       Eigen::Vector4f template_center = (minpt + maxpt) / 2;
 
  747       Eigen::Vector3f translation = center - Eigen::Vector3f(template_center[0],
 
  750       Eigen::Affine3f 
pose = 
template_poses_[linemod_detection.template_id] * Eigen::Translation3f(translation);
 
  751       geometry_msgs::PoseStamped ros_pose;
 
  753       ros_pose.header = cloud_msg->header;
 
  755       for (
size_t i = 0; 
i < 
result->points.size(); 
i++) {
 
  756         result->points[
i].getVector3fMap()
 
  757           = 
result->points[
i].getVector3fMap() + translation;
 
  759       sensor_msgs::PointCloud2 ros_result;
 
  761       ros_result.header = cloud_msg->header;
 
  763       sensor_msgs::PointCloud2 ros_template;
 
  765       ros_template.header = cloud_msg->header;