particle_filter_tracking.h
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Yuto Inagaki and JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #ifndef JSK_PCL_ROS_PARTICLE_FILTER_TRACKING_H_
00037 #define JSK_PCL_ROS_PARTICLE_FILTER_TRACKING_H_
00038 
00039 // ros
00040 #include <ros/ros.h>
00041 #include <ros/names.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <visualization_msgs/Marker.h>
00044 #include <tf/transform_broadcaster.h>
00045 #include <tf_conversions/tf_eigen.h>
00046 #include <jsk_pcl_ros/pcl_conversion_util.h>
00047 // pcl
00048 #include <pcl_ros/pcl_nodelet.h>
00049 #include <pcl/point_types.h>
00050 #include <pcl/common/centroid.h>
00051 #include <pcl/common/transforms.h>
00052 
00053 #include <pcl/search/pcl_search.h>
00054 #include <pcl/common/transforms.h>
00055 
00056 #include <pcl/tracking/tracking.h>
00057 #include <pcl/tracking/particle_filter.h>
00058 #include <pcl/tracking/kld_adaptive_particle_filter_omp.h>
00059 #include <pcl/tracking/particle_filter_omp.h>
00060 #include <pcl/tracking/coherence.h>
00061 #include <pcl/tracking/distance_coherence.h>
00062 #include <pcl/tracking/hsv_color_coherence.h>
00063 #include <pcl/tracking/approx_nearest_pair_point_cloud_coherence.h>
00064 #include <pcl/tracking/nearest_pair_point_cloud_coherence.h>
00065 
00066 #include <jsk_pcl_ros/SetPointCloud2.h>
00067 #include <jsk_pcl_ros/ParticleFilterTrackingConfig.h>
00068 #include <jsk_recognition_msgs/BoundingBox.h>
00069 
00070 #include <dynamic_reconfigure/server.h>
00071 #include <message_filters/subscriber.h>
00072 #include <message_filters/time_synchronizer.h>
00073 #include <message_filters/synchronizer.h>
00074 
00075 #include <pcl/tracking/particle_filter.h>
00076 #include <pcl/tracking/impl/tracking.hpp>
00077 #include <pcl/tracking/impl/particle_filter.hpp>
00078 
00079 // This namespace follows PCL coding style
00080 namespace pcl
00081 {
00082   namespace tracking
00083   {
00084     // hack pcl::tracking
00085     // original tracker assumes that the number of reference points is smaller
00086     // than the number of input.
00087     // ReversedParticleFilterTracker assumues that the number of reference
00088     // points is greater than the number of input.
00089     // So we need to change:
00090     //   1) transform input pointcloud during weight phase with inverse of each particles
00091     //      particle should keep meaning the pose of reference for simplicity.
00092     template <typename PointInT, typename StateT>
00093     class ReversedParticleFilterTracker: public ParticleFilterTracker<PointInT, StateT>
00094     {
00095     public:
00096       using Tracker<PointInT, StateT>::tracker_name_;
00097       using Tracker<PointInT, StateT>::search_;
00098       using Tracker<PointInT, StateT>::input_;
00099       using Tracker<PointInT, StateT>::indices_;
00100       using Tracker<PointInT, StateT>::getClassName;
00101       using ParticleFilterTracker<PointInT, StateT>::particles_;
00102       using ParticleFilterTracker<PointInT, StateT>::change_detector_;
00103       using ParticleFilterTracker<PointInT, StateT>::change_counter_;
00104       using ParticleFilterTracker<PointInT, StateT>::change_detector_resolution_;
00105       using ParticleFilterTracker<PointInT, StateT>::change_detector_interval_;
00106       using ParticleFilterTracker<PointInT, StateT>::use_change_detector_;
00107       using ParticleFilterTracker<PointInT, StateT>::alpha_;
00108       using ParticleFilterTracker<PointInT, StateT>::changed_;
00109       using ParticleFilterTracker<PointInT, StateT>::ref_;
00110       using ParticleFilterTracker<PointInT, StateT>::coherence_;
00111       using ParticleFilterTracker<PointInT, StateT>::use_normal_;
00112       using ParticleFilterTracker<PointInT, StateT>::particle_num_;
00113       using ParticleFilterTracker<PointInT, StateT>::change_detector_filter_;
00114       using ParticleFilterTracker<PointInT, StateT>::transed_reference_vector_;
00115       //using ParticleFilterTracker<PointInT, StateT>::calcLikelihood;
00116       using ParticleFilterTracker<PointInT, StateT>::normalizeWeight;
00117       using ParticleFilterTracker<PointInT, StateT>::initParticles;
00118       using ParticleFilterTracker<PointInT, StateT>::normalizeParticleWeight;
00119       using ParticleFilterTracker<PointInT, StateT>::calcBoundingBox;
00120 
00121       typedef Tracker<PointInT, StateT> BaseClass;
00122       
00123       typedef typename Tracker<PointInT, StateT>::PointCloudIn PointCloudIn;
00124       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00125       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00126 
00127       typedef typename Tracker<PointInT, StateT>::PointCloudState PointCloudState;
00128       typedef typename PointCloudState::Ptr PointCloudStatePtr;
00129       typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr;
00130 
00131       typedef PointCoherence<PointInT> Coherence;
00132       typedef boost::shared_ptr< Coherence > CoherencePtr;
00133       typedef boost::shared_ptr< const Coherence > CoherenceConstPtr;
00134 
00135       typedef PointCloudCoherence<PointInT> CloudCoherence;
00136       typedef boost::shared_ptr< CloudCoherence > CloudCoherencePtr;
00137       typedef boost::shared_ptr< const CloudCoherence > CloudCoherenceConstPtr;
00138 
00139       // call initCompute only if reference pointcloud is updated
00140       inline void
00141       setReferenceCloud (const PointCloudInConstPtr &ref)
00142       {
00143         ref_ = ref;
00144         if (coherence_) {
00145           coherence_->setTargetCloud (ref_);
00146           coherence_->initCompute ();
00147         }
00148         else {
00149           PCL_ERROR("coherence_ is not yet available!");
00150         }
00151       }
00152 
00153 
00154     protected:
00155       std::vector<PointCloudInPtr> transed_input_vector_;
00156       
00157       virtual bool initCompute()
00158       {
00159         if (!Tracker<PointInT, StateT>::initCompute ())
00160         {
00161           PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00162           return (false);
00163         }
00164         
00165         // allocate pointclouds in transed_input_vector_ instead of transed_reference_vector_
00166         if (transed_input_vector_.empty ())
00167         {
00168           //std::cout << "initializing " << particle_num_ << " input" << std::endl;
00169           // only one time allocation
00170           transed_input_vector_.resize (particle_num_ + 1);
00171           for (int i = 0; i < particle_num_ + 1; i++)
00172           {
00173             transed_input_vector_[i] = PointCloudInPtr (new PointCloudIn ());
00174           }
00175         }
00176 
00177         // set reference instead of input
00178         // if (coherence_) {
00179         //   coherence_->setTargetCloud (ref_);
00180         // }
00181           
00182         if (!change_detector_)
00183           change_detector_ = boost::shared_ptr<pcl::octree::OctreePointCloudChangeDetector<PointInT> >(new pcl::octree::OctreePointCloudChangeDetector<PointInT> (change_detector_resolution_));
00184           
00185         if (!particles_ || particles_->points.empty ())
00186           initParticles (true);
00187         return (true);
00188       }
00189 
00190       // only is computation without normal supported
00191       void computeTransformedPointCloudWithoutNormal
00192       (const StateT& hypothesis, PointCloudIn &cloud)
00193         {
00194           const Eigen::Affine3f trans = this->toEigenMatrix (hypothesis);
00195           // destructively assigns to cloud
00196           pcl::transformPointCloud<PointInT> (*input_, cloud, trans);
00197         }
00198 
00199       
00200       virtual void weight()
00201       {
00202         changed_ = true;
00203         if (!use_normal_)
00204         {
00205           for (size_t i = 0; i < particles_->points.size (); i++)
00206           {
00207             //std::cout << "processing " << i << " particle: " << particles_->points[i].weight << std::endl;
00208             // compute `inverse` of particle
00209             StateT inverse_particle;
00210             Eigen::Affine3f trans = particles_->points[i].toEigenMatrix();
00211             Eigen::Affine3f inverse_trans = trans.inverse();
00212             inverse_particle = StateT::toState(inverse_trans);
00213             computeTransformedPointCloudWithoutNormal (inverse_particle, *transed_input_vector_[i]);
00214             IndicesPtr indices;
00215             coherence_->compute (transed_input_vector_[i], indices, particles_->points[i].weight);
00216           }
00217         }
00218         else
00219         {
00220           for (size_t i = 0; i < particles_->points.size (); i++)
00221           {
00222             StateT inverse_particle;
00223             Eigen::Affine3f trans = particles_->points[i].toEigenMatrix();
00224             Eigen::Affine3f inverse_trans = trans.inverse();
00225             inverse_particle = StateT::toState(inverse_trans);
00226             IndicesPtr indices (new std::vector<int>);
00227             this->computeTransformedPointCloudWithNormal (inverse_particle, *indices, *transed_input_vector_[i]);
00228             coherence_->compute (transed_input_vector_[i], indices, particles_->points[i].weight);
00229           }
00230         }
00231   
00232         normalizeWeight ();
00233         
00234       }
00235     private:
00236     };
00237     
00238     template <typename PointInT, typename StateT>
00239     class ReversedParticleFilterOMPTracker: public ReversedParticleFilterTracker<PointInT, StateT>
00240     {
00241     public:
00242       using Tracker<PointInT, StateT>::tracker_name_;
00243       using Tracker<PointInT, StateT>::search_;
00244       using Tracker<PointInT, StateT>::input_;
00245       using Tracker<PointInT, StateT>::indices_;
00246       using Tracker<PointInT, StateT>::getClassName;
00247       using ParticleFilterTracker<PointInT, StateT>::particles_;
00248       using ParticleFilterTracker<PointInT, StateT>::change_detector_;
00249       using ParticleFilterTracker<PointInT, StateT>::change_counter_;
00250       using ParticleFilterTracker<PointInT, StateT>::change_detector_resolution_;
00251       using ParticleFilterTracker<PointInT, StateT>::change_detector_interval_;
00252       using ParticleFilterTracker<PointInT, StateT>::use_change_detector_;
00253       using ParticleFilterTracker<PointInT, StateT>::alpha_;
00254       using ParticleFilterTracker<PointInT, StateT>::changed_;
00255       using ParticleFilterTracker<PointInT, StateT>::ref_;
00256       using ParticleFilterTracker<PointInT, StateT>::coherence_;
00257       using ParticleFilterTracker<PointInT, StateT>::use_normal_;
00258       using ParticleFilterTracker<PointInT, StateT>::particle_num_;
00259       using ParticleFilterTracker<PointInT, StateT>::change_detector_filter_;
00260       using ParticleFilterTracker<PointInT, StateT>::transed_reference_vector_;
00261       //using ParticleFilterTracker<PointInT, StateT>::calcLikelihood;
00262       using ParticleFilterTracker<PointInT, StateT>::normalizeWeight;
00263       using ParticleFilterTracker<PointInT, StateT>::initParticles;
00264       using ParticleFilterTracker<PointInT, StateT>::normalizeParticleWeight;
00265       using ParticleFilterTracker<PointInT, StateT>::calcBoundingBox;
00266 
00267       typedef Tracker<PointInT, StateT> BaseClass;
00268       
00269       typedef typename Tracker<PointInT, StateT>::PointCloudIn PointCloudIn;
00270       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00271       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00272 
00273       typedef typename Tracker<PointInT, StateT>::PointCloudState PointCloudState;
00274       typedef typename PointCloudState::Ptr PointCloudStatePtr;
00275       typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr;
00276 
00277       typedef PointCoherence<PointInT> Coherence;
00278       typedef boost::shared_ptr< Coherence > CoherencePtr;
00279       typedef boost::shared_ptr< const Coherence > CoherenceConstPtr;
00280 
00281       typedef PointCloudCoherence<PointInT> CloudCoherence;
00282       typedef boost::shared_ptr< CloudCoherence > CloudCoherencePtr;
00283       typedef boost::shared_ptr< const CloudCoherence > CloudCoherenceConstPtr;
00284       using ReversedParticleFilterTracker<PointInT, StateT>::transed_input_vector_;
00285     protected:
00286 
00287       unsigned int threads_;
00288       
00289     public:
00290       ReversedParticleFilterOMPTracker (unsigned int nr_threads = 0)
00291         : ReversedParticleFilterTracker<PointInT, StateT> ()
00292         , threads_ (nr_threads)
00293       {
00294         tracker_name_ = "ReversedParticleFilterOMPTracker";
00295       }
00296 
00297       inline void
00298       setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00299 
00300     protected:
00301       
00302       virtual void weight()
00303       {
00304         changed_ = true;
00305         if (!use_normal_)
00306         {
00307 #ifdef _OPENMP
00308 #pragma omp parallel for num_threads(threads_)
00309 #endif
00310           for (size_t i = 0; i < particles_->points.size (); i++)
00311           {
00312             //std::cout << "processing " << i << " particle: " << particles_->points[i].weight << std::endl;
00313             // compute `inverse` of particle
00314             StateT inverse_particle;
00315             Eigen::Affine3f trans = particles_->points[i].toEigenMatrix();
00316             Eigen::Affine3f inverse_trans = trans.inverse();
00317             inverse_particle = StateT::toState(inverse_trans);
00318             this->computeTransformedPointCloudWithoutNormal (inverse_particle, *transed_input_vector_[i]);
00319             //computeTransformedPointCloudWithoutNormal (particles_->points[i], *transed_input_vector_[i]);
00320             IndicesPtr indices;
00321             coherence_->compute (transed_input_vector_[i], indices, particles_->points[i].weight);
00322             //std::cout << "processing " << i << " particle: " << particles_->points[i].weight << std::endl;
00323             //std::cout << inverse_particle << std::endl;
00324           }
00325         }
00326         else
00327         {
00328 #ifdef _OPENMP
00329 #pragma omp parallel for num_threads(threads_)
00330 #endif
00331           for (size_t i = 0; i < particles_->points.size (); i++)
00332           {
00333             StateT inverse_particle;
00334             Eigen::Affine3f trans = particles_->points[i].toEigenMatrix();
00335             Eigen::Affine3f inverse_trans = trans.inverse();
00336             inverse_particle = StateT::toState(inverse_trans);
00337             IndicesPtr indices (new std::vector<int>);
00338             this->computeTransformedPointCloudWithNormal (inverse_particle, *indices, *transed_input_vector_[i]);
00339             coherence_->compute (transed_input_vector_[i], indices, particles_->points[i].weight);
00340           }
00341         }
00342   
00343         normalizeWeight ();
00344         for (size_t i = 0; i < particles_->points.size (); i++)
00345         {
00346           //std::cout << "normalized " << i << " particle: " << particles_->points[i].weight << std::endl;
00347         }
00348       }
00349     private:
00350     };
00351 
00352     template <typename PointInT>
00353     class CachedApproxNearestPairPointCloudCoherence: public ApproxNearestPairPointCloudCoherence<PointInT>
00354     {
00355     public:
00356       typedef typename ApproxNearestPairPointCloudCoherence<PointInT>::PointCoherencePtr PointCoherencePtr;
00357       typedef typename ApproxNearestPairPointCloudCoherence<PointInT>::PointCloudInConstPtr PointCloudInConstPtr;
00358       //using NearestPairPointCloudCoherence<PointInT>::search_;
00359       using ApproxNearestPairPointCloudCoherence<PointInT>::maximum_distance_;
00360       using ApproxNearestPairPointCloudCoherence<PointInT>::target_input_;
00361       using ApproxNearestPairPointCloudCoherence<PointInT>::point_coherences_;
00362       using ApproxNearestPairPointCloudCoherence<PointInT>::coherence_name_;
00363       using ApproxNearestPairPointCloudCoherence<PointInT>::new_target_;
00364       using ApproxNearestPairPointCloudCoherence<PointInT>::getClassName;
00365       using ApproxNearestPairPointCloudCoherence<PointInT>::search_;
00366       
00368       CachedApproxNearestPairPointCloudCoherence (const double bin_x,
00369                                                   const double bin_y,
00370                                                   const double bin_z) : 
00371         ApproxNearestPairPointCloudCoherence<PointInT> (),
00372         bin_x_(bin_x), bin_y_(bin_y), bin_z_(bin_z)
00373       {
00374         coherence_name_ = "CachedApproxNearestPairPointCloudCoherence";
00375       }
00376       
00377     protected:
00379       virtual void
00380       computeCoherence (const PointCloudInConstPtr &cloud, const IndicesConstPtr &indices, float &w_j)
00381       {
00382         boost::mutex::scoped_lock lock(cache_mutex_);
00383         double val = 0.0;
00384         //for (size_t i = 0; i < indices->size (); i++)
00385         for (size_t i = 0; i < cloud->points.size (); i++)
00386         {
00387           PointInT input_point = cloud->points[i];
00388           int xi, yi, zi;
00389           computeBin(input_point.getVector3fMap(), xi, yi, zi);
00390           int k_index;
00391           if (checkCache(xi, yi, zi)) {
00392             k_index = getCachedIndex(xi, yi, zi);
00393           }
00394           else {
00395             float k_distance = 0.0; // dummy
00396             search_->approxNearestSearch(input_point, k_index, k_distance);
00397             registerCache(k_index, xi, yi, zi);
00398           }
00399           PointInT target_point = target_input_->points[k_index];
00400           float dist = (target_point.getVector3fMap() - input_point.getVector3fMap()).norm();
00401           if (dist < maximum_distance_)
00402           {
00403             double coherence_val = 1.0;
00404             for (size_t i = 0; i < point_coherences_.size (); i++)
00405             {
00406               PointCoherencePtr coherence = point_coherences_[i];  
00407               double w = coherence->compute (input_point, target_point);
00408               coherence_val *= w;
00409             }
00410             val += coherence_val;
00411           }
00412         }
00413         w_j = - static_cast<float> (val);
00414         //ROS_INFO("hit: %d", counter);
00415       }
00416 
00417       virtual void computeBin(
00418         const Eigen::Vector3f& p, int& xi, int& yi, int& zi)
00419       {
00420         xi = (int)(p[0]/bin_x_);
00421         yi = (int)(p[1]/bin_y_);
00422         zi = (int)(p[2]/bin_z_);
00423       }
00424       
00425       virtual void registerCache(int k_index, int bin_x, int bin_y, int bin_z)
00426       {
00427         //boost::mutex::scoped_lock lock(cache_mutex_);
00428         if (cache_.find(bin_x) == cache_.end()) {
00429           cache_[bin_x] = std::map<int, std::map<int, int> >();
00430         }
00431         if (cache_[bin_x].find(bin_y) == cache_[bin_x].end()) {
00432           cache_[bin_x][bin_y] = std::map<int, int>();
00433         }
00434         cache_[bin_x][bin_y][bin_z] = k_index;
00435       }
00436       
00437       virtual int getCachedIndex(int bin_x, int bin_y, int bin_z)
00438       {
00439         //boost::mutex::scoped_lock lock(cache_mutex_);
00440         return cache_[bin_x][bin_y][bin_z];
00441       }
00442       
00443       virtual bool checkCache(int bin_x, int bin_y, int bin_z)
00444       {
00445         //boost::mutex::scoped_lock lock(cache_mutex_);
00446         if (cache_.find(bin_x) == cache_.end()) {
00447           return false;
00448         }
00449         else {
00450           if (cache_[bin_x].find(bin_y) == cache_[bin_x].end()) {
00451             return false;
00452           }
00453           else {
00454             if (cache_[bin_x][bin_y].find(bin_z) == cache_[bin_x][bin_y].end()) {
00455               return false;
00456             }
00457             else {
00458               return true;
00459             }
00460           }
00461         }
00462       }
00463       
00464       virtual void clearCache()
00465       {
00466         boost::mutex::scoped_lock lock(cache_mutex_);
00467         cache_ = CacheMap();
00468       }
00469 
00470       virtual bool initCompute()
00471       {
00472         if (!ApproxNearestPairPointCloudCoherence<PointInT>::initCompute ())
00473         {
00474           PCL_ERROR ("[pcl::%s::initCompute] PointCloudCoherence::Init failed.\n", getClassName ().c_str ());
00475           //deinitCompute ();
00476           return false;
00477         }
00478         clearCache();
00479         return true;
00480       }
00481       
00482       //typename boost::shared_ptr<pcl::search::Octree<PointInT> > search_;
00483       typedef std::map<int, std::map<int, std::map<int, int> > > CacheMap;
00484       CacheMap cache_;
00485       boost::mutex cache_mutex_;
00486       double bin_x_;
00487       double bin_y_;
00488       double bin_z_;
00489       
00490     };
00491 
00492     
00493     template <typename PointInT>
00494     class OrganizedNearestPairPointCloudCoherence: public NearestPairPointCloudCoherence<PointInT>
00495     {
00496     public:
00497       using NearestPairPointCloudCoherence<PointInT>::target_input_;
00498       using NearestPairPointCloudCoherence<PointInT>::new_target_;
00499       using NearestPairPointCloudCoherence<PointInT>::getClassName;
00500       typename boost::shared_ptr<pcl::search::OrganizedNeighbor<PointInT> > search_;
00501     protected:
00502       virtual bool initCompute ()
00503       {
00504         if (!PointCloudCoherence<PointInT>::initCompute ())
00505           {
00506             PCL_ERROR ("[pcl::%s::initCompute] PointCloudCoherence::Init failed.\n", getClassName ().c_str ());
00507             //deinitCompute ();
00508             return (false);
00509           }
00510         
00511         // initialize tree
00512         if (!search_)
00513           search_.reset (new pcl::search::OrganizedNeighbor<PointInT> (false));
00514       
00515         if (new_target_ && target_input_)
00516           {
00517             search_->setInputCloud (target_input_);
00518             if (!search_->isValid())
00519               return false;
00520             new_target_ = false;
00521           }
00522       
00523         return true;
00524       }
00525     };
00526   }  
00527 }
00528 
00529 using namespace pcl::tracking;
00530 namespace jsk_pcl_ros
00531 {
00532   class ParticleFilterTracking: public pcl_ros::PCLNodelet
00533   {
00534   public:
00535     typedef pcl::PointXYZRGB PointT;
00536     typedef ParticleFilterTrackingConfig Config;
00537     typedef message_filters::sync_policies::ExactTime<
00538       sensor_msgs::PointCloud2,
00539       jsk_recognition_msgs::BoundingBox > SyncPolicy;
00540     typedef ParticleFilterTracker<PointT, ParticleXYZRPY>::PointCloudStatePtr
00541     PointCloudStatePtr;
00542   protected:
00543     pcl::PointCloud<PointT>::Ptr cloud_pass_;
00544     pcl::PointCloud<PointT>::Ptr cloud_pass_downsampled_;
00545     pcl::PointCloud<PointT>::Ptr target_cloud_;
00546 
00547     //boost::shared_ptr<ParticleFilterTracker<PointT, ParticleXYZRPY> > tracker_;
00548     boost::shared_ptr<KLDAdaptiveParticleFilterOMPTracker<PointT, ParticleXYZRPY> > tracker_;
00549     boost::shared_ptr<ReversedParticleFilterOMPTracker<PointT, ParticleXYZRPY> > reversed_tracker_;
00550     //boost::shared_ptr<ReversedParticleFilterTracker<PointT, ParticleXYZRPY> > reversed_tracker_;
00551     boost::mutex mtx_;
00552     bool new_cloud_;
00553     bool track_target_set_;
00554     bool align_box_;
00555     bool change_frame_;
00556     std::string frame_id_;
00557     std::string base_frame_id_;
00558     std::string track_target_name_;
00559     ros::Time stamp_;
00560     tf::Transform reference_transform_;
00561 
00562     ros::Subscriber sub_;
00563     ros::Subscriber sub_update_model_;
00564     ros::Subscriber sub_update_with_marker_model_;
00565 
00566     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00567     message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> sub_box_;
00568     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00569     ros::Publisher particle_publisher_;
00570     ros::Publisher track_result_publisher_;
00571     ros::Publisher pose_stamped_publisher_;
00572     ros::ServiceServer renew_model_srv_;
00573     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00574     tf::TransformListener listener_;
00575     
00577     // parameters
00579     int max_particle_num_;
00580     double delta_;
00581     double epsilon_;
00582     int iteration_num_;
00583     double resample_likelihood_thr_;
00584     ParticleXYZRPY bin_size_;
00585     std::vector<double> default_step_covariance_;
00586     bool reversed_;
00587     bool not_use_reference_centroid_;
00588     bool not_publish_tf_;
00589     int marker_to_pointcloud_sampling_nums_;
00590     virtual void config_callback(Config &config, uint32_t level);
00591     virtual void publish_particles();
00592     virtual void publish_result();
00593     virtual std::string reference_frame_id();
00594     virtual void reset_tracking_target_model(
00595       const pcl::PointCloud<PointT>::ConstPtr &new_target_cloud);
00596     virtual tf::Transform change_pointcloud_frame(
00597       pcl::PointCloud<PointT>::Ptr cloud);
00598 
00599     virtual void cloud_cb(const sensor_msgs::PointCloud2 &pc);
00600     virtual bool renew_model_cb(
00601       jsk_pcl_ros::SetPointCloud2::Request &req,
00602       jsk_pcl_ros::SetPointCloud2::Response &response);
00603     virtual void renew_model_with_box_topic_cb(
00604       const sensor_msgs::PointCloud2::ConstPtr &pc_ptr,
00605       const jsk_recognition_msgs::BoundingBox::ConstPtr &bb_ptr);
00606     virtual void renew_model_topic_cb(const sensor_msgs::PointCloud2 &pc);
00607     virtual void renew_model_with_marker_topic_cb(const visualization_msgs::Marker &marker);
00608 
00610     // Wrap particle filter methods
00612     virtual void tracker_set_trans(const Eigen::Affine3f& trans);
00613     virtual void tracker_set_step_noise_covariance(
00614       const std::vector<double>& covariance);
00615     virtual void tracker_set_initial_noise_covariance(
00616       const std::vector<double>& covariance);
00617     virtual void tracker_set_initial_noise_mean(
00618       const std::vector<double>& mean);
00619     virtual void tracker_set_iteration_num(const int num);
00620     virtual void tracker_set_particle_num(const int num);
00621     virtual void tracker_set_resample_likelihood_thr(double thr);
00622     virtual void tracker_set_use_normal(bool use_normal);
00623     virtual void tracker_set_cloud_coherence(
00624       ApproxNearestPairPointCloudCoherence<PointT>::Ptr coherence);
00625     virtual void tracker_set_maximum_particle_num(int num);
00626     virtual void tracker_set_delta(double delta);
00627     virtual void tracker_set_epsilon(double epsilon);
00628     virtual void tracker_set_bin_size(const ParticleXYZRPY bin_size);
00629     virtual ParticleFilterTracker<PointT, ParticleXYZRPY>::PointCloudStatePtr
00630     tracker_get_particles();
00631     virtual ParticleXYZRPY tracker_get_result();
00632     virtual Eigen::Affine3f tracker_to_eigen_matrix(
00633       const ParticleXYZRPY& result);
00634     virtual pcl::PointCloud<PointT>::ConstPtr tracker_get_reference_cloud();
00635     virtual void tracker_set_reference_cloud(pcl::PointCloud<PointT>::Ptr ref);
00636     virtual void tracker_reset_tracking();
00637     virtual void tracker_set_input_cloud(pcl::PointCloud<PointT>::Ptr input);
00638     virtual void tracker_compute();
00639   private:
00640     virtual void onInit();
00641 
00642   };
00643 }
00644 
00645 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48