Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::PlaneSupportedCuboidEstimator Class Reference

#include <plane_supported_cuboid_estimator.h>

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

Public Types

typedef PlaneSupportedCuboidEstimatorConfig Config
 
typedef pcl::tracking::ParticleCuboid Particle
 
typedef pcl::PointCloud< ParticleParticleCloud
 
typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > PolygonSyncPolicy
 
typedef boost::shared_ptr< PlaneSupportedCuboidEstimatorPtr
 

Public Member Functions

 PlaneSupportedCuboidEstimator ()
 
virtual ~PlaneSupportedCuboidEstimator ()
 

Protected Member Functions

virtual size_t chooseUniformRandomPlaneIndex (const std::vector< Polygon::Ptr > &polygons)
 
virtual void cloudCallback (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void configCallback (Config &config, uint32_t level)
 
virtual void estimate (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void fastCloudCallback (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual size_t getNearestPolygon (const Particle &p, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &polygons)
 Compute the nearest polygon to the particle ‘p’. More...
 
virtual pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr initParticles ()
 
virtual void likelihood (pcl::PointCloud< pcl::PointXYZ >::ConstPtr input, pcl::tracking::ParticleCuboid &p)
 
virtual void onInit ()
 
virtual void polygonCallback (const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coef_msg)
 
virtual void publishHistogram (ParticleCloud::Ptr particles, int index, ros::Publisher &pub, const std_msgs::Header &header)
 
virtual bool resetCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
 
virtual pcl::tracking::ParticleCuboid sample (const pcl::tracking::ParticleCuboid &p)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
virtual void updateParticlePolygonRelationship (ParticleCloud::Ptr particles)
 Compute distances between particles and polygons and assing each particle to the nearest polygon. This method is called only if the "polygon sensor" measurement is updated. For simplicity, this method expects convex polygon. More...
 

Protected Attributes

pcl::PointCloud< pcl::PointXYZ >::Ptr candidate_cloud_
 
Config config_
 
bool disable_init_pitch_
 
bool disable_init_roll_
 
double fast_cloud_threshold_
 
double init_dx_mean_
 
double init_dx_variance_
 
double init_dy_mean_
 
double init_dy_variance_
 
double init_dz_mean_
 
double init_dz_variance_
 
double init_global_orientation_yaw_mean_
 
double init_global_orientation_yaw_variance_
 
double init_local_orientation_pitch_mean_
 
double init_local_orientation_pitch_variance_
 
double init_local_orientation_roll_mean_
 
double init_local_orientation_roll_variance_
 
double init_local_orientation_yaw_mean_
 
double init_local_orientation_yaw_variance_
 
double init_local_position_z_max_
 
double init_local_position_z_min_
 
double init_world_position_z_max_
 
double init_world_position_z_min_
 
jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr latest_coefficients_msg_
 
jsk_recognition_msgs::PolygonArray::ConstPtr latest_polygon_msg_
 
double min_dx_
 
double min_dy_
 
double min_dz_
 
boost::mutex mutex_
 
int particle_num_
 
std::vector< Polygon::Ptrpolygons_
 
ros::Publisher pub_candidate_cloud_
 
ros::Publisher pub_histogram_dx_
 
ros::Publisher pub_histogram_dy_
 
ros::Publisher pub_histogram_dz_
 
ros::Publisher pub_histogram_global_pitch_
 
ros::Publisher pub_histogram_global_roll_
 
ros::Publisher pub_histogram_global_x_
 
ros::Publisher pub_histogram_global_y_
 
ros::Publisher pub_histogram_global_yaw_
 
ros::Publisher pub_histogram_global_z_
 
ros::Publisher pub_particles_
 
ros::Publisher pub_result_
 
ros::Publisher pub_result_pose_
 
boost::mt19937 random_generator_
 
std::string sensor_frame_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::ServiceServer srv_reset_
 
double step_dx_variance_
 
double step_dy_variance_
 
double step_dz_variance_
 
double step_pitch_variance_
 
double step_roll_variance_
 
double step_x_variance_
 
double step_y_variance_
 
double step_yaw_variance_
 
double step_z_variance_
 
ros::Subscriber sub_cloud_
 
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
 
ros::Subscriber sub_fast_cloud_
 
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
 
bool support_plane_updated_
 
boost::shared_ptr< message_filters::Synchronizer< PolygonSyncPolicy > > sync_polygon_
 
tf::TransformListenertf_
 
pcl::tracking::ROSCollaborativeParticleFilterTracker< pcl::PointXYZ, pcl::tracking::ParticleCuboid >::Ptr tracker_
 
pcl::KdTreeFLANN< pcl::PointXYZ > tree_
 
bool use_global_init_yaw_
 
bool use_init_polygon_likelihood_
 
bool use_init_world_position_z_model_
 
Eigen::Vector3f viewpoint_
 

Detailed Description

Definition at line 300 of file plane_supported_cuboid_estimator.h.

Member Typedef Documentation

◆ Config

typedef PlaneSupportedCuboidEstimatorConfig jsk_pcl_ros::PlaneSupportedCuboidEstimator::Config

Definition at line 306 of file plane_supported_cuboid_estimator.h.

◆ Particle

Definition at line 303 of file plane_supported_cuboid_estimator.h.

◆ ParticleCloud

Definition at line 304 of file plane_supported_cuboid_estimator.h.

◆ PolygonSyncPolicy

typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::PlaneSupportedCuboidEstimator::PolygonSyncPolicy

Definition at line 309 of file plane_supported_cuboid_estimator.h.

◆ Ptr

Definition at line 305 of file plane_supported_cuboid_estimator.h.

Constructor & Destructor Documentation

◆ PlaneSupportedCuboidEstimator()

jsk_pcl_ros::PlaneSupportedCuboidEstimator::PlaneSupportedCuboidEstimator ( )
inline

Definition at line 311 of file plane_supported_cuboid_estimator.h.

◆ ~PlaneSupportedCuboidEstimator()

jsk_pcl_ros::PlaneSupportedCuboidEstimator::~PlaneSupportedCuboidEstimator ( )
virtual

Definition at line 88 of file plane_supported_cuboid_estimator_nodelet.cpp.

Member Function Documentation

◆ chooseUniformRandomPlaneIndex()

size_t jsk_pcl_ros::PlaneSupportedCuboidEstimator::chooseUniformRandomPlaneIndex ( const std::vector< Polygon::Ptr > &  polygons)
protectedvirtual

◆ cloudCallback()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::cloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

◆ configCallback()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

◆ estimate()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

◆ fastCloudCallback()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::fastCloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

◆ getNearestPolygon()

size_t jsk_pcl_ros::PlaneSupportedCuboidEstimator::getNearestPolygon ( const Particle p,
const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &  polygons 
)
protectedvirtual

Compute the nearest polygon to the particle ‘p’.

Definition at line 109 of file plane_supported_cuboid_estimator_nodelet.cpp.

◆ initParticles()

pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::initParticles ( )
protectedvirtual

◆ likelihood()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::likelihood ( pcl::PointCloud< pcl::PointXYZ >::ConstPtr  input,
pcl::tracking::ParticleCuboid p 
)
protectedvirtual

◆ onInit()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::onInit ( )
protectedvirtual

Definition at line 51 of file plane_supported_cuboid_estimator_nodelet.cpp.

◆ polygonCallback()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::polygonCallback ( const jsk_recognition_msgs::PolygonArray::ConstPtr &  polygon_msg,
const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &  coef_msg 
)
protectedvirtual

◆ publishHistogram()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::publishHistogram ( ParticleCloud::Ptr  particles,
int  index,
ros::Publisher pub,
const std_msgs::Header header 
)
protectedvirtual

◆ resetCallback()

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::resetCallback ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
)
protectedvirtual

◆ sample()

pcl::tracking::ParticleCuboid jsk_pcl_ros::PlaneSupportedCuboidEstimator::sample ( const pcl::tracking::ParticleCuboid p)
protectedvirtual

◆ subscribe()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::subscribe ( )
protectedvirtual

Definition at line 99 of file plane_supported_cuboid_estimator_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::unsubscribe ( )
protectedvirtual

◆ updateParticlePolygonRelationship()

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::updateParticlePolygonRelationship ( ParticleCloud::Ptr  particles)
protectedvirtual

Compute distances between particles and polygons and assing each particle to the nearest polygon. This method is called only if the "polygon sensor" measurement is updated. For simplicity, this method expects convex polygon.

Definition at line 129 of file plane_supported_cuboid_estimator_nodelet.cpp.

Member Data Documentation

◆ candidate_cloud_

pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::candidate_cloud_
protected

Definition at line 378 of file plane_supported_cuboid_estimator.h.

◆ config_

Config jsk_pcl_ros::PlaneSupportedCuboidEstimator::config_
protected

Definition at line 382 of file plane_supported_cuboid_estimator.h.

◆ disable_init_pitch_

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_pitch_
protected

Definition at line 399 of file plane_supported_cuboid_estimator.h.

◆ disable_init_roll_

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_roll_
protected

Definition at line 398 of file plane_supported_cuboid_estimator.h.

◆ fast_cloud_threshold_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::fast_cloud_threshold_
protected

Definition at line 421 of file plane_supported_cuboid_estimator.h.

◆ init_dx_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_mean_
protected

Definition at line 401 of file plane_supported_cuboid_estimator.h.

◆ init_dx_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_variance_
protected

Definition at line 402 of file plane_supported_cuboid_estimator.h.

◆ init_dy_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_mean_
protected

Definition at line 403 of file plane_supported_cuboid_estimator.h.

◆ init_dy_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_variance_
protected

Definition at line 404 of file plane_supported_cuboid_estimator.h.

◆ init_dz_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_mean_
protected

Definition at line 405 of file plane_supported_cuboid_estimator.h.

◆ init_dz_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_variance_
protected

Definition at line 406 of file plane_supported_cuboid_estimator.h.

◆ init_global_orientation_yaw_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_mean_
protected

Definition at line 395 of file plane_supported_cuboid_estimator.h.

◆ init_global_orientation_yaw_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_variance_
protected

Definition at line 396 of file plane_supported_cuboid_estimator.h.

◆ init_local_orientation_pitch_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_mean_
protected

Definition at line 390 of file plane_supported_cuboid_estimator.h.

◆ init_local_orientation_pitch_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_variance_
protected

Definition at line 391 of file plane_supported_cuboid_estimator.h.

◆ init_local_orientation_roll_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_mean_
protected

Definition at line 388 of file plane_supported_cuboid_estimator.h.

◆ init_local_orientation_roll_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_variance_
protected

Definition at line 389 of file plane_supported_cuboid_estimator.h.

◆ init_local_orientation_yaw_mean_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_mean_
protected

Definition at line 392 of file plane_supported_cuboid_estimator.h.

◆ init_local_orientation_yaw_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_variance_
protected

Definition at line 393 of file plane_supported_cuboid_estimator.h.

◆ init_local_position_z_max_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_max_
protected

Definition at line 384 of file plane_supported_cuboid_estimator.h.

◆ init_local_position_z_min_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_min_
protected

Definition at line 383 of file plane_supported_cuboid_estimator.h.

◆ init_world_position_z_max_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_max_
protected

Definition at line 387 of file plane_supported_cuboid_estimator.h.

◆ init_world_position_z_min_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_min_
protected

Definition at line 386 of file plane_supported_cuboid_estimator.h.

◆ latest_coefficients_msg_

jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_coefficients_msg_
protected

Definition at line 377 of file plane_supported_cuboid_estimator.h.

◆ latest_polygon_msg_

jsk_recognition_msgs::PolygonArray::ConstPtr jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_polygon_msg_
protected

Definition at line 376 of file plane_supported_cuboid_estimator.h.

◆ min_dx_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dx_
protected

Definition at line 418 of file plane_supported_cuboid_estimator.h.

◆ min_dy_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dy_
protected

Definition at line 419 of file plane_supported_cuboid_estimator.h.

◆ min_dz_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dz_
protected

Definition at line 420 of file plane_supported_cuboid_estimator.h.

◆ mutex_

boost::mutex jsk_pcl_ros::PlaneSupportedCuboidEstimator::mutex_
protected

Definition at line 356 of file plane_supported_cuboid_estimator.h.

◆ particle_num_

int jsk_pcl_ros::PlaneSupportedCuboidEstimator::particle_num_
protected

Definition at line 423 of file plane_supported_cuboid_estimator.h.

◆ polygons_

std::vector<Polygon::Ptr> jsk_pcl_ros::PlaneSupportedCuboidEstimator::polygons_
protected

Definition at line 430 of file plane_supported_cuboid_estimator.h.

◆ pub_candidate_cloud_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_candidate_cloud_
protected

Definition at line 361 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_dx_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dx_
protected

Definition at line 368 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_dy_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dy_
protected

Definition at line 369 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_dz_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dz_
protected

Definition at line 370 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_global_pitch_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_pitch_
protected

Definition at line 366 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_global_roll_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_roll_
protected

Definition at line 365 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_global_x_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_x_
protected

Definition at line 362 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_global_y_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_y_
protected

Definition at line 363 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_global_yaw_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_yaw_
protected

Definition at line 367 of file plane_supported_cuboid_estimator.h.

◆ pub_histogram_global_z_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_z_
protected

Definition at line 364 of file plane_supported_cuboid_estimator.h.

◆ pub_particles_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_particles_
protected

Definition at line 360 of file plane_supported_cuboid_estimator.h.

◆ pub_result_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_result_
protected

Definition at line 359 of file plane_supported_cuboid_estimator.h.

◆ pub_result_pose_

ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_result_pose_
protected

Definition at line 371 of file plane_supported_cuboid_estimator.h.

◆ random_generator_

boost::mt19937 jsk_pcl_ros::PlaneSupportedCuboidEstimator::random_generator_
protected

Definition at line 425 of file plane_supported_cuboid_estimator.h.

◆ sensor_frame_

std::string jsk_pcl_ros::PlaneSupportedCuboidEstimator::sensor_frame_
protected

Definition at line 424 of file plane_supported_cuboid_estimator.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PlaneSupportedCuboidEstimator::srv_
protected

Definition at line 379 of file plane_supported_cuboid_estimator.h.

◆ srv_reset_

ros::ServiceServer jsk_pcl_ros::PlaneSupportedCuboidEstimator::srv_reset_
protected

Definition at line 372 of file plane_supported_cuboid_estimator.h.

◆ step_dx_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dx_variance_
protected

Definition at line 414 of file plane_supported_cuboid_estimator.h.

◆ step_dy_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dy_variance_
protected

Definition at line 415 of file plane_supported_cuboid_estimator.h.

◆ step_dz_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dz_variance_
protected

Definition at line 416 of file plane_supported_cuboid_estimator.h.

◆ step_pitch_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_pitch_variance_
protected

Definition at line 412 of file plane_supported_cuboid_estimator.h.

◆ step_roll_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_roll_variance_
protected

Definition at line 411 of file plane_supported_cuboid_estimator.h.

◆ step_x_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_x_variance_
protected

Definition at line 408 of file plane_supported_cuboid_estimator.h.

◆ step_y_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_y_variance_
protected

Definition at line 409 of file plane_supported_cuboid_estimator.h.

◆ step_yaw_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_yaw_variance_
protected

Definition at line 413 of file plane_supported_cuboid_estimator.h.

◆ step_z_variance_

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_z_variance_
protected

Definition at line 410 of file plane_supported_cuboid_estimator.h.

◆ sub_cloud_

ros::Subscriber jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_cloud_
protected

Definition at line 357 of file plane_supported_cuboid_estimator.h.

◆ sub_coefficients_

message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_coefficients_
protected

Definition at line 374 of file plane_supported_cuboid_estimator.h.

◆ sub_fast_cloud_

ros::Subscriber jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_fast_cloud_
protected

Definition at line 358 of file plane_supported_cuboid_estimator.h.

◆ sub_polygon_

message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_polygon_
protected

Definition at line 373 of file plane_supported_cuboid_estimator.h.

◆ support_plane_updated_

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::support_plane_updated_
protected

Definition at line 428 of file plane_supported_cuboid_estimator.h.

◆ sync_polygon_

boost::shared_ptr<message_filters::Synchronizer<PolygonSyncPolicy> > jsk_pcl_ros::PlaneSupportedCuboidEstimator::sync_polygon_
protected

Definition at line 375 of file plane_supported_cuboid_estimator.h.

◆ tf_

tf::TransformListener* jsk_pcl_ros::PlaneSupportedCuboidEstimator::tf_
protected

Definition at line 426 of file plane_supported_cuboid_estimator.h.

◆ tracker_

pcl::tracking::ROSCollaborativeParticleFilterTracker<pcl::PointXYZ, pcl::tracking::ParticleCuboid>::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::tracker_
protected

Definition at line 429 of file plane_supported_cuboid_estimator.h.

◆ tree_

pcl::KdTreeFLANN<pcl::PointXYZ> jsk_pcl_ros::PlaneSupportedCuboidEstimator::tree_
protected

Definition at line 431 of file plane_supported_cuboid_estimator.h.

◆ use_global_init_yaw_

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_global_init_yaw_
protected

Definition at line 394 of file plane_supported_cuboid_estimator.h.

◆ use_init_polygon_likelihood_

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_polygon_likelihood_
protected

Definition at line 422 of file plane_supported_cuboid_estimator.h.

◆ use_init_world_position_z_model_

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_world_position_z_model_
protected

Definition at line 385 of file plane_supported_cuboid_estimator.h.

◆ viewpoint_

Eigen::Vector3f jsk_pcl_ros::PlaneSupportedCuboidEstimator::viewpoint_
protected

Definition at line 427 of file plane_supported_cuboid_estimator.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46