particle_filter_tracking_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Yuto Inagaki and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #define BOOST_PARAMETER_MAX_ARITY 7
36 
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>
46 
47 using namespace pcl::tracking;
48 
49 namespace jsk_pcl_ros
50 {
51 
52  void ParticleFilterTracking::onInit(void)
53  {
54  // Suppress huge amount of error message.
55  pcl::console::setVerbosityLevel(pcl::console::VERBOSITY_LEVEL::L_ALWAYS);
56  // not implemented yet
57  ConnectionBasedNodelet::onInit();
58 
59  track_target_set_ = false;
60  new_cloud_ = false;
61 
62  default_step_covariance_.resize(6);
63 
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);
67  srv_->setCallback(f);
68 
69  int particle_num;
70  pnh_->param("particle_num", particle_num, max_particle_num_ - 1);
71  bool use_normal;
72  pnh_->param("use_normal", use_normal, false);
73  bool use_hsv;
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);
84 
85  //First the track target is not set
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) {
92  }
93  target_cloud_.reset(new pcl::PointCloud<PointT>());
94  pnh_->param("not_use_reference_centroid", not_use_reference_centroid_,
95  false);
96  pnh_->param("not_publish_tf", not_publish_tf_, false);
97  pnh_->param("reversed", reversed_, false);
98 
99  int thread_nr;
100  pnh_->param("thread_nr", thread_nr, omp_get_num_procs());
101 
102  if (!reversed_) {
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_);
109  tracker_ = tracker;
110  }
111  else {
114  // boost::shared_ptr<ReversedParticleFilterTracker<PointT, ParticleXYZRPY> > tracker
115  // (new ReversedParticleFilterTracker<PointT, ParticleXYZRPY>());
116  reversed_tracker_ = tracker;
117  }
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);
126 
127  //Setup coherence object for tracking
128  bool enable_cache;
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;
133  if (enable_cache) {
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){
142  }
143  else {
144  coherence.reset(new ApproxNearestPairPointCloudCoherence<PointT>());
145  }
146 
147 
149  distance_coherence(new DistanceCoherence<PointT>);
150  coherence->addPointCoherence(distance_coherence);
151 
152  //add HSV coherence
153  if (use_hsv) {
154  boost::shared_ptr<HSVColorCoherence<PointT> > hsv_color_coherence
155  = boost::shared_ptr<HSVColorCoherence<PointT> >(new HSVColorCoherence<PointT>());
156  coherence->addPointCoherence(hsv_color_coherence);
157  }
158 
160  (new pcl::search::Octree<PointT>(octree_resolution));
161  //boost::shared_ptr<pcl::search::KdTree<PointT> > search(new pcl::search::KdTree<PointT>());
162  coherence->setSearchMethod(search);
163  double max_distance;
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);
168 
169  //Set publish setting
170  particle_publisher_ = pnh_->advertise<sensor_msgs::PointCloud2>(
171  "particle", 1);
172  track_result_publisher_ = pnh_->advertise<sensor_msgs::PointCloud2>(
173  "track_result", 1);
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);
194  //Set subscribe setting
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(
205  boost::bind(
206  &ParticleFilterTracking::cloud_change_cb,
207  this, _1, _2));
208  }
209  else {
210  sub_ = pnh_->subscribe("input", 1, &ParticleFilterTracking::cloud_cb,this);
211  }
212  if (align_box_) {
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(
218  boost::bind(
219  &ParticleFilterTracking::renew_model_with_box_topic_cb,
220  this, _1, _2));
221  }
222  else {
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);
227  }
228 
229  pnh_->param("marker_to_pointcloud_sampling_nums", marker_to_pointcloud_sampling_nums_, 10000);
230  renew_model_srv_
231  = pnh_->advertiseService(
232  "renew_model", &ParticleFilterTracking::renew_model_cb, this);
233 
234  onInitPostProcess();
235  }
236 
237  void ParticleFilterTracking::config_callback(Config &config, uint32_t level)
238  {
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_)
260  {
261  NODELET_INFO("update tracker parameter");
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_);
269  }
270  }
271 
272  //Publish the current particles
273  void ParticleFilterTracking::publish_particles()
274  {
275  PointCloudStatePtr particles = tracker_get_particles();
276  if (particles && new_cloud_ && particle_publisher_.getNumSubscribers()) {
277  //Set pointCloud with particle's points
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++)
281  {
282  pcl::PointXYZ point;
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);
287  }
288  //publish particle_cloud
289  sensor_msgs::PointCloud2 particle_pointcloud2;
290  pcl::toROSMsg(*particle_cloud, particle_pointcloud2);
291  particle_pointcloud2.header.frame_id = reference_frame_id();
292  particle_pointcloud2.header.stamp = stamp_;
293  particle_publisher_.publish(particle_pointcloud2);
294  }
295  }
296  //Publish model reference point cloud
297  void ParticleFilterTracking::publish_result()
298  {
299  ParticleXYZRPY result = tracker_get_result();
300  Eigen::Affine3f transformation = tracker_to_eigen_matrix(result);
301 
302  //Publisher object transformation
303  tf::Transform tfTransformation;
304  tf::transformEigenToTF((Eigen::Affine3d) transformation, tfTransformation);
305 
306  if (!not_publish_tf_) {
307  static tf::TransformBroadcaster tfBroadcaster;
308  tfBroadcaster.sendTransform(tf::StampedTransform(
309  tfTransformation, stamp_,
310  reference_frame_id(), track_target_name_));
311  }
312  //Publish Pose
313  geometry_msgs::PoseStamped result_pose_stamped;
314  result_pose_stamped.header.frame_id = reference_frame_id();
315  result_pose_stamped.header.stamp = stamp_;
317  tf::poseTFToMsg(tfTransformation, result_pose_stamped.pose);
318  pose_stamped_publisher_.publish(result_pose_stamped);
319  //Publish model reference point cloud
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;
325  pcl::toROSMsg(*result_cloud, result_pointcloud2);
326  result_pointcloud2.header.frame_id = reference_frame_id();
327  result_pointcloud2.header.stamp = stamp_;
328  track_result_publisher_.publish(result_pointcloud2);
329 
330  if (counter_ > 0) { // publish velocity
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);
353  }
354 
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_;
369  ++counter_;
370  }
371 
372  std::string ParticleFilterTracking::reference_frame_id()
373  {
374  if (base_frame_id_.compare("NONE") == 0) {
375  return frame_id_;
376  }
377  else {
378  return base_frame_id_;
379  }
380  }
381 
382  void ParticleFilterTracking::reset_tracking_target_model(
383  const pcl::PointCloud<PointT>::ConstPtr &recieved_target_cloud)
384  {
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);
390 
391  if (base_frame_id_.compare("NONE") != 0) {
392  tf::Transform transform_result
393  = change_pointcloud_frame(new_target_cloud);
394  reference_transform_ = transform_result * reference_transform_;;
395  }
396 
397  if (!recieved_target_cloud->points.empty()) {
398  //prepare the model of tracker's target
399  Eigen::Affine3f trans = Eigen::Affine3f::Identity();
400  pcl::PointCloud<PointT>::Ptr transed_ref(new pcl::PointCloud<PointT>);
401  if (!align_box_) {
402  if (!not_use_reference_centroid_) {
403  Eigen::Vector4f c;
404  pcl::compute3DCentroid(*new_target_cloud, c);
405  trans.translation().matrix() = Eigen::Vector3f(c[0], c[1], c[2]);
406  }
407  }
408  else {
409  Eigen::Affine3d trans_3d = Eigen::Affine3d::Identity();
410  tf::transformTFToEigen(reference_transform_, trans_3d);
411  trans = (Eigen::Affine3f) trans_3d;
412  }
413  pcl::transformPointCloud(*new_target_cloud, *transed_ref, trans.inverse());
414  //set reference model and trans
415  {
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);
421  }
422  track_target_set_ = true;
423  NODELET_INFO("RESET TARGET MODEL");
424  }
425  else {
426  track_target_set_ = false;
427  NODELET_ERROR("TARGET MODEL POINTS SIZE IS 0 !! Stop TRACKING");
428  }
429  }
430 
431  tf::Transform ParticleFilterTracking::change_pointcloud_frame(
432  pcl::PointCloud<PointT>::Ptr cloud)
433  {
434  tf::Transform tfTransformation;
435  tf::StampedTransform tfTransformationStamped;
437  try {
438  listener_->waitForTransform(base_frame_id_, frame_id_, now,
439  ros::Duration(2.0));
440  listener_->lookupTransform(base_frame_id_, frame_id_, now,
441  tfTransformationStamped);
442  //frame_id_ = base_frame_id_;
443  }
444  catch(tf::TransformException ex) {
445  NODELET_ERROR("%s",ex.what());
446  tfTransformation = tf::Transform(tf::Quaternion(0, 0, 0, 1));
447  }
448  tfTransformation = tf::Transform(tfTransformationStamped.getBasis(),
449  tfTransformationStamped.getOrigin());
450  Eigen::Affine3f trans; Eigen::Affine3d trans_3d;
451  tf::transformTFToEigen(tfTransformation, trans_3d);
452  trans = (Eigen::Affine3f) trans_3d;
453  pcl::transformPointCloud(*cloud, *cloud, trans);
454  return tfTransformation;
455  }
456 
457  void ParticleFilterTracking::publish_tracker_status(const std_msgs::Header& header,
458  const bool is_tracking)
459  {
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);
464  }
465 
466  void ParticleFilterTracking::cloud_change_cb(const sensor_msgs::PointCloud2::ConstPtr &pc_msg,
467  const sensor_msgs::PointCloud2::ConstPtr &change_cloud_msg)
468  {
469  if (no_move_buffer_.isAllTrueFilled()) {
471  = timer_.reporter(pub_latest_time_, pub_average_time_);
472  // change change_cloud
473  pcl::PointCloud<pcl::PointXYZRGB>::Ptr change_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
474  pcl::fromROSMsg(*change_cloud_msg, *change_cloud);
475  if (change_cloud->points.size() == 0) {
476  stamp_ = pc_msg->header.stamp;
477  publish_result();
478  publish_tracker_status(pc_msg->header, false);
479  return;
480  }
481  pcl::KdTreeFLANN<pcl::PointXYZRGB> kdtree;
482  kdtree.setInputCloud(change_cloud);
483  std::vector<int> k_indices;
484  std::vector<float> k_sqr_distances;
485  pcl::PointXYZRGB p;
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) {
490  NODELET_INFO("change detection triggered!");
491  // there is near pointcloud
492  cloud_cb(*pc_msg);
493  r.setIsEnabled(false);
494  no_move_buffer_.clear();
495  publish_tracker_status(pc_msg->header, true);
496  }
497  else {
498  // publish previous result
499  stamp_ = pc_msg->header.stamp;
500  publish_result();
501  publish_tracker_status(pc_msg->header, false);
502  }
503  }
504  else {
505  publish_tracker_status(pc_msg->header, true);
506  cloud_cb(*pc_msg);
507  }
508  }
509 
510  //OpenNI Grabber's cloud Callback function
511  void ParticleFilterTracking::cloud_cb(const sensor_msgs::PointCloud2 &pc)
512  {
513  if (track_target_set_) {
514  pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
515  frame_id_ = pc.header.frame_id;
516  stamp_ = pc.header.stamp;
517  std::vector<int> indices;
518  pcl::fromROSMsg(pc, *cloud);
519  cloud->is_dense = false;
520  {
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);
526  }
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_);
532  tracker_compute();
533  publish_particles();
534  publish_result();
535  }
536  new_cloud_ = true;
537  }
538  }
539  }
540 
541  void ParticleFilterTracking::renew_model_topic_cb(
542  const sensor_msgs::PointCloud2 &pc)
543  {
544  pcl::PointCloud<PointT>::Ptr new_target_cloud
545  (new pcl::PointCloud<PointT>());
546  pcl::fromROSMsg(pc, *new_target_cloud);
547  frame_id_ = pc.header.frame_id;
548  reset_tracking_target_model(new_target_cloud);
549  }
550 
551  void ParticleFilterTracking::renew_model_with_marker_topic_cb(const visualization_msgs::Marker &marker)
552  {
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_,
558  *cloud
559  );
560 
561  Eigen::Affine3f trans;
562  tf::poseMsgToEigen(marker.pose, trans);
563  pcl::transformPointCloud(*cloud, *cloud, trans);
564 
565  frame_id_ = marker.header.frame_id;
566  reset_tracking_target_model(cloud);
567  }else{
568  ROS_ERROR(" Marker Models type is not TRIANGLE ");
569  ROS_ERROR(" OR ");
570  ROS_ERROR(" Marker Points is empty ");
571  }
572  }
573 
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)
577  {
578  pcl::PointCloud<PointT>::Ptr new_target_cloud
579  (new pcl::PointCloud<PointT>());
580  pcl::fromROSMsg(*pc_ptr, *new_target_cloud);
581  frame_id_ = pc_ptr->header.frame_id;
582  tf::poseMsgToTF(bb_ptr->pose, reference_transform_);
583  reset_tracking_target_model(new_target_cloud);
584  }
585 
586  bool ParticleFilterTracking::renew_model_cb(
587  jsk_recognition_msgs::SetPointCloud2::Request &req,
588  jsk_recognition_msgs::SetPointCloud2::Response &res)
589  {
590  pcl::PointCloud<PointT>::Ptr new_target_cloud(new pcl::PointCloud<PointT>());
591  pcl::fromROSMsg(req.cloud, *new_target_cloud);
592  frame_id_ = req.cloud.header.frame_id;
593  reset_tracking_target_model(new_target_cloud);
594  return true;
595  }
596 
597  void ParticleFilterTracking::tracker_set_trans(
598  const Eigen::Affine3f& trans)
599  {
600  Eigen::Vector3f pos = trans.translation();
601  NODELET_INFO("trans: [%f, %f, %f]", pos[0], pos[1], pos[2]);
602  if (reversed_) {
603  reversed_tracker_->setTrans(trans);
604  }
605  else {
606  tracker_->setTrans(trans);
607  }
608  }
609 
610  void ParticleFilterTracking::tracker_set_step_noise_covariance(
611  const std::vector<double>& covariance)
612  {
613  if (reversed_) {
614  reversed_tracker_->setStepNoiseCovariance(covariance);
615  }
616  else {
617  tracker_->setStepNoiseCovariance(covariance);
618  }
619  }
620 
621  void ParticleFilterTracking::tracker_set_initial_noise_covariance(
622  const std::vector<double>& covariance)
623  {
624  if (reversed_) {
625  reversed_tracker_->setInitialNoiseCovariance(covariance);
626  }
627  else {
628  tracker_->setInitialNoiseCovariance(covariance);
629  }
630  }
631 
632  void ParticleFilterTracking::tracker_set_initial_noise_mean(
633  const std::vector<double>& mean)
634  {
635  if (reversed_) {
636  reversed_tracker_->setInitialNoiseMean(mean);
637  }
638  else {
639  tracker_->setInitialNoiseMean(mean);
640  }
641  }
642 
643  void ParticleFilterTracking::tracker_set_iteration_num(const int num)
644  {
645  if (reversed_) {
646  reversed_tracker_->setIterationNum(num);
647  }
648  else {
649  tracker_->setIterationNum(num);
650  }
651  }
652 
653  void ParticleFilterTracking::tracker_set_particle_num(const int num)
654  {
655  if (reversed_) {
656  reversed_tracker_->setParticleNum(num);
657  }
658  else {
659  tracker_->setParticleNum(num);
660  }
661  }
662 
663  void ParticleFilterTracking::tracker_set_resample_likelihood_thr(double thr)
664  {
665  if (reversed_) {
666  reversed_tracker_->setResampleLikelihoodThr(thr);
667  }
668  else {
669  tracker_->setResampleLikelihoodThr(thr);
670  }
671  }
672 
673  void ParticleFilterTracking::tracker_set_use_normal(bool use_normal)
674  {
675  if (reversed_) {
676  reversed_tracker_->setUseNormal(use_normal);
677  }
678  else {
679  tracker_->setUseNormal(use_normal);
680  }
681  }
682 
683  void ParticleFilterTracking::tracker_set_cloud_coherence(
684  ApproxNearestPairPointCloudCoherence<PointT>::Ptr coherence)
685  {
686  if (reversed_) {
687  reversed_tracker_->setCloudCoherence(coherence);
688  }
689  else {
690  tracker_->setCloudCoherence(coherence);
691  }
692  }
693 
694  void ParticleFilterTracking::tracker_set_maximum_particle_num(int num)
695  {
696  if (!reversed_) {
697  tracker_->setMaximumParticleNum(num);
698  }
699  }
700 
701  void ParticleFilterTracking::tracker_set_delta(double delta)
702  {
703  if (!reversed_) {
704  tracker_->setDelta(delta);
705  }
706  }
707 
708  void ParticleFilterTracking::tracker_set_epsilon(double epsilon)
709  {
710  if (!reversed_) {
711  tracker_->setEpsilon(epsilon);
712  }
713  }
714 
715  void ParticleFilterTracking::tracker_set_bin_size(
716  const ParticleXYZRPY bin_size)
717  {
718  if (!reversed_) {
719  tracker_->setBinSize(bin_size);
720  }
721  }
722 
724  ParticleFilterTracking::tracker_get_particles()
725  {
726  if (!reversed_) {
727  return tracker_->getParticles();
728  }
729  else {
730  return reversed_tracker_->getParticles();
731  }
732  }
733 
734  ParticleXYZRPY ParticleFilterTracking::tracker_get_result()
735  {
736  if (!reversed_) {
737  return tracker_->getResult();
738  }
739  else {
740  return reversed_tracker_->getResult();
741  }
742  }
743 
744  Eigen::Affine3f ParticleFilterTracking::tracker_to_eigen_matrix(
745  const ParticleXYZRPY& result)
746  {
747  if (!reversed_) {
748  return tracker_->toEigenMatrix(result);
749  }
750  else {
751  return reversed_tracker_->toEigenMatrix(result);
752  }
753  }
754 
755  pcl::PointCloud<ParticleFilterTracking::PointT>::ConstPtr
756  ParticleFilterTracking::tracker_get_reference_cloud()
757  {
758  if (!reversed_) {
759  return tracker_->getReferenceCloud();
760  }
761  else {
762  return reversed_tracker_->getReferenceCloud();
763  }
764  }
765 
766  void ParticleFilterTracking::tracker_set_reference_cloud(
767  pcl::PointCloud<PointT>::Ptr ref)
768  {
769  if (!reversed_) {
770  tracker_->setReferenceCloud(ref);
771  }
772  else {
773  reversed_tracker_->setReferenceCloud(ref);
774  }
775  counter_ = 0;
776  no_move_buffer_.clear();
777  }
778 
779  void ParticleFilterTracking::tracker_reset_tracking()
780  {
781  if (!reversed_) {
782  tracker_->resetTracking();
783  }
784  else {
785  reversed_tracker_->resetTracking();
786  }
787  }
788 
789  void ParticleFilterTracking::tracker_set_input_cloud(
790  pcl::PointCloud<PointT>::Ptr input)
791  {
792  if (!reversed_) {
793  tracker_->setInputCloud(input);
794  }
795  else {
796  reversed_tracker_->setInputCloud(input);
797  }
798  }
799  void ParticleFilterTracking::tracker_compute()
800  {
801  if (!reversed_) {
802  tracker_->compute();
803  }
804  else {
805  reversed_tracker_->compute();
806  }
807  }
808 }
809 
ParticleFilterTracker< PointT, ParticleXYZRPY >::PointCloudStatePtr PointCloudStatePtr
void transformEigenToTF(const Eigen::Affine3d &e, tf::Transform &t)
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
def cloud_cb(cloud)
#define NODELET_ERROR(...)
pos
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
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)
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
q
result
void markerMsgToPointCloud(const visualization_msgs::Marker &input_marker, int sample_nums, pcl::PointCloud< PointT > &output_cloud)
GLfloat angle
#define ROS_INFO(...)
void sendTransform(const StampedTransform &transform)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
double x
#define NODELET_INFO(...)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
p
static Time now()
c
std::string frame_id_
static tf::TransformListener * getInstance()
cloud
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
#define ROS_ERROR(...)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47