35 #define BOOST_PARAMETER_MAX_ARITY 7 39 #include <pcl/tracking/impl/distance_coherence.hpp> 40 #include <pcl/tracking/impl/approx_nearest_pair_point_cloud_coherence.hpp> 43 #include <geometry_msgs/TwistStamped.h> 44 #include <std_msgs/Bool.h> 45 #include <pcl/kdtree/kdtree_flann.h> 52 void ParticleFilterTracking::onInit(
void)
55 pcl::console::setVerbosityLevel(pcl::console::VERBOSITY_LEVEL::L_ALWAYS);
57 ConnectionBasedNodelet::onInit();
59 track_target_set_ =
false;
62 default_step_covariance_.resize(6);
64 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
65 dynamic_reconfigure::Server<Config>::CallbackType
f =
66 boost::bind(&ParticleFilterTracking::config_callback,
this, _1, _2);
70 pnh_->param(
"particle_num", particle_num, max_particle_num_ - 1);
72 pnh_->param(
"use_normal", use_normal,
false);
74 pnh_->param(
"use_hsv", use_hsv,
true);
75 pnh_->param(
"track_target_name", track_target_name_,
76 std::string(
"track_result"));
77 std::vector<double> initial_noise_covariance(6, 0.00001);
79 *pnh_,
"initial_noise_covariance",
80 initial_noise_covariance);
81 std::vector<double> default_initial_mean(6, 0.0);
83 *pnh_,
"default_initial_mean", default_initial_mean);
86 double octree_resolution = 0.01;
87 pnh_->getParam(
"octree_resolution", octree_resolution);
88 pnh_->param(
"align_box", align_box_,
false);
89 pnh_->param(
"BASE_FRAME_ID", base_frame_id_, std::string(
"NONE"));
90 if (base_frame_id_.compare(
"NONE") != 0) {
93 target_cloud_.reset(
new pcl::PointCloud<PointT>());
94 pnh_->param(
"not_use_reference_centroid", not_use_reference_centroid_,
96 pnh_->param(
"not_publish_tf", not_publish_tf_,
false);
97 pnh_->param(
"reversed", reversed_,
false);
100 pnh_->param(
"thread_nr", thread_nr, omp_get_num_procs());
104 (
new KLDAdaptiveParticleFilterOMPTracker<PointT, ParticleXYZRPY>(thread_nr));
105 tracker->setMaximumParticleNum(max_particle_num_);
106 tracker->setDelta(delta_);
107 tracker->setEpsilon(epsilon_);
108 tracker->setBinSize(bin_size_);
116 reversed_tracker_ = tracker;
118 tracker_set_trans(Eigen::Affine3f::Identity());
119 tracker_set_step_noise_covariance(default_step_covariance_);
120 tracker_set_initial_noise_covariance(initial_noise_covariance);
121 tracker_set_initial_noise_mean(default_initial_mean);
122 tracker_set_iteration_num(iteration_num_);
123 tracker_set_particle_num(particle_num);
124 tracker_set_resample_likelihood_thr(resample_likelihood_thr_);
125 tracker_set_use_normal(use_normal);
129 bool enable_organized;
130 pnh_->param(
"enable_cache", enable_cache,
false);
131 pnh_->param(
"enable_organized", enable_organized,
false);
132 ApproxNearestPairPointCloudCoherence<PointT>::Ptr coherence;
134 double cache_bin_size_x, cache_bin_size_y, cache_bin_size_z;
135 pnh_->param(
"cache_size_x", cache_bin_size_x, 0.01);
136 pnh_->param(
"cache_size_y", cache_bin_size_y, 0.01);
137 pnh_->param(
"cache_size_z", cache_bin_size_z, 0.01);
139 cache_bin_size_x, cache_bin_size_y, cache_bin_size_z));
140 }
else if(enable_organized){
144 coherence.reset(
new ApproxNearestPairPointCloudCoherence<PointT>());
149 distance_coherence(
new DistanceCoherence<PointT>);
150 coherence->addPointCoherence(distance_coherence);
156 coherence->addPointCoherence(hsv_color_coherence);
160 (
new pcl::search::Octree<PointT>(octree_resolution));
162 coherence->setSearchMethod(search);
164 pnh_->param(
"max_distance", max_distance, 0.01);
165 coherence->setMaximumDistance(max_distance);
166 pnh_->param(
"use_change_detection", use_change_detection_,
false);
167 tracker_set_cloud_coherence(coherence);
170 particle_publisher_ = pnh_->advertise<sensor_msgs::PointCloud2>(
172 track_result_publisher_ = pnh_->advertise<sensor_msgs::PointCloud2>(
174 pose_stamped_publisher_ = pnh_->advertise<geometry_msgs::PoseStamped>(
175 "track_result_pose", 1);
176 pub_latest_time_ = pnh_->advertise<std_msgs::Float32>(
177 "output/latest_time", 1);
178 pub_average_time_ = pnh_->advertise<std_msgs::Float32>(
179 "output/average_time", 1);
180 pub_rms_angle_ = pnh_->advertise<std_msgs::Float32>(
181 "output/rms_angle_error", 1);
182 pub_rms_distance_ = pnh_->advertise<std_msgs::Float32>(
183 "output/rms_distance_error", 1);
184 pub_velocity_ = pnh_->advertise<geometry_msgs::TwistStamped>(
185 "output/velocity", 1);
186 pub_velocity_norm_ = pnh_->advertise<std_msgs::Float32>(
187 "output/velocity_norm", 1);
188 pub_no_move_raw_ = pnh_->advertise<std_msgs::Bool>(
189 "output/no_move_raw", 1);
190 pub_no_move_ = pnh_->advertise<std_msgs::Bool>(
191 "output/no_move", 1);
192 pub_skipped_ = pnh_->advertise<std_msgs::Bool>(
193 "output/skipped", 1);
195 if (use_change_detection_) {
196 pub_change_cloud_marker_ = pnh_->advertise<visualization_msgs::MarkerArray>(
197 "output/change_marker", 1);
198 pub_tracker_status_ = pnh_->advertise<jsk_recognition_msgs::TrackerStatus>(
199 "output/tracker_status", 1);
200 sub_input_cloud_.subscribe(*pnh_,
"input", 4);
201 sub_change_cloud_.subscribe(*pnh_,
"input_change", 4);
202 change_sync_ = boost::make_shared<message_filters::Synchronizer<SyncChangePolicy> >(100);
203 change_sync_->connectInput(sub_input_cloud_, sub_change_cloud_);
204 change_sync_->registerCallback(
206 &ParticleFilterTracking::cloud_change_cb,
210 sub_ = pnh_->subscribe(
"input", 1, &ParticleFilterTracking::cloud_cb,
this);
213 sub_input_.subscribe(*pnh_,
"renew_model", 1);
214 sub_box_.subscribe(*pnh_,
"renew_box", 1);
215 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
216 sync_->connectInput(sub_input_, sub_box_);
217 sync_->registerCallback(
219 &ParticleFilterTracking::renew_model_with_box_topic_cb,
223 sub_update_model_ = pnh_->subscribe(
224 "renew_model", 1, &ParticleFilterTracking::renew_model_topic_cb,
this);
225 sub_update_with_marker_model_
226 = pnh_->subscribe(
"renew_model_with_marker", 1, &ParticleFilterTracking::renew_model_with_marker_topic_cb,
this);
229 pnh_->param(
"marker_to_pointcloud_sampling_nums", marker_to_pointcloud_sampling_nums_, 10000);
231 = pnh_->advertiseService(
232 "renew_model", &ParticleFilterTracking::renew_model_cb,
this);
237 void ParticleFilterTracking::config_callback(
Config &config, uint32_t level)
239 boost::mutex::scoped_lock
lock(mtx_);
240 max_particle_num_ = config.max_particle_num;
241 iteration_num_ = config.iteration_num;
242 resample_likelihood_thr_ = config.resample_likelihood_thr;
243 delta_ = config.delta;
244 epsilon_ = config.epsilon;
245 bin_size_.x = config.bin_size_x;
246 bin_size_.y = config.bin_size_y;
247 bin_size_.z = config.bin_size_z;
248 bin_size_.roll = config.bin_size_roll;
249 bin_size_.pitch = config.bin_size_pitch;
250 bin_size_.yaw = config.bin_size_yaw;
251 default_step_covariance_[0] = config.default_step_covariance_x;
252 default_step_covariance_[1] = config.default_step_covariance_y;
253 default_step_covariance_[2] = config.default_step_covariance_z;
254 default_step_covariance_[3] = config.default_step_covariance_roll;
255 default_step_covariance_[4] = config.default_step_covariance_pitch;
256 default_step_covariance_[5] = config.default_step_covariance_yaw;
257 static_velocity_thr_ = config.static_velocity_thr;
258 change_cloud_near_threshold_ = config.change_cloud_near_thr;
259 if (tracker_ || reversed_tracker_)
262 tracker_set_step_noise_covariance(default_step_covariance_);
263 tracker_set_iteration_num(iteration_num_);
264 tracker_set_resample_likelihood_thr(resample_likelihood_thr_);
265 tracker_set_maximum_particle_num(max_particle_num_);
266 tracker_set_delta(delta_);
267 tracker_set_epsilon(epsilon_);
268 tracker_set_bin_size(bin_size_);
273 void ParticleFilterTracking::publish_particles()
276 if (particles && new_cloud_ && particle_publisher_.getNumSubscribers()) {
278 pcl::PointCloud<pcl::PointXYZ>::Ptr particle_cloud
279 (
new pcl::PointCloud<pcl::PointXYZ>());
280 for (
size_t i = 0; i < particles->points.size(); i++)
283 point.
x = particles->points[i].x;
284 point.y = particles->points[i].y;
285 point.z = particles->points[i].z;
286 particle_cloud->points.push_back(point);
289 sensor_msgs::PointCloud2 particle_pointcloud2;
291 particle_pointcloud2.header.frame_id = reference_frame_id();
292 particle_pointcloud2.header.stamp = stamp_;
293 particle_publisher_.publish(particle_pointcloud2);
297 void ParticleFilterTracking::publish_result()
299 ParticleXYZRPY
result = tracker_get_result();
300 Eigen::Affine3f transformation = tracker_to_eigen_matrix(result);
306 if (!not_publish_tf_) {
309 tfTransformation, stamp_,
310 reference_frame_id(), track_target_name_));
313 geometry_msgs::PoseStamped result_pose_stamped;
314 result_pose_stamped.header.frame_id = reference_frame_id();
315 result_pose_stamped.header.stamp = stamp_;
318 pose_stamped_publisher_.publish(result_pose_stamped);
320 pcl::PointCloud<PointT>::Ptr result_cloud
321 (
new pcl::PointCloud<PointT>());
322 pcl::transformPointCloud<PointT>(
323 *(tracker_get_reference_cloud()), *result_cloud, transformation);
324 sensor_msgs::PointCloud2 result_pointcloud2;
326 result_pointcloud2.header.frame_id = reference_frame_id();
327 result_pointcloud2.header.stamp = stamp_;
328 track_result_publisher_.publish(result_pointcloud2);
331 geometry_msgs::TwistStamped twist;
332 twist.header.frame_id = reference_frame_id();
333 twist.header.stamp = stamp_;
334 double dt = (stamp_ - prev_stamp_).toSec();
335 twist.twist.linear.x = (result.x - prev_result_.x) / dt;
336 twist.twist.linear.y = (result.y - prev_result_.y) / dt;
337 twist.twist.linear.z = (result.z - prev_result_.z) / dt;
338 twist.twist.angular.x = (result.roll - prev_result_.roll) / dt;
339 twist.twist.angular.y = (result.pitch - prev_result_.pitch) / dt;
340 twist.twist.angular.z = (result.yaw - prev_result_.yaw) / dt;
341 pub_velocity_.publish(twist);
342 Eigen::Vector3f vel(twist.twist.linear.x, twist.twist.linear.y, twist.twist.linear.z);
343 std_msgs::Float32 velocity_norm;
344 velocity_norm.data = vel.norm();
345 pub_velocity_norm_.publish(velocity_norm);
346 bool is_static = vel.norm() < static_velocity_thr_;
347 no_move_buffer_.addValue(is_static);
348 std_msgs::Bool no_move_raw, no_move;
349 no_move_raw.data = is_static;
350 no_move.data = no_move_buffer_.isAllTrueFilled();
351 pub_no_move_.publish(no_move);
352 pub_no_move_raw_.publish(no_move_raw);
355 Eigen::Affine3f diff_trans = transformation.inverse() * initial_pose_;
356 double distance_error = Eigen::Vector3f(diff_trans.translation()).norm();
357 double angle_error = Eigen::AngleAxisf(diff_trans.rotation()).
angle();
358 distance_error_buffer_.push_back(distance_error);
359 angle_error_buffer_.push_back(angle_error);
360 double distance_rms = rms(distance_error_buffer_);
361 double angle_rms = rms(angle_error_buffer_);
362 std_msgs::Float32 ros_distance_rms, ros_angle_rms;
363 ros_distance_rms.data = distance_rms;
364 ros_angle_rms.data = angle_rms;
365 pub_rms_distance_.publish(ros_distance_rms);
366 pub_rms_angle_.publish(ros_angle_rms);
367 prev_result_ = result;
368 prev_stamp_ = stamp_;
372 std::string ParticleFilterTracking::reference_frame_id()
374 if (base_frame_id_.compare(
"NONE") == 0) {
378 return base_frame_id_;
382 void ParticleFilterTracking::reset_tracking_target_model(
383 const pcl::PointCloud<PointT>::ConstPtr &recieved_target_cloud)
385 pcl::PointCloud<PointT>::Ptr new_target_cloud(
new pcl::PointCloud<PointT>);
386 std::vector<int> indices;
387 new_target_cloud->is_dense =
false;
388 pcl::removeNaNFromPointCloud(
389 *recieved_target_cloud, *new_target_cloud, indices);
391 if (base_frame_id_.compare(
"NONE") != 0) {
393 = change_pointcloud_frame(new_target_cloud);
394 reference_transform_ = transform_result * reference_transform_;;
397 if (!recieved_target_cloud->points.empty()) {
399 Eigen::Affine3f trans = Eigen::Affine3f::Identity();
400 pcl::PointCloud<PointT>::Ptr transed_ref(
new pcl::PointCloud<PointT>);
402 if (!not_use_reference_centroid_) {
404 pcl::compute3DCentroid(*new_target_cloud, c);
405 trans.translation().matrix() = Eigen::Vector3f(c[0], c[1], c[2]);
409 Eigen::Affine3d trans_3d = Eigen::Affine3d::Identity();
411 trans = (Eigen::Affine3f) trans_3d;
413 pcl::transformPointCloud(*new_target_cloud, *transed_ref, trans.inverse());
416 boost::mutex::scoped_lock
lock(mtx_);
417 tracker_set_reference_cloud(transed_ref);
418 tracker_set_trans(trans);
419 tracker_reset_tracking();
420 initial_pose_ = Eigen::Affine3f(trans);
422 track_target_set_ =
true;
426 track_target_set_ =
false;
427 NODELET_ERROR(
"TARGET MODEL POINTS SIZE IS 0 !! Stop TRACKING");
432 pcl::PointCloud<PointT>::Ptr cloud)
438 listener_->waitForTransform(base_frame_id_,
frame_id_, now,
440 listener_->lookupTransform(base_frame_id_,
frame_id_, now,
441 tfTransformationStamped);
450 Eigen::Affine3f trans; Eigen::Affine3d trans_3d;
452 trans = (Eigen::Affine3f) trans_3d;
453 pcl::transformPointCloud(*cloud, *cloud, trans);
454 return tfTransformation;
457 void ParticleFilterTracking::publish_tracker_status(
const std_msgs::Header&
header,
458 const bool is_tracking)
460 jsk_recognition_msgs::TrackerStatus tracker_status;
461 tracker_status.header =
header;
462 tracker_status.is_tracking = is_tracking;
463 pub_tracker_status_.publish(tracker_status);
466 void ParticleFilterTracking::cloud_change_cb(
const sensor_msgs::PointCloud2::ConstPtr &pc_msg,
467 const sensor_msgs::PointCloud2::ConstPtr &change_cloud_msg)
469 if (no_move_buffer_.isAllTrueFilled()) {
471 = timer_.reporter(pub_latest_time_, pub_average_time_);
473 pcl::PointCloud<pcl::PointXYZRGB>::Ptr change_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
475 if (change_cloud->points.size() == 0) {
476 stamp_ = pc_msg->header.stamp;
478 publish_tracker_status(pc_msg->header,
false);
481 pcl::KdTreeFLANN<pcl::PointXYZRGB> kdtree;
482 kdtree.setInputCloud(change_cloud);
483 std::vector<int> k_indices;
484 std::vector<float> k_sqr_distances;
486 p.x = prev_result_.x;
487 p.y = prev_result_.y;
488 p.z = prev_result_.z;
489 if (kdtree.radiusSearch(p, change_cloud_near_threshold_, k_indices, k_sqr_distances, 1) > 0) {
494 no_move_buffer_.clear();
495 publish_tracker_status(pc_msg->header,
true);
499 stamp_ = pc_msg->header.stamp;
501 publish_tracker_status(pc_msg->header,
false);
505 publish_tracker_status(pc_msg->header,
true);
511 void ParticleFilterTracking::cloud_cb(
const sensor_msgs::PointCloud2 &pc)
513 if (track_target_set_) {
514 pcl::PointCloud<PointT>::Ptr
cloud(
new pcl::PointCloud<PointT>());
516 stamp_ = pc.header.stamp;
517 std::vector<int> indices;
519 cloud->is_dense =
false;
522 = timer_.reporter(pub_latest_time_, pub_average_time_);
523 pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
524 if (base_frame_id_.compare(
"NONE")!=0) {
525 change_pointcloud_frame(cloud);
527 cloud_pass_downsampled_.reset(
new pcl::PointCloud<PointT>);
528 pcl::copyPointCloud(*cloud, *cloud_pass_downsampled_);
529 if (!cloud_pass_downsampled_->points.empty()) {
530 boost::mutex::scoped_lock
lock(mtx_);
531 tracker_set_input_cloud(cloud_pass_downsampled_);
541 void ParticleFilterTracking::renew_model_topic_cb(
542 const sensor_msgs::PointCloud2 &pc)
544 pcl::PointCloud<PointT>::Ptr new_target_cloud
545 (
new pcl::PointCloud<PointT>());
548 reset_tracking_target_model(new_target_cloud);
551 void ParticleFilterTracking::renew_model_with_marker_topic_cb(
const visualization_msgs::Marker &marker)
553 if(marker.type == visualization_msgs::Marker::TRIANGLE_LIST && !marker.points.empty()){
554 ROS_INFO(
"Reset Tracker Model with renew_model_with_marker_topic_cb");
555 pcl::PointCloud<PointT>::Ptr
cloud(
new pcl::PointCloud<PointT>);
557 marker_to_pointcloud_sampling_nums_,
561 Eigen::Affine3f trans;
563 pcl::transformPointCloud(*cloud, *cloud, trans);
566 reset_tracking_target_model(cloud);
568 ROS_ERROR(
" Marker Models type is not TRIANGLE ");
574 void ParticleFilterTracking::renew_model_with_box_topic_cb(
575 const sensor_msgs::PointCloud2::ConstPtr &pc_ptr,
576 const jsk_recognition_msgs::BoundingBox::ConstPtr &bb_ptr)
578 pcl::PointCloud<PointT>::Ptr new_target_cloud
579 (
new pcl::PointCloud<PointT>());
583 reset_tracking_target_model(new_target_cloud);
586 bool ParticleFilterTracking::renew_model_cb(
587 jsk_recognition_msgs::SetPointCloud2::Request &
req,
588 jsk_recognition_msgs::SetPointCloud2::Response &
res)
590 pcl::PointCloud<PointT>::Ptr new_target_cloud(
new pcl::PointCloud<PointT>());
593 reset_tracking_target_model(new_target_cloud);
597 void ParticleFilterTracking::tracker_set_trans(
598 const Eigen::Affine3f& trans)
600 Eigen::Vector3f
pos = trans.translation();
601 NODELET_INFO(
"trans: [%f, %f, %f]", pos[0], pos[1], pos[2]);
603 reversed_tracker_->setTrans(trans);
606 tracker_->setTrans(trans);
610 void ParticleFilterTracking::tracker_set_step_noise_covariance(
611 const std::vector<double>& covariance)
614 reversed_tracker_->setStepNoiseCovariance(covariance);
617 tracker_->setStepNoiseCovariance(covariance);
621 void ParticleFilterTracking::tracker_set_initial_noise_covariance(
622 const std::vector<double>& covariance)
625 reversed_tracker_->setInitialNoiseCovariance(covariance);
628 tracker_->setInitialNoiseCovariance(covariance);
632 void ParticleFilterTracking::tracker_set_initial_noise_mean(
633 const std::vector<double>&
mean)
636 reversed_tracker_->setInitialNoiseMean(mean);
639 tracker_->setInitialNoiseMean(mean);
643 void ParticleFilterTracking::tracker_set_iteration_num(
const int num)
646 reversed_tracker_->setIterationNum(num);
649 tracker_->setIterationNum(num);
653 void ParticleFilterTracking::tracker_set_particle_num(
const int num)
656 reversed_tracker_->setParticleNum(num);
659 tracker_->setParticleNum(num);
663 void ParticleFilterTracking::tracker_set_resample_likelihood_thr(
double thr)
666 reversed_tracker_->setResampleLikelihoodThr(thr);
669 tracker_->setResampleLikelihoodThr(thr);
673 void ParticleFilterTracking::tracker_set_use_normal(
bool use_normal)
676 reversed_tracker_->setUseNormal(use_normal);
679 tracker_->setUseNormal(use_normal);
683 void ParticleFilterTracking::tracker_set_cloud_coherence(
684 ApproxNearestPairPointCloudCoherence<PointT>::Ptr coherence)
687 reversed_tracker_->setCloudCoherence(coherence);
690 tracker_->setCloudCoherence(coherence);
694 void ParticleFilterTracking::tracker_set_maximum_particle_num(
int num)
697 tracker_->setMaximumParticleNum(num);
701 void ParticleFilterTracking::tracker_set_delta(
double delta)
704 tracker_->setDelta(delta);
708 void ParticleFilterTracking::tracker_set_epsilon(
double epsilon)
711 tracker_->setEpsilon(epsilon);
715 void ParticleFilterTracking::tracker_set_bin_size(
716 const ParticleXYZRPY bin_size)
719 tracker_->setBinSize(bin_size);
724 ParticleFilterTracking::tracker_get_particles()
727 return tracker_->getParticles();
730 return reversed_tracker_->getParticles();
734 ParticleXYZRPY ParticleFilterTracking::tracker_get_result()
737 return tracker_->getResult();
740 return reversed_tracker_->getResult();
744 Eigen::Affine3f ParticleFilterTracking::tracker_to_eigen_matrix(
745 const ParticleXYZRPY& result)
748 return tracker_->toEigenMatrix(result);
751 return reversed_tracker_->toEigenMatrix(result);
755 pcl::PointCloud<ParticleFilterTracking::PointT>::ConstPtr
756 ParticleFilterTracking::tracker_get_reference_cloud()
759 return tracker_->getReferenceCloud();
762 return reversed_tracker_->getReferenceCloud();
766 void ParticleFilterTracking::tracker_set_reference_cloud(
767 pcl::PointCloud<PointT>::Ptr ref)
770 tracker_->setReferenceCloud(ref);
773 reversed_tracker_->setReferenceCloud(ref);
776 no_move_buffer_.clear();
779 void ParticleFilterTracking::tracker_reset_tracking()
782 tracker_->resetTracking();
785 reversed_tracker_->resetTracking();
789 void ParticleFilterTracking::tracker_set_input_cloud(
790 pcl::PointCloud<PointT>::Ptr input)
793 tracker_->setInputCloud(input);
796 reversed_tracker_->setInputCloud(input);
799 void ParticleFilterTracking::tracker_compute()
805 reversed_tracker_->compute();
ParticleFilterTracker< PointT, ParticleXYZRPY >::PointCloudStatePtr PointCloudStatePtr
void transformEigenToTF(const Eigen::Affine3d &e, tf::Transform &t)
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
virtual void setIsEnabled(bool)
#define NODELET_ERROR(...)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ParticleFilterTracking, nodelet::Nodelet)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ParticleFilterTrackingConfig Config
void markerMsgToPointCloud(const visualization_msgs::Marker &input_marker, int sample_nums, pcl::PointCloud< PointT > &output_cloud)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define NODELET_INFO(...)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
static tf::TransformListener * getInstance()
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)