Go to the documentation of this file.
    2 #ifndef _TARGET_ADAPTIVE_TRACKING_H_ 
    3 #define _TARGET_ADAPTIVE_TRACKING_H_ 
   14 #include <sensor_msgs/Image.h> 
   16 #include <sensor_msgs/PointCloud2.h> 
   19 #include <opencv2/core/core.hpp> 
   20 #include <opencv2/opencv.hpp> 
   21 #include <boost/thread/mutex.hpp> 
   24 #include <pcl/point_cloud.h> 
   25 #include <pcl/point_types.h> 
   26 #include <pcl/io/pcd_io.h> 
   27 #include <pcl/correspondence.h> 
   28 #include <pcl/recognition/cg/hough_3d.h> 
   29 #include <pcl/recognition/cg/geometric_consistency.h> 
   30 #include <pcl/kdtree/kdtree_flann.h> 
   31 #include <pcl/kdtree/impl/kdtree_flann.hpp> 
   32 #include <pcl/common/transforms.h> 
   33 #include <pcl/filters/extract_indices.h> 
   34 #include <pcl/segmentation/segment_differences.h> 
   35 #include <pcl/octree/octree.h> 
   36 #include <pcl/surface/concave_hull.h> 
   37 #include <pcl/segmentation/extract_clusters.h> 
   38 #include <pcl/filters/filter.h> 
   39 #include <pcl/common/centroid.h> 
   40 #include <pcl/features/fpfh_omp.h> 
   41 #include <pcl/features/vfh.h> 
   42 #include <pcl/features/gfpfh.h> 
   43 #include <pcl/features/pfh.h> 
   44 #include <pcl/features/cvfh.h> 
   45 #include <pcl/features/pfh_tools.h>  
   46 #include <pcl/features/normal_3d_omp.h> 
   47 #include <pcl/tracking/tracking.h> 
   48 #include <pcl/common/common.h> 
   49 #include <pcl/registration/distances.h> 
   50 #include <pcl/filters/passthrough.h> 
   51 #include <pcl/segmentation/supervoxel_clustering.h> 
   56 #include <geometry_msgs/Pose.h> 
   57 #include <geometry_msgs/PoseStamped.h> 
   58 #include <std_msgs/Header.h> 
   59 #include <dynamic_reconfigure/server.h> 
   60 #include <jsk_recognition_msgs/ClusterPointIndices.h> 
   61 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   63 #include <jsk_pcl_ros/TargetAdaptiveTrackingConfig.h> 
   95       typedef std::vector<ReferenceModel> 
Models;
 
  100          sensor_msgs::PointCloud2,
 
  106          sensor_msgs::PointCloud2,
 
  107          sensor_msgs::PointCloud2,
 
  164       typedef jsk_pcl_ros::TargetAdaptiveTrackingConfig 
Config;
 
  177          const sensor_msgs::PointCloud2::ConstPtr &,
 
  178          const geometry_msgs::PoseStamped::ConstPtr &);
 
  180          const sensor_msgs::PointCloud2::ConstPtr &,
 
  181          const sensor_msgs::PointCloud2::ConstPtr &,
 
  182          const geometry_msgs::PoseStamped::ConstPtr &);
 
  183       virtual std::vector<pcl::PointIndices::Ptr>
 
  185          const jsk_recognition_msgs::ClusterPointIndicesConstPtr &);
 
  187          const geometry_msgs::PoseStamped::ConstPtr &, 
PointXYZRPY &);
 
  189          const pcl::PointCloud<PointT>::Ptr cloud,
 
  190          const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &,
 
  191          const std::multimap<uint32_t, uint32_t> &,
 
  192          std::vector<AdjacentInfo> &,
 
  193          ModelsPtr &, 
bool = 
true, 
bool = 
true, 
bool = 
true, 
bool = 
false);
 
  195          pcl::PointCloud<PointT>::Ptr, 
const Eigen::Affine3f &,
 
  197          const std_msgs::Header);
 
  201          const pcl::PointCloud<pcl::Normal>::Ptr, 
const Eigen::Vector4f &,
 
  205          Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f);
 
  208          const pcl::PointCloud<PointT>::Ptr, pcl::PointCloud<pcl::Normal>::Ptr,
 
  209          T = 0.05
f, 
bool = 
false) 
const;
 
  211          const pcl::PointCloud<PointT>::Ptr,
 
  212          const pcl::PointCloud<pcl::Normal>::Ptr, cv::Mat &) 
const;
 
  214          const pcl::PointCloud<PointT>::Ptr, cv::Mat &, 
const int = 16,
 
  215          const int = 16, 
bool = 
true) 
const;
 
  217          const pcl::PointCloud<PointT>::Ptr,
 
  218          pcl::PointCloud<pcl::Normal>::Ptr, cv::Mat &, 
bool = 
true) 
const;
 
  220          const pcl::PointCloud<PointT>::Ptr, Eigen::Vector4f &) 
const;
 
  222          const pcl::PointCloud<pcl::Normal>::Ptr, 
bool = 
true);
 
  225          const Eigen::Vector4f &, 
const Eigen::Vector4f &, 
const cv::Scalar);
 
  230          const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr> &,
 
  231          const std::map<uint32_t, std::vector<uint32_t> >&,
 
  232          cv::Mat &, 
const int = 3);
 
  234          const std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr>,
 
  235          const std::multimap<uint32_t, uint32_t>,
 
  240          const pcl::PointCloud<PointT>::Ptr);
 
  242          pcl::PointCloud<PointT>::Ptr,
 
  243          const Eigen::Vector4f, 
const ModelsPtr, 
const float);
 
  245          const pcl::PointCloud<PointT>::Ptr, 
ModelsPtr);
 
  249          pcl::PointCloud<PointT>::Ptr, 
const ModelsPtr, 
const float = 0.6
f);
 
  251          const pcl::PointCloud<PointT>::Ptr,
 
  252          const Eigen::Vector4f);
 
  253       template<
typename T, 
typename U, 
typename V>
 
  256          const pcl::PointCloud<PointT>::Ptr,
 
  257          std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > &,
 
  258          std::multimap<uint32_t, uint32_t> &);
 
  260          const pcl::PointCloud<PointT>::Ptr,
 
  261          std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > &,
 
  262          std::multimap<uint32_t, uint32_t> &, 
const float);
 
  264          const std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr>,
 
  265          sensor_msgs::PointCloud2 &,
 
  266          jsk_recognition_msgs::ClusterPointIndices &,
 
  267          const std_msgs::Header &);
 
  269          const jsk_recognition_msgs::ClusterPointIndices &,
 
  270          const std::vector<uint32_t> &,
 
  271          jsk_recognition_msgs::ClusterPointIndices &);
 
  276 #endif  // _TARGET_ADAPTIVE_TRACKING_H_ 
  
std::vector< ReferenceModel > Models
void targetDescriptiveSurfelsEstimationAndUpdate(pcl::PointCloud< PointT >::Ptr, const Eigen::Affine3f &, const TargetAdaptiveTracking::PointXYZRPY &, const std_msgs::Header)
std::vector< PointXYZRPY > MotionHistory
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
void computePointFPFH(const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &, bool=true) const
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_obj_cloud_
ModelsPtr background_reference_
pcl::PointCloud< pcl::Normal >::Ptr cluster_normals
Eigen::Vector4f current_pose_
AdjacentInfo cluster_neigbors
virtual ~TargetAdaptiveTracking()
tf::Transform previous_transform_
pcl::PointXYZRGBNormal convertVector4fToPointXyzRgbNormal(const Eigen::Vector4f &, const Eigen::Vector4f &, const cv::Scalar)
double spatial_importance_
pcl::tracking::ParticleXYZRPY PointXYZRPY
ros::Publisher pub_normal_
void transformModelPrimitives(const ModelsPtr &, ModelsPtr, const Eigen::Affine3f &)
virtual std::vector< pcl::PointIndices::Ptr > clusterPointIndicesToPointIndices(const jsk_recognition_msgs::ClusterPointIndicesConstPtr &)
void publishSupervoxel(const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr >, sensor_msgs::PointCloud2 &, jsk_recognition_msgs::ClusterPointIndices &, const std_msgs::Header &)
boost::shared_ptr< Models > ModelsPtr
void computeCloudClusterRPYHistogram(const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &) const
void compute3DCentroids(const pcl::PointCloud< PointT >::Ptr, Eigen::Vector4f &) const
ros::Publisher pub_templ_
std::string child_frame_id_
void backgroundReferenceLikelihood(const ModelsPtr, const ModelsPtr, std::map< uint32_t, float >)
std::vector< int > history_window
Eigen::Vector4f previous_pose_
ros::Publisher pub_cloud_
cv::Scalar plotJetColour(T, U, V)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_bkgd_cloud_
pcl::PointCloud< PointT >::Ptr cluster_cloud
double normal_importance_
cv::Mat cluster_color_hist
Eigen::Vector4f cluster_centroid
Eigen::Vector3f centroid_distance
void filterCloudForBoundingBoxViz(pcl::PointCloud< PointT >::Ptr, const ModelsPtr, const float=0.6f)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > ObjectSyncPolicy
std::map< uint32_t, std::vector< uint32_t > > adjacent_voxel_indices
T localVoxelConvexityLikelihood(Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f)
uint32_t supervoxel_index
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_obj_pose_
ros::Publisher pub_inliers_
void estimatePointCloudNormals(const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, T=0.05f, bool=false) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void supervoxelSegmentation(const pcl::PointCloud< PointT >::Ptr, std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, std::multimap< uint32_t, uint32_t > &)
boost::shared_ptr< message_filters::Synchronizer< ObjectSyncPolicy > > obj_sync_
virtual void unsubscribe()
Eigen::Vector4f cloudMeanNormal(const pcl::PointCloud< pcl::Normal >::Ptr, bool=true)
virtual void configCallback(Config &, uint32_t)
void processVoxelForReferenceModel(const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr >, const std::multimap< uint32_t, uint32_t >, const uint32_t, TargetAdaptiveTracking::ReferenceModel *)
ros::Publisher pub_centroids_
ModelsPtr object_reference_
T targetCandidateToReferenceLikelihood(const ReferenceModel &, const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, const Eigen::Vector4f &, ReferenceModel *=NULL)
void processInitCloud(const pcl::PointCloud< PointT >::Ptr, ModelsPtr)
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
MotionHistory motion_history_
void targetDescriptiveSurfelsIndices(const jsk_recognition_msgs::ClusterPointIndices &, const std::vector< uint32_t > &, jsk_recognition_msgs::ClusterPointIndices &)
pcl::PointCloud< PointT >::Ptr previous_template_
void getRotationMatrixFromRPY(const PointXYZRPY &, Eigen::Matrix< T, 3, 3 > &)
ros::Publisher pub_scloud_
std::string parent_frame_id_
boost::mutex mutex
global mutex.
bool update_filter_template_
ros::Publisher pub_sindices_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > SyncPolicy
virtual void callback(const sensor_msgs::PointCloud2::ConstPtr &, const geometry_msgs::PoseStamped::ConstPtr &)
void computeColorHistogram(const pcl::PointCloud< PointT >::Ptr, cv::Mat &, const int=16, const int=16, bool=true) const
void estimatedPFPose(const geometry_msgs::PoseStamped::ConstPtr &, PointXYZRPY &)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void computeScatterMatrix(const pcl::PointCloud< PointT >::Ptr, const Eigen::Vector4f)
virtual void objInitCallback(const sensor_msgs::PointCloud2::ConstPtr &, const sensor_msgs::PointCloud2::ConstPtr &, const geometry_msgs::PoseStamped::ConstPtr &)
float computeCoherency(const float, const float)
jsk_pcl_ros::TargetAdaptiveTrackingConfig Config
float templateCloudFilterLenght(const pcl::PointCloud< PointT >::Ptr)
void voxelizeAndProcessPointCloud(const pcl::PointCloud< PointT >::Ptr cloud, const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, const std::multimap< uint32_t, uint32_t > &, std::vector< AdjacentInfo > &, ModelsPtr &, bool=true, bool=true, bool=true, bool=false)
bool update_tracker_reference_
PointXYZRPY tracker_pose_
void computeLocalPairwiseFeautures(const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, const std::map< uint32_t, std::vector< uint32_t > > &, cv::Mat &, const int=3)
bool filterPointCloud(pcl::PointCloud< PointT >::Ptr, const Eigen::Vector4f, const ModelsPtr, const float)
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:12