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> 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(
118 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
119 const PCLIndicesMsg::ConstPtr& indices_msg)
122 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
cloud 123 (
new pcl::PointCloud<pcl::PointXYZRGBA>);
125 pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
133 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
136 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
cloud 137 (
new pcl::PointCloud<pcl::PointXYZRGBA>);
144 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
151 std_srvs::Empty::Request&
req,
152 std_srvs::Empty::Response&
res)
162 const Eigen::Affine3f& transform,
163 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud,
165 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr colored_cloud,
166 pcl::PointIndices& mask)
170 double fx = model.
fx();
171 double fy = model.
fy();
172 double cx = model.
cx();
173 double cy = model.
cy();
174 Eigen::Affine3f viewpoint_transform = transform;
175 Eigen::Affine3f object_transform = viewpoint_transform.inverse();
176 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
cloud 177 (
new pcl::PointCloud<pcl::PointXYZRGBA>);
178 pcl::transformPointCloud<pcl::PointXYZRGBA>(
179 *raw_cloud, *cloud, object_transform);
180 pcl::RangeImagePlanar range_image;
181 Eigen::Affine3f dummytrans;
182 dummytrans.setIdentity();
183 range_image.createFromPointCloudWithFixedSize(
184 *cloud, width, height,
185 cx, cy, fx, fy, dummytrans);
186 cv::Mat mat(range_image.height, range_image.width, CV_32FC1);
187 float *tmpf = (
float *)mat.ptr();
188 for(
unsigned int i = 0; i < range_image.height * range_image.width; i++) {
189 tmpf[i] = range_image.points[i].z;
191 std_msgs::Header dummy_header;
198 pcl::KdTreeFLANN<pcl::PointXYZRGBA>::Ptr
199 kdtree (
new pcl::KdTreeFLANN<pcl::PointXYZRGBA>);
200 kdtree->setInputCloud(cloud);
202 colored_cloud->width = range_image.width;
203 colored_cloud->height = range_image.height;
204 colored_cloud->is_dense = range_image.is_dense;
205 pcl::PointXYZRGBA nan_point;
206 nan_point.x = nan_point.y = nan_point.z
207 = std::numeric_limits<float>::quiet_NaN();
208 pcl::PointIndices::Ptr mask_indices (
new pcl::PointIndices);
209 colored_cloud->points.resize(range_image.points.size());
211 cv::Mat colored_image = cv::Mat::zeros(
212 range_image.height, range_image.width, CV_8UC3);
213 for (
size_t pi = 0; pi < range_image.points.size(); pi++) {
214 if (std::isnan(range_image.points[pi].x) ||
215 std::isnan(range_image.points[pi].y) ||
216 std::isnan(range_image.points[pi].z)) {
218 colored_cloud->points[pi] = nan_point;
221 pcl::PointXYZRGBA input_point;
222 input_point.x = range_image.points[pi].x;
223 input_point.y = range_image.points[pi].y;
224 input_point.z = range_image.points[pi].z;
225 std::vector<int> indices;
226 std::vector<float> distances;
227 kdtree->nearestKSearch(input_point, 1, indices, distances);
228 if (indices.size() > 0) {
229 input_point.rgba = cloud->points[indices[0]].rgba;
231 colored_image.at<cv::Vec3b>(pi / range_image.width,
232 pi % range_image.width)
233 = cv::Vec3b(cloud->points[indices[0]].r,
234 cloud->points[indices[0]].g,
235 cloud->points[indices[0]].b);
236 colored_cloud->points[pi] = input_point;
239 for (
size_t pi = 0; pi < range_image.points.size(); pi++) {
240 if (!std::isnan(range_image.points[pi].x) &&
241 !std::isnan(range_image.points[pi].y) &&
242 !std::isnan(range_image.points[pi].z)) {
244 mask.indices.push_back(pi);
252 sensor_msgs::PointCloud2 ros_sample_cloud;
254 pcl::PointCloud<pcl::PointXYZRGB> rgb_cloud;
257 ros_sample_cloud.header = dummy_header;
269 NODELET_FATAL(
"we expect only one training pointcloud, but it has %lu pointclouds",
288 std::vector<Eigen::Affine3f> transforms;
290 for (
size_t i = 0; i < sampler.
sampleNum(); i++) {
291 Eigen::Affine3f transform;
292 sampler.
get(transform);
293 transforms[i] = transform;
302 pcl::RangeImagePlanar dummy_range_image;
304 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud
308 std::vector<pcl::ColorGradientModality<pcl::PointXYZRGBA> >
310 std::vector<pcl::SurfaceNormalModality<pcl::PointXYZRGBA> >
311 surface_norm_modalities (sampler.
sampleNum());
312 std::vector<pcl::MaskMap> mask_maps (sampler.
sampleNum());
313 std::vector<pcl::RegionXY> regions (sampler.
sampleNum());
315 pcl::LINEMOD linemod;
317 std::vector<Eigen::Affine3f> pose_in_order_of_training;
319 #pragma omp parallel for 321 for (
size_t j = 0; j < sampler.
sampleNum(); j++) {
323 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZRGBA>);
324 pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
328 pcl::ColorGradientModality<pcl::PointXYZRGBA> color_modality;
329 pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_norm_mod;
332 pcl::RegionXY region;
334 color_modality, surface_norm_mod,
336 std::vector<pcl::QuantizableModality*> modalities(2);
337 modalities[0] = &color_modality;
338 modalities[1] = &surface_norm_mod;
339 std::vector<pcl::MaskMap*> masks(2);
340 masks[0] = &mask_map;
341 masks[1] = &mask_map;
343 boost::mutex::scoped_lock
lock(train_mutex);
346 linemod.createAndAddTemplate(modalities, masks, region);
347 pose_in_order_of_training.push_back(transforms[j]);
354 std::ofstream linemod_file;
355 const std::string linemod_file_name =
output_file_ +
".linemod";
356 NODELET_INFO(
"writing to %s", linemod_file_name.c_str());
357 linemod_file.open(linemod_file_name.c_str(),
358 std::ofstream::out | std::ofstream::binary);
359 linemod.serialize(linemod_file);
360 linemod_file.close();
361 const std::string pcd_file_name =
output_file_ +
".pcd";
364 writer.writeBinaryCompressed(pcd_file_name, *raw_cloud);
366 std::ofstream pose_file;
367 const std::string pose_file_name =
output_file_ +
"_poses.yaml";
369 pose_file.open(pose_file_name.c_str(), std::ofstream::out);
370 pose_file <<
"template_poses: [" << std::endl;
371 for (
size_t i = 0; i < pose_in_order_of_training.size(); i++) {
372 Eigen::Affine3f
pose = pose_in_order_of_training[i];
373 Eigen::Vector3f
pos(pose.translation());
374 Eigen::Quaternionf
rot(pose.rotation());
376 <<
pos[0] <<
", " <<
pos[1] <<
", " <<
pos[2] <<
", " 377 <<
rot.x() <<
", " <<
rot.y() <<
", " <<
rot.z() <<
", " <<
rot.w() <<
"]";
378 if (i != pose_in_order_of_training.size() - 1) {
379 pose_file <<
", " << std::endl;
382 pose_file <<
"]" << std::endl;
390 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
391 pcl::PointIndices::Ptr mask,
392 pcl::ColorGradientModality<pcl::PointXYZRGBA>& color_grad_mod,
393 pcl::SurfaceNormalModality<pcl::PointXYZRGBA>& surface_norm_mod,
394 pcl::MaskMap& mask_map,
395 pcl::RegionXY& region)
397 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr masked_cloud
398 (
new pcl::PointCloud<pcl::PointXYZRGBA>);
399 pcl::ExtractIndices<pcl::PointXYZRGBA>
ex;
400 ex.setKeepOrganized(
true);
401 ex.setInputCloud(cloud);
403 ex.filter(*masked_cloud);
404 color_grad_mod.setInputCloud(masked_cloud);
405 color_grad_mod.processInputData();
406 surface_norm_mod.setInputCloud(cloud);
407 surface_norm_mod.processInputData();
408 size_t min_x(masked_cloud->width), min_y(masked_cloud->height), max_x(0), max_y(0);
409 for (
size_t j = 0; j < masked_cloud->height; ++j) {
410 for (
size_t i = 0; i < masked_cloud->width; ++i) {
412 = masked_cloud->points[j * masked_cloud->width + i];
413 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
425 region.x =
static_cast<int>(min_x);
426 region.y =
static_cast<int>(min_y);
427 region.width =
static_cast<int>(max_x - min_x + 1);
428 region.height =
static_cast<int>(max_y - min_y + 1);
433 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
434 pcl::PointIndices::Ptr mask,
435 std::string& tempstr,
438 pcl::LINEMOD linemod;
439 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr masked_cloud
440 (
new pcl::PointCloud<pcl::PointXYZRGBA>);
441 pcl::ExtractIndices<pcl::PointXYZRGBA>
ex;
442 ex.setKeepOrganized(
true);
443 ex.setInputCloud(cloud);
445 ex.filter(*masked_cloud);
446 pcl::ColorGradientModality<pcl::PointXYZRGBA> color_grad_mod;
447 color_grad_mod.setInputCloud(masked_cloud);
448 color_grad_mod.processInputData();
449 pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_norm_mod;
450 surface_norm_mod.setInputCloud(masked_cloud);
451 surface_norm_mod.processInputData();
452 std::vector<pcl::QuantizableModality*> modalities(2);
453 modalities[0] = &color_grad_mod;
454 modalities[1] = &surface_norm_mod;
455 size_t min_x(masked_cloud->width), min_y(masked_cloud->height), max_x(0), max_y(0);
456 pcl::MaskMap mask_map(masked_cloud->width, masked_cloud->height);
457 for (
size_t j = 0; j < masked_cloud->height; ++j) {
458 for (
size_t i = 0; i < masked_cloud->width; ++i) {
460 = masked_cloud->points[j * masked_cloud->width + i];
461 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
473 std::vector<pcl::MaskMap*> masks(2);
474 masks[0] = &mask_map;
475 masks[1] = &mask_map;
476 pcl::RegionXY region;
477 region.x =
static_cast<int>(min_x);
478 region.y =
static_cast<int>(min_y);
479 region.width =
static_cast<int>(max_x - min_x + 1);
480 region.height =
static_cast<int>(max_y - min_y + 1);
481 linemod.createAndAddTemplate(modalities, masks, region);
483 std::vector<std::string> ret;
486 std::stringstream filename_stream;
487 filename_stream << boost::format(
"%s/%05d_template.sqmmt") % tempstr % i;
488 std::string
filename = filename_stream.str();
489 std::cerr <<
"writing " << filename << std::endl;
490 std::ofstream file_stream;
491 file_stream.open(filename.c_str(),
492 std::ofstream::out | std::ofstream::binary);
493 linemod.getTemplate(0).serialize(file_stream);
495 ret.push_back(filename);
499 std::stringstream filename_stream;
500 filename_stream << boost::format(
"%s/%05d_template.pcd") % tempstr % i;
501 std::string
filename = filename_stream.str();
502 std::cerr <<
"writing " << filename << std::endl;
504 writer.writeBinaryCompressed(filename, *masked_cloud);
505 ret.push_back(filename);
513 boost::filesystem::path temp = boost::filesystem::unique_path();
514 boost::filesystem::create_directory(temp);
515 std::string tempstr = temp.native();
517 std::vector<std::string> all_files;
518 for (
size_t i = 0; i <
samples_.size(); i++) {
533 std::stringstream command_stream;
534 command_stream <<
"tar --format=ustar -cf " << output <<
" " << directory <<
"/*";
535 NODELET_INFO(
"executing %s", command_stream.str().c_str());
536 int ret = system(command_stream.str().c_str());
540 std_srvs::Empty::Request&
req,
541 std_srvs::Empty::Response&
res)
555 DiagnosticNodelet::onInit();
556 pnh_->param(
"template_file", template_file_, std::string(
"template"));
558 template_cloud_.reset(
new pcl::PointCloud<pcl::PointXYZRGBA>);
560 reader.read(template_file_ +
".pcd", *template_cloud_);
561 const std::string pose_yaml = template_file_ +
"_poses.yaml";
564 std::ifstream pose_fin;
565 pose_fin.open(pose_yaml.c_str(), std::ifstream::in);
566 YAML::Parser
parser(pose_fin);
567 while (parser.GetNextDocument(doc)) {
573 doc = YAML::LoadFile(pose_yaml);
578 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
579 dynamic_reconfigure::Server<Config>::CallbackType
f =
582 srv_->setCallback (f);
584 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
585 pub_detect_mask_ = advertise<sensor_msgs::Image>(*
pnh_,
"output/mask", 1);
586 pub_pose_ = advertise<geometry_msgs::PoseStamped>(*
pnh_,
"output/pose", 1);
587 pub_original_template_cloud_ = advertise<sensor_msgs::PointCloud2>(
588 *
pnh_,
"output/template", 1);
600 sub_cloud_.shutdown();
605 const YAML::Node& template_pose_yaml = doc[
"template_poses"];
606 for (
size_t i = 0; i < template_pose_yaml.size(); i++) {
607 const YAML::Node&
pose = template_pose_yaml[i];
609 template_poses_.push_back(trans);
611 pcl::PointCloud<pcl::PointXYZRGBA> transformed_cloud;
612 pcl::transformPointCloud<pcl::PointXYZRGBA>(*template_cloud_, transformed_cloud, trans);
614 Eigen::Vector4f minpt, maxpt;
615 pcl::getMinMax3D<pcl::PointXYZRGBA>(transformed_cloud, minpt, maxpt);
618 template_bboxes_.push_back(bbox);
625 gradient_magnitude_threshold_ = config.gradient_magnitude_threshold;
626 detection_threshold_ = config.detection_threshold;
627 color_gradient_mod_.setGradientMagnitudeThreshold(gradient_magnitude_threshold_);
628 linemod_.setDetectionThreshold(detection_threshold_);
631 const std::string linemod_file = template_file_ +
".linemod";
632 std::ifstream linemod_in;
633 linemod_in.open(linemod_file.c_str(), std::ifstream::in);
634 linemod_.deserialize(linemod_in);
639 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
640 const pcl::SparseQuantizedMultiModTemplate& linemod_template,
641 const pcl::LINEMODDetection& linemod_detection,
642 Eigen::Vector3f& center)
644 const size_t start_x =
std::max(linemod_detection.x, 0);
645 const size_t start_y =
std::max(linemod_detection.y, 0);
647 static_cast<size_t> (start_x + linemod_template.region.width * linemod_detection.scale),
648 static_cast<size_t> (cloud->width));
650 static_cast<size_t> (start_y + linemod_template.region.height * linemod_detection.scale),
651 static_cast<size_t> (cloud->height));
653 for (
size_t row_index = start_y; row_index < end_y; ++row_index) {
654 for (
size_t col_index = start_x; col_index < end_x; ++col_index) {
655 const pcl::PointXYZRGBA &
point = (*cloud) (col_index, row_index);
656 if (pcl_isfinite (point.x) &&
657 pcl_isfinite (point.y) &&
658 pcl_isfinite (point.z)) {
659 center = center + point.getVector3fMap();
668 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
671 vital_checker_->poke();
673 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
674 cloud (
new pcl::PointCloud<pcl::PointXYZRGBA>);
677 surface_normal_mod_.setInputCloud(cloud);
678 surface_normal_mod_.processInputData ();
679 color_gradient_mod_.setInputCloud (cloud);
680 color_gradient_mod_.processInputData ();
681 std::vector<pcl::LINEMODDetection> linemod_detections;
682 std::vector<pcl::QuantizableModality*> modalities;
683 modalities.push_back(&color_gradient_mod_);
684 modalities.push_back(&surface_normal_mod_);
685 linemod_.detectTemplatesSemiScaleInvariant(modalities, linemod_detections,
686 0.6944444
f, 1.44
f, 1.2
f);
687 NODELET_INFO(
"detected %lu result", linemod_detections.size());
689 if (linemod_detections.size() > 0) {
690 double max_score = 0;
691 size_t max_template_id = 0;
692 double max_scale = 0;
693 pcl::LINEMODDetection linemod_detection;
694 for (
size_t i = 0; i < linemod_detections.size(); i++) {
695 const pcl::LINEMODDetection& detection = linemod_detections[i];
696 if (max_score < detection.score) {
697 linemod_detection = detection;
698 max_score = detection.score;
702 const pcl::SparseQuantizedMultiModTemplate& linemod_template =
703 linemod_.getTemplate(linemod_detection.template_id);
704 Eigen::Vector3f center(0, 0, 0);
705 computeCenterOfTemplate(
706 cloud, linemod_template, linemod_detection, center);
708 cv::Mat detect_mask = cv::Mat::zeros(cloud->height, cloud->width, CV_8UC1);
709 int scaled_template_width
710 = linemod_template.region.width * linemod_detection.scale;
711 int scaled_template_height
712 = linemod_template.region.height * linemod_detection.scale;
715 cv::Point(linemod_detection.x, linemod_detection.y),
716 cv::Point(linemod_detection.x + scaled_template_width,
717 linemod_detection.y + scaled_template_height),
718 cv::Scalar(255), CV_FILLED);
723 jsk_recognition_msgs::BoundingBox bbox = template_bboxes_[linemod_detection.template_id];
724 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
725 result (
new pcl::PointCloud<pcl::PointXYZRGBA>);
726 pcl::transformPointCloud<pcl::PointXYZRGBA>(
727 *template_cloud_, *result, template_poses_[linemod_detection.template_id]);
728 Eigen::Vector4f minpt, maxpt;
729 pcl::getMinMax3D<pcl::PointXYZRGBA>(*result, minpt, maxpt);
730 Eigen::Vector4f template_center = (minpt + maxpt) / 2;
731 Eigen::Vector3f translation = center - Eigen::Vector3f(template_center[0],
734 Eigen::Affine3f
pose = template_poses_[linemod_detection.template_id] * Eigen::Translation3f(translation);
735 geometry_msgs::PoseStamped ros_pose;
737 ros_pose.header = cloud_msg->header;
739 for (
size_t i = 0; i < result->points.size(); i++) {
740 result->points[i].getVector3fMap()
741 = result->points[i].getVector3fMap() + translation;
743 sensor_msgs::PointCloud2 ros_result;
745 ros_result.header = cloud_msg->header;
746 pub_cloud_.publish(ros_result);
747 sensor_msgs::PointCloud2 ros_template;
749 ros_template.header = cloud_msg->header;
750 pub_original_template_cloud_.publish(ros_template);
virtual void subscribeCloud(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::ServiceServer clear_data_srv_
std::vector< pcl::PointIndices::Ptr > sample_indices_
cv::Size fullResolution() const
double min(const OneDataStat &d)
wrapper function for min method for boost::function
double sample_viewpoint_radius_max_
virtual void setTemplate(YAML::Node doc)
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
sensor_msgs::CameraInfo::ConstPtr camera_info_
double max(const OneDataStat &d)
wrapper function for max method for boost::function
virtual void trainWithViewpointSampling()
double sample_viewpoint_angle_min_
virtual void trainWithoutViewpointSampling()
std::vector< pcl::PointCloud< pcl::PointXYZRGBA >::Ptr > samples_before_sampling_
double sample_viewpoint_radius_min_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher pub_range_image_
virtual size_t sampleNum()
virtual void computeCenterOfTemplate(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, const pcl::SparseQuantizedMultiModTemplate &linemod_template, const pcl::LINEMODDetection &linemod_detection, Eigen::Vector3f ¢er)
virtual bool startTraining(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual std::vector< std::string > trainOneData(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, pcl::PointIndices::Ptr mask, std::string &tempstr, int i)
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
std::vector< pcl::PointCloud< pcl::PointXYZRGBA >::Ptr > samples_
ros::Subscriber sub_input_nonsync_
virtual void unsubscribe()
virtual void subscribeCameraInfo(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
ros::ServiceServer start_training_srv_
virtual void store(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const PCLIndicesMsg::ConstPtr &indices_msg)
Eigen::Affine3f affineFromYAMLNode(const YAML::Node &pose)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
virtual void tar(const std::string &directory, const std::string &output)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::Publisher pub_sample_cloud_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
ros::Subscriber sub_camera_info_nonsync_
boost::mutex mutex
global mutex.
LINEMODDetectorConfig Config
#define NODELET_INFO(...)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
virtual void generateLINEMODTrainingData(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, pcl::PointIndices::Ptr mask, pcl::ColorGradientModality< pcl::PointXYZRGBA > &color_grad_mod, pcl::SurfaceNormalModality< pcl::PointXYZRGBA > &surface_norm_mod, pcl::MaskMap &mask_map, pcl::RegionXY ®ion)
jsk_recognition_msgs::BoundingBox boundingBoxFromPointCloud(const pcl::PointCloud< PointT > &cloud)
double sample_viewpoint_angle_step_
double sample_viewpoint_angle_max_
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::LINEMODTrainer, nodelet::Nodelet)
ros::Publisher pub_colored_range_image_
#define NODELET_FATAL(...)
virtual void get(Eigen::Affine3f &transform)
double sample_viewpoint_radius_step_
sensor_msgs::ImagePtr toImageMsg() const
virtual void organizedPointCloudWithViewPoint(const Eigen::Affine3f &transform, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr raw_cloud, const image_geometry::PinholeCameraModel &model, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr output, pcl::PointIndices &mask)
virtual bool clearData(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)