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 Types inherited from jsk_topic_tools::DiagnosticNodelet
typedef boost::shared_ptr< DiagnosticNodeletPtr
 

Public Member Functions

 PlaneSupportedCuboidEstimator ()
 
- 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 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 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
 

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_
 
- 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 268 of file plane_supported_cuboid_estimator.h.

Member Typedef Documentation

typedef PlaneSupportedCuboidEstimatorConfig jsk_pcl_ros::PlaneSupportedCuboidEstimator::Config

Definition at line 274 of file plane_supported_cuboid_estimator.h.

Definition at line 271 of file plane_supported_cuboid_estimator.h.

Definition at line 272 of file plane_supported_cuboid_estimator.h.

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

Definition at line 277 of file plane_supported_cuboid_estimator.h.

Definition at line 273 of file plane_supported_cuboid_estimator.h.

Constructor & Destructor Documentation

jsk_pcl_ros::PlaneSupportedCuboidEstimator::PlaneSupportedCuboidEstimator ( )
inline

Definition at line 279 of file plane_supported_cuboid_estimator.h.

Member Function Documentation

size_t jsk_pcl_ros::PlaneSupportedCuboidEstimator::chooseUniformRandomPlaneIndex ( const std::vector< Polygon::Ptr > &  polygons)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::cloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::fastCloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual
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 98 of file plane_supported_cuboid_estimator_nodelet.cpp.

pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::initParticles ( )
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::likelihood ( pcl::PointCloud< pcl::PointXYZ >::ConstPtr  input,
pcl::tracking::ParticleCuboid p 
)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::onInit ( void  )
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::polygonCallback ( const jsk_recognition_msgs::PolygonArray::ConstPtr &  polygon_msg,
const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &  coef_msg 
)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::publishHistogram ( ParticleCloud::Ptr  particles,
int  index,
ros::Publisher pub,
const std_msgs::Header header 
)
protectedvirtual
bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::resetCallback ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
)
protectedvirtual
pcl::tracking::ParticleCuboid jsk_pcl_ros::PlaneSupportedCuboidEstimator::sample ( const pcl::tracking::ParticleCuboid p)
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::subscribe ( )
protectedvirtual
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::unsubscribe ( )
protectedvirtual
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 118 of file plane_supported_cuboid_estimator_nodelet.cpp.

Member Data Documentation

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

Definition at line 346 of file plane_supported_cuboid_estimator.h.

Config jsk_pcl_ros::PlaneSupportedCuboidEstimator::config_
protected

Definition at line 350 of file plane_supported_cuboid_estimator.h.

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_pitch_
protected

Definition at line 367 of file plane_supported_cuboid_estimator.h.

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_roll_
protected

Definition at line 366 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::fast_cloud_threshold_
protected

Definition at line 389 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_mean_
protected

Definition at line 369 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_variance_
protected

Definition at line 370 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_mean_
protected

Definition at line 371 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_variance_
protected

Definition at line 372 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_mean_
protected

Definition at line 373 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_variance_
protected

Definition at line 374 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_mean_
protected

Definition at line 363 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_variance_
protected

Definition at line 364 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_mean_
protected

Definition at line 358 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_variance_
protected

Definition at line 359 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_mean_
protected

Definition at line 356 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_variance_
protected

Definition at line 357 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_mean_
protected

Definition at line 360 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_variance_
protected

Definition at line 361 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_max_
protected

Definition at line 352 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_min_
protected

Definition at line 351 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_max_
protected

Definition at line 355 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_min_
protected

Definition at line 354 of file plane_supported_cuboid_estimator.h.

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

Definition at line 345 of file plane_supported_cuboid_estimator.h.

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

Definition at line 344 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dx_
protected

Definition at line 386 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dy_
protected

Definition at line 387 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dz_
protected

Definition at line 388 of file plane_supported_cuboid_estimator.h.

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

Definition at line 324 of file plane_supported_cuboid_estimator.h.

int jsk_pcl_ros::PlaneSupportedCuboidEstimator::particle_num_
protected

Definition at line 391 of file plane_supported_cuboid_estimator.h.

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

Definition at line 398 of file plane_supported_cuboid_estimator.h.

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

Definition at line 329 of file plane_supported_cuboid_estimator.h.

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

Definition at line 336 of file plane_supported_cuboid_estimator.h.

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

Definition at line 337 of file plane_supported_cuboid_estimator.h.

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

Definition at line 338 of file plane_supported_cuboid_estimator.h.

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

Definition at line 334 of file plane_supported_cuboid_estimator.h.

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

Definition at line 333 of file plane_supported_cuboid_estimator.h.

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

Definition at line 330 of file plane_supported_cuboid_estimator.h.

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

Definition at line 331 of file plane_supported_cuboid_estimator.h.

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

Definition at line 335 of file plane_supported_cuboid_estimator.h.

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

Definition at line 332 of file plane_supported_cuboid_estimator.h.

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

Definition at line 328 of file plane_supported_cuboid_estimator.h.

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

Definition at line 327 of file plane_supported_cuboid_estimator.h.

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

Definition at line 339 of file plane_supported_cuboid_estimator.h.

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

Definition at line 393 of file plane_supported_cuboid_estimator.h.

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

Definition at line 392 of file plane_supported_cuboid_estimator.h.

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

Definition at line 347 of file plane_supported_cuboid_estimator.h.

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

Definition at line 340 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dx_variance_
protected

Definition at line 382 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dy_variance_
protected

Definition at line 383 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dz_variance_
protected

Definition at line 384 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_pitch_variance_
protected

Definition at line 380 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_roll_variance_
protected

Definition at line 379 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_x_variance_
protected

Definition at line 376 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_y_variance_
protected

Definition at line 377 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_yaw_variance_
protected

Definition at line 381 of file plane_supported_cuboid_estimator.h.

double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_z_variance_
protected

Definition at line 378 of file plane_supported_cuboid_estimator.h.

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

Definition at line 325 of file plane_supported_cuboid_estimator.h.

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

Definition at line 342 of file plane_supported_cuboid_estimator.h.

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

Definition at line 326 of file plane_supported_cuboid_estimator.h.

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

Definition at line 341 of file plane_supported_cuboid_estimator.h.

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::support_plane_updated_
protected

Definition at line 396 of file plane_supported_cuboid_estimator.h.

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

Definition at line 343 of file plane_supported_cuboid_estimator.h.

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

Definition at line 394 of file plane_supported_cuboid_estimator.h.

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

Definition at line 397 of file plane_supported_cuboid_estimator.h.

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

Definition at line 399 of file plane_supported_cuboid_estimator.h.

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_global_init_yaw_
protected

Definition at line 362 of file plane_supported_cuboid_estimator.h.

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_polygon_likelihood_
protected

Definition at line 390 of file plane_supported_cuboid_estimator.h.

bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_world_position_z_model_
protected

Definition at line 353 of file plane_supported_cuboid_estimator.h.

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

Definition at line 395 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 Mon May 3 2021 03:03:48