Classes | Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
jsk_pcl_ros::TargetAdaptiveTracking Class Reference

#include <target_adaptive_tracking.h>

Inheritance diagram for jsk_pcl_ros::TargetAdaptiveTracking:
Inheritance graph
[legend]

Classes

struct  AdjacentInfo
 
struct  ReferenceModel
 

Public Member Functions

void backgroundReferenceLikelihood (const ModelsPtr, const ModelsPtr, std::map< uint32_t, float >)
 
virtual void callback (const sensor_msgs::PointCloud2::ConstPtr &, const geometry_msgs::PoseStamped::ConstPtr &)
 
Eigen::Vector4f cloudMeanNormal (const pcl::PointCloud< pcl::Normal >::Ptr, bool=true)
 
virtual std::vector< pcl::PointIndices::Ptr > clusterPointIndicesToPointIndices (const jsk_recognition_msgs::ClusterPointIndicesConstPtr &)
 
void compute3DCentroids (const pcl::PointCloud< PointT >::Ptr, Eigen::Vector4f &) const
 
void computeCloudClusterRPYHistogram (const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &) const
 
float computeCoherency (const float, const float)
 
void computeColorHistogram (const pcl::PointCloud< PointT >::Ptr, cv::Mat &, const int=16, const int=16, bool=true) const
 
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)
 
void computePointFPFH (const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &, bool=true) const
 
void computeScatterMatrix (const pcl::PointCloud< PointT >::Ptr, const Eigen::Vector4f)
 
pcl::PointXYZRGBNormal convertVector4fToPointXyzRgbNormal (const Eigen::Vector4f &, const Eigen::Vector4f &, const cv::Scalar)
 
void estimatedPFPose (const geometry_msgs::PoseStamped::ConstPtr &, PointXYZRPY &)
 
template<class T >
void estimatePointCloudNormals (const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, T=0.05f, bool=false) const
 
void filterCloudForBoundingBoxViz (pcl::PointCloud< PointT >::Ptr, const ModelsPtr, const float=0.6f)
 
bool filterPointCloud (pcl::PointCloud< PointT >::Ptr, const Eigen::Vector4f, const ModelsPtr, const float)
 
template<typename T >
void getRotationMatrixFromRPY (const PointXYZRPY &, Eigen::Matrix< T, 3, 3 > &)
 
template<class T >
T localVoxelConvexityLikelihood (Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f, Eigen::Vector4f)
 
virtual void objInitCallback (const sensor_msgs::PointCloud2::ConstPtr &, const sensor_msgs::PointCloud2::ConstPtr &, const geometry_msgs::PoseStamped::ConstPtr &)
 
template<typename T , typename U , typename V >
cv::Scalar plotJetColour (T, U, V)
 
void processInitCloud (const pcl::PointCloud< PointT >::Ptr, ModelsPtr)
 
void processVoxelForReferenceModel (const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr >, const std::multimap< uint32_t, uint32_t >, const uint32_t, TargetAdaptiveTracking::ReferenceModel *)
 
void publishSupervoxel (const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr >, sensor_msgs::PointCloud2 &, jsk_recognition_msgs::ClusterPointIndices &, const std_msgs::Header &)
 
void supervoxelSegmentation (const pcl::PointCloud< PointT >::Ptr, std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, std::multimap< uint32_t, uint32_t > &)
 
void supervoxelSegmentation (const pcl::PointCloud< PointT >::Ptr, std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &, std::multimap< uint32_t, uint32_t > &, const float)
 
 TargetAdaptiveTracking ()
 
template<class T >
T targetCandidateToReferenceLikelihood (const ReferenceModel &, const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, const Eigen::Vector4f &, ReferenceModel *=NULL)
 
void targetDescriptiveSurfelsEstimationAndUpdate (pcl::PointCloud< PointT >::Ptr, const Eigen::Affine3f &, const TargetAdaptiveTracking::PointXYZRPY &, const std_msgs::Header)
 
void targetDescriptiveSurfelsIndices (const jsk_recognition_msgs::ClusterPointIndices &, const std::vector< uint32_t > &, jsk_recognition_msgs::ClusterPointIndices &)
 
float templateCloudFilterLenght (const pcl::PointCloud< PointT >::Ptr)
 
void transformModelPrimitives (const ModelsPtr &, ModelsPtr, const Eigen::Affine3f &)
 
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)
 
- Public Member Functions inherited from jsk_topic_tools::DiagnosticNodelet
 DiagnosticNodelet (const std::string &name)
 
- Public Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
 ConnectionBasedNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
- Protected Member Functions inherited from jsk_topic_tools::DiagnosticNodelet
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
- Protected Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
virtual void cameraConnectionBaseCallback ()
 
virtual void cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 
virtual void cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 
virtual bool isSubscribed ()
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
virtual void warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Private Types

typedef jsk_pcl_ros::TargetAdaptiveTrackingConfig Config
 
typedef std::vector< ReferenceModelModels
 
typedef boost::shared_ptr< ModelsModelsPtr
 
typedef std::vector< PointXYZRPYMotionHistory
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > ObjectSyncPolicy
 
typedef pcl::PointXYZRGB PointT
 
typedef pcl::tracking::ParticleXYZRPY PointXYZRPY
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > SyncPolicy
 

Private Member Functions

virtual void configCallback (Config &, uint32_t)
 

Private Attributes

ModelsPtr background_reference_
 
int bin_size_
 
std::string child_frame_id_
 
double color_importance_
 
float color_scaling_
 
Eigen::Vector4f current_pose_
 
float eps_distance_
 
int eps_min_samples_
 
float growth_rate_
 
int history_window_size_
 
int init_counter_
 
int min_cluster_size_
 
MotionHistory motion_history_
 
boost::mutex mutex_
 
double normal_importance_
 
boost::shared_ptr< message_filters::Synchronizer< ObjectSyncPolicy > > obj_sync_
 
ModelsPtr object_reference_
 
std::string parent_frame_id_
 
float previous_distance_
 
Eigen::Vector4f previous_pose_
 
pcl::PointCloud< PointT >::Ptr previous_template_
 
tf::Transform previous_transform_
 
ros::Publisher pub_centroids_
 
ros::Publisher pub_cloud_
 
ros::Publisher pub_inliers_
 
ros::Publisher pub_normal_
 
ros::Publisher pub_pose_
 
ros::Publisher pub_prob_
 
ros::Publisher pub_scloud_
 
ros::Publisher pub_sindices_
 
ros::Publisher pub_tdp_
 
ros::Publisher pub_templ_
 
double seed_resolution_
 
double spatial_importance_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
float structure_scaling_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_bkgd_cloud_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_obj_cloud_
 
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_obj_pose_
 
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
float threshold_
 
PointXYZRPY tracker_pose_
 
int update_counter_
 
bool update_filter_template_
 
bool update_tracker_reference_
 
bool use_tf_
 
bool use_transform_
 
float vfh_scaling_
 
double voxel_resolution_
 

Additional Inherited Members

- Public Types inherited from jsk_topic_tools::DiagnosticNodelet
typedef boost::shared_ptr< DiagnosticNodeletPtr
 
- Protected Attributes inherited from jsk_topic_tools::DiagnosticNodelet
TimeredDiagnosticUpdater::Ptr diagnostic_updater_
 
const std::string name_
 
jsk_topic_tools::VitalChecker::Ptr vital_checker_
 
- Protected Attributes inherited from jsk_topic_tools::ConnectionBasedNodelet
bool always_subscribe_
 
std::vector< image_transport::CameraPublishercamera_publishers_
 
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
std::vector< image_transport::Publisherimage_publishers_
 
boost::shared_ptr< ros::NodeHandlenh_
 
bool on_init_post_process_called_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
bool subscribed_
 
ros::WallTimer timer_warn_never_subscribed_
 
ros::WallTimer timer_warn_on_init_post_process_called_
 
bool verbose_connection_
 

Detailed Description

Definition at line 66 of file target_adaptive_tracking.h.

Member Typedef Documentation

typedef jsk_pcl_ros::TargetAdaptiveTrackingConfig jsk_pcl_ros::TargetAdaptiveTracking::Config
private

Definition at line 163 of file target_adaptive_tracking.h.

Definition at line 94 of file target_adaptive_tracking.h.

Definition at line 95 of file target_adaptive_tracking.h.

Definition at line 97 of file target_adaptive_tracking.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, geometry_msgs::PoseStamped> jsk_pcl_ros::TargetAdaptiveTracking::ObjectSyncPolicy
private

Definition at line 107 of file target_adaptive_tracking.h.

typedef pcl::PointXYZRGB jsk_pcl_ros::TargetAdaptiveTracking::PointT
private

Definition at line 68 of file target_adaptive_tracking.h.

typedef pcl::tracking::ParticleXYZRPY jsk_pcl_ros::TargetAdaptiveTracking::PointXYZRPY
private

Definition at line 96 of file target_adaptive_tracking.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped> jsk_pcl_ros::TargetAdaptiveTracking::SyncPolicy
private

Definition at line 100 of file target_adaptive_tracking.h.

Constructor & Destructor Documentation

jsk_pcl_ros::TargetAdaptiveTracking::TargetAdaptiveTracking ( )

Definition at line 10 of file target_adaptive_tracking_nodelet.cpp.

Member Function Documentation

void jsk_pcl_ros::TargetAdaptiveTracking::backgroundReferenceLikelihood ( const ModelsPtr  background_reference,
const ModelsPtr  target_voxels,
std::map< uint32_t, float max_prob 
)

Definition at line 1139 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::callback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const geometry_msgs::PoseStamped::ConstPtr &  pose_msg 
)
virtual

Definition at line 162 of file target_adaptive_tracking_nodelet.cpp.

Eigen::Vector4f jsk_pcl_ros::TargetAdaptiveTracking::cloudMeanNormal ( const pcl::PointCloud< pcl::Normal >::Ptr  normal,
bool  isnorm = true 
)

Definition at line 1400 of file target_adaptive_tracking_nodelet.cpp.

std::vector< pcl::PointIndices::Ptr > jsk_pcl_ros::TargetAdaptiveTracking::clusterPointIndicesToPointIndices ( const jsk_recognition_msgs::ClusterPointIndicesConstPtr &  indices_mgs)
virtual

Definition at line 1329 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::compute3DCentroids ( const pcl::PointCloud< PointT >::Ptr  cloud,
Eigen::Vector4f &  centre 
) const

Definition at line 1384 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::computeCloudClusterRPYHistogram ( const pcl::PointCloud< PointT >::Ptr  cloud,
const pcl::PointCloud< pcl::Normal >::Ptr  normal,
cv::Mat &  histogram 
) const

Definition at line 1186 of file target_adaptive_tracking_nodelet.cpp.

float jsk_pcl_ros::TargetAdaptiveTracking::computeCoherency ( const float  dist,
const float  weight 
)

Definition at line 1459 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::computeColorHistogram ( const pcl::PointCloud< PointT >::Ptr  cloud,
cv::Mat &  hist,
const int  hBin = 16,
const int  sBin = 16,
bool  is_norm = true 
) const

Definition at line 1263 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::computeLocalPairwiseFeautures ( const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &  supervoxel_clusters,
const std::map< uint32_t, std::vector< uint32_t > > &  adjacency_list,
cv::Mat &  histogram,
const int  feature_count = 3 
)

Definition at line 1501 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::computePointFPFH ( const pcl::PointCloud< PointT >::Ptr  cloud,
pcl::PointCloud< pcl::Normal >::Ptr  normals,
cv::Mat &  histogram,
bool  holistic = true 
) const

Definition at line 1290 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::computeScatterMatrix ( const pcl::PointCloud< PointT >::Ptr  cloud,
const Eigen::Vector4f  centroid 
)

Definition at line 1432 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::configCallback ( Config config,
uint32_t  level 
)
privatevirtual

Definition at line 1849 of file target_adaptive_tracking_nodelet.cpp.

pcl::PointXYZRGBNormal jsk_pcl_ros::TargetAdaptiveTracking::convertVector4fToPointXyzRgbNormal ( const Eigen::Vector4f &  centroid,
const Eigen::Vector4f &  normal,
const cv::Scalar  color 
)

Definition at line 1468 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::estimatedPFPose ( const geometry_msgs::PoseStamped::ConstPtr &  pose_msg,
PointXYZRPY motion_displacement 
)

Definition at line 1342 of file target_adaptive_tracking_nodelet.cpp.

template<class T >
void jsk_pcl_ros::TargetAdaptiveTracking::estimatePointCloudNormals ( const pcl::PointCloud< PointT >::Ptr  cloud,
pcl::PointCloud< pcl::Normal >::Ptr  normals,
T  k = 0.05f,
bool  use_knn = false 
) const

Definition at line 1166 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::filterCloudForBoundingBoxViz ( pcl::PointCloud< PointT >::Ptr  cloud,
const ModelsPtr  background_reference,
const float  threshold = 0.6f 
)

Definition at line 1687 of file target_adaptive_tracking_nodelet.cpp.

bool jsk_pcl_ros::TargetAdaptiveTracking::filterPointCloud ( pcl::PointCloud< PointT >::Ptr  cloud,
const Eigen::Vector4f  tracker_position,
const ModelsPtr  template_model,
const float  scaling_factor 
)

Definition at line 1616 of file target_adaptive_tracking_nodelet.cpp.

template<typename T >
void jsk_pcl_ros::TargetAdaptiveTracking::getRotationMatrixFromRPY ( const PointXYZRPY motion_displacement,
Eigen::Matrix< T, 3, 3 > &  rotation 
)

Definition at line 1486 of file target_adaptive_tracking_nodelet.cpp.

template<class T >
T jsk_pcl_ros::TargetAdaptiveTracking::localVoxelConvexityLikelihood ( Eigen::Vector4f  c_centroid,
Eigen::Vector4f  c_normal,
Eigen::Vector4f  n_centroid,
Eigen::Vector4f  n_normal 
)

Definition at line 1115 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::objInitCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const sensor_msgs::PointCloud2::ConstPtr &  bkgd_msg,
const geometry_msgs::PoseStamped::ConstPtr &  pose_msg 
)
virtual

Definition at line 102 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::onInit ( void  )
protectedvirtual

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 22 of file target_adaptive_tracking_nodelet.cpp.

template<typename T , typename U , typename V >
cv::Scalar jsk_pcl_ros::TargetAdaptiveTracking::plotJetColour ( T  v,
vmin,
vmax 
)

Definition at line 1734 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::processInitCloud ( const pcl::PointCloud< PointT >::Ptr  cloud,
ModelsPtr  object_reference 
)

Definition at line 135 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::processVoxelForReferenceModel ( const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr supervoxel_clusters,
const std::multimap< uint32_t, uint32_t >  supervoxel_adjacency,
const uint32_t  match_index,
TargetAdaptiveTracking::ReferenceModel ref_model 
)

Definition at line 1022 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::publishSupervoxel ( const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr supervoxel_clusters,
sensor_msgs::PointCloud2 &  ros_cloud,
jsk_recognition_msgs::ClusterPointIndices &  ros_indices,
const std_msgs::Header header 
)

Definition at line 1806 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::subscribe ( )
protectedvirtual
void jsk_pcl_ros::TargetAdaptiveTracking::supervoxelSegmentation ( const pcl::PointCloud< PointT >::Ptr  cloud,
std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &  supervoxel_clusters,
std::multimap< uint32_t, uint32_t > &  supervoxel_adjacency 
)

Definition at line 1784 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::supervoxelSegmentation ( const pcl::PointCloud< PointT >::Ptr  cloud,
std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &  supervoxel_clusters,
std::multimap< uint32_t, uint32_t > &  supervoxel_adjacency,
const float  seed_resolution 
)

Definition at line 1760 of file target_adaptive_tracking_nodelet.cpp.

template<class T >
T jsk_pcl_ros::TargetAdaptiveTracking::targetCandidateToReferenceLikelihood ( const ReferenceModel reference_model,
const pcl::PointCloud< PointT >::Ptr  cloud,
const pcl::PointCloud< pcl::Normal >::Ptr  normal,
const Eigen::Vector4f &  centroid,
ReferenceModel voxel_model = NULL 
)

Definition at line 1074 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::targetDescriptiveSurfelsEstimationAndUpdate ( pcl::PointCloud< PointT >::Ptr  cloud,
const Eigen::Affine3f &  transformation_matrix,
const TargetAdaptiveTracking::PointXYZRPY motion_disp,
const std_msgs::Header  header 
)

Definition at line 351 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::targetDescriptiveSurfelsIndices ( const jsk_recognition_msgs::ClusterPointIndices &  sv_indices,
const std::vector< uint32_t > &  tdp_list,
jsk_recognition_msgs::ClusterPointIndices &  ros_indices 
)

Definition at line 1836 of file target_adaptive_tracking_nodelet.cpp.

float jsk_pcl_ros::TargetAdaptiveTracking::templateCloudFilterLenght ( const pcl::PointCloud< PointT >::Ptr  cloud)

Definition at line 1599 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::transformModelPrimitives ( const ModelsPtr obj_ref,
ModelsPtr  trans_models,
const Eigen::Affine3f &  transform_model 
)

Definition at line 1664 of file target_adaptive_tracking_nodelet.cpp.

void jsk_pcl_ros::TargetAdaptiveTracking::unsubscribe ( )
protectedvirtual
void jsk_pcl_ros::TargetAdaptiveTracking::voxelizeAndProcessPointCloud ( const pcl::PointCloud< PointT >::Ptr  cloud,
const std::map< uint32_t, pcl::Supervoxel< PointT >::Ptr > &  supervoxel_clusters,
const std::multimap< uint32_t, uint32_t > &  supervoxel_adjacency,
std::vector< AdjacentInfo > &  supervoxel_list,
TargetAdaptiveTracking::ModelsPtr models,
bool  norm_flag = true,
bool  feat_flag = true,
bool  cent_flag = true,
bool  neigh_pfh = false 
)

Definition at line 268 of file target_adaptive_tracking_nodelet.cpp.

Member Data Documentation

ModelsPtr jsk_pcl_ros::TargetAdaptiveTracking::background_reference_
private

Definition at line 128 of file target_adaptive_tracking.h.

int jsk_pcl_ros::TargetAdaptiveTracking::bin_size_
private

Definition at line 152 of file target_adaptive_tracking.h.

std::string jsk_pcl_ros::TargetAdaptiveTracking::child_frame_id_
private

Definition at line 141 of file target_adaptive_tracking.h.

double jsk_pcl_ros::TargetAdaptiveTracking::color_importance_
private

Definition at line 143 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::color_scaling_
private

Definition at line 156 of file target_adaptive_tracking.h.

Eigen::Vector4f jsk_pcl_ros::TargetAdaptiveTracking::current_pose_
private

Definition at line 131 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::eps_distance_
private

Definition at line 153 of file target_adaptive_tracking.h.

int jsk_pcl_ros::TargetAdaptiveTracking::eps_min_samples_
private

Definition at line 154 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::growth_rate_
private

Definition at line 136 of file target_adaptive_tracking.h.

int jsk_pcl_ros::TargetAdaptiveTracking::history_window_size_
private

Definition at line 160 of file target_adaptive_tracking.h.

int jsk_pcl_ros::TargetAdaptiveTracking::init_counter_
private

Definition at line 126 of file target_adaptive_tracking.h.

int jsk_pcl_ros::TargetAdaptiveTracking::min_cluster_size_
private

Definition at line 150 of file target_adaptive_tracking.h.

MotionHistory jsk_pcl_ros::TargetAdaptiveTracking::motion_history_
private

Definition at line 129 of file target_adaptive_tracking.h.

boost::mutex jsk_pcl_ros::TargetAdaptiveTracking::mutex_
private

Definition at line 161 of file target_adaptive_tracking.h.

double jsk_pcl_ros::TargetAdaptiveTracking::normal_importance_
private

Definition at line 145 of file target_adaptive_tracking.h.

boost::shared_ptr< message_filters::Synchronizer<ObjectSyncPolicy> > jsk_pcl_ros::TargetAdaptiveTracking::obj_sync_
private

Definition at line 112 of file target_adaptive_tracking.h.

ModelsPtr jsk_pcl_ros::TargetAdaptiveTracking::object_reference_
private

Definition at line 127 of file target_adaptive_tracking.h.

std::string jsk_pcl_ros::TargetAdaptiveTracking::parent_frame_id_
private

Definition at line 140 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::previous_distance_
private

Definition at line 137 of file target_adaptive_tracking.h.

Eigen::Vector4f jsk_pcl_ros::TargetAdaptiveTracking::previous_pose_
private

Definition at line 132 of file target_adaptive_tracking.h.

pcl::PointCloud<PointT>::Ptr jsk_pcl_ros::TargetAdaptiveTracking::previous_template_
private

Definition at line 135 of file target_adaptive_tracking.h.

tf::Transform jsk_pcl_ros::TargetAdaptiveTracking::previous_transform_
private

Definition at line 134 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_centroids_
private

Definition at line 122 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_cloud_
private

Definition at line 115 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_inliers_
private

Definition at line 121 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_normal_
private

Definition at line 119 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_pose_
private

Definition at line 123 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_prob_
private

Definition at line 124 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_scloud_
private

Definition at line 118 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_sindices_
private

Definition at line 117 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_tdp_
private

Definition at line 120 of file target_adaptive_tracking.h.

ros::Publisher jsk_pcl_ros::TargetAdaptiveTracking::pub_templ_
private

Definition at line 116 of file target_adaptive_tracking.h.

double jsk_pcl_ros::TargetAdaptiveTracking::seed_resolution_
private

Definition at line 147 of file target_adaptive_tracking.h.

double jsk_pcl_ros::TargetAdaptiveTracking::spatial_importance_
private

Definition at line 144 of file target_adaptive_tracking.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::TargetAdaptiveTracking::srv_
private

Definition at line 165 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::structure_scaling_
private

Definition at line 157 of file target_adaptive_tracking.h.

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::TargetAdaptiveTracking::sub_bkgd_cloud_
private

Definition at line 109 of file target_adaptive_tracking.h.

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::TargetAdaptiveTracking::sub_cloud_
private

Definition at line 101 of file target_adaptive_tracking.h.

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::TargetAdaptiveTracking::sub_obj_cloud_
private

Definition at line 108 of file target_adaptive_tracking.h.

message_filters::Subscriber<geometry_msgs::PoseStamped> jsk_pcl_ros::TargetAdaptiveTracking::sub_obj_pose_
private

Definition at line 110 of file target_adaptive_tracking.h.

message_filters::Subscriber<geometry_msgs::PoseStamped> jsk_pcl_ros::TargetAdaptiveTracking::sub_pose_
private

Definition at line 102 of file target_adaptive_tracking.h.

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::TargetAdaptiveTracking::sync_
private

Definition at line 103 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::threshold_
private

Definition at line 151 of file target_adaptive_tracking.h.

PointXYZRPY jsk_pcl_ros::TargetAdaptiveTracking::tracker_pose_
private

Definition at line 133 of file target_adaptive_tracking.h.

int jsk_pcl_ros::TargetAdaptiveTracking::update_counter_
private

Definition at line 130 of file target_adaptive_tracking.h.

bool jsk_pcl_ros::TargetAdaptiveTracking::update_filter_template_
private

Definition at line 159 of file target_adaptive_tracking.h.

bool jsk_pcl_ros::TargetAdaptiveTracking::update_tracker_reference_
private

Definition at line 158 of file target_adaptive_tracking.h.

bool jsk_pcl_ros::TargetAdaptiveTracking::use_tf_
private

Definition at line 139 of file target_adaptive_tracking.h.

bool jsk_pcl_ros::TargetAdaptiveTracking::use_transform_
private

Definition at line 148 of file target_adaptive_tracking.h.

float jsk_pcl_ros::TargetAdaptiveTracking::vfh_scaling_
private

Definition at line 155 of file target_adaptive_tracking.h.

double jsk_pcl_ros::TargetAdaptiveTracking::voxel_resolution_
private

Definition at line 146 of file target_adaptive_tracking.h.


The documentation for this class was generated from the following files:


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