Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::PlaneSupportedCuboidEstimator Class Reference

#include <plane_supported_cuboid_estimator.h>

List of all members.

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
< PlaneSupportedCuboidEstimator
Ptr

Public Member Functions

 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'.
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.

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 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

Definition at line 279 of file plane_supported_cuboid_estimator.h.


Member Function Documentation

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::cloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::fastCloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]

Compute the nearest polygon to the particle `p'.

Definition at line 98 of file plane_supported_cuboid_estimator_nodelet.cpp.

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::likelihood ( pcl::PointCloud< pcl::PointXYZ >::ConstPtr  input,
pcl::tracking::ParticleCuboid p 
) [protected, virtual]
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::onInit ( void  ) [protected, virtual]

Definition at line 51 of file plane_supported_cuboid_estimator_nodelet.cpp.

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::polygonCallback ( const jsk_recognition_msgs::PolygonArray::ConstPtr &  polygon_msg,
const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &  coef_msg 
) [protected, virtual]
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::publishHistogram ( ParticleCloud::Ptr  particles,
int  index,
ros::Publisher pub,
const std_msgs::Header header 
) [protected, virtual]
bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::resetCallback ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
) [protected, virtual]

Definition at line 88 of file plane_supported_cuboid_estimator_nodelet.cpp.

Definition at line 93 of file plane_supported_cuboid_estimator_nodelet.cpp.

void jsk_pcl_ros::PlaneSupportedCuboidEstimator::updateParticlePolygonRelationship ( ParticleCloud::Ptr  particles) [protected, virtual]

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

Definition at line 346 of file plane_supported_cuboid_estimator.h.

Definition at line 350 of file plane_supported_cuboid_estimator.h.

Definition at line 367 of file plane_supported_cuboid_estimator.h.

Definition at line 366 of file plane_supported_cuboid_estimator.h.

Definition at line 389 of file plane_supported_cuboid_estimator.h.

Definition at line 369 of file plane_supported_cuboid_estimator.h.

Definition at line 370 of file plane_supported_cuboid_estimator.h.

Definition at line 371 of file plane_supported_cuboid_estimator.h.

Definition at line 372 of file plane_supported_cuboid_estimator.h.

Definition at line 373 of file plane_supported_cuboid_estimator.h.

Definition at line 374 of file plane_supported_cuboid_estimator.h.

Definition at line 363 of file plane_supported_cuboid_estimator.h.

Definition at line 364 of file plane_supported_cuboid_estimator.h.

Definition at line 358 of file plane_supported_cuboid_estimator.h.

Definition at line 359 of file plane_supported_cuboid_estimator.h.

Definition at line 356 of file plane_supported_cuboid_estimator.h.

Definition at line 357 of file plane_supported_cuboid_estimator.h.

Definition at line 360 of file plane_supported_cuboid_estimator.h.

Definition at line 361 of file plane_supported_cuboid_estimator.h.

Definition at line 352 of file plane_supported_cuboid_estimator.h.

Definition at line 351 of file plane_supported_cuboid_estimator.h.

Definition at line 355 of file plane_supported_cuboid_estimator.h.

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.

Definition at line 386 of file plane_supported_cuboid_estimator.h.

Definition at line 387 of file plane_supported_cuboid_estimator.h.

Definition at line 388 of file plane_supported_cuboid_estimator.h.

Definition at line 324 of file plane_supported_cuboid_estimator.h.

Definition at line 391 of file plane_supported_cuboid_estimator.h.

Definition at line 398 of file plane_supported_cuboid_estimator.h.

Definition at line 329 of file plane_supported_cuboid_estimator.h.

Definition at line 336 of file plane_supported_cuboid_estimator.h.

Definition at line 337 of file plane_supported_cuboid_estimator.h.

Definition at line 338 of file plane_supported_cuboid_estimator.h.

Definition at line 334 of file plane_supported_cuboid_estimator.h.

Definition at line 333 of file plane_supported_cuboid_estimator.h.

Definition at line 330 of file plane_supported_cuboid_estimator.h.

Definition at line 331 of file plane_supported_cuboid_estimator.h.

Definition at line 335 of file plane_supported_cuboid_estimator.h.

Definition at line 332 of file plane_supported_cuboid_estimator.h.

Definition at line 328 of file plane_supported_cuboid_estimator.h.

Definition at line 327 of file plane_supported_cuboid_estimator.h.

Definition at line 339 of file plane_supported_cuboid_estimator.h.

Definition at line 393 of file plane_supported_cuboid_estimator.h.

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.

Definition at line 340 of file plane_supported_cuboid_estimator.h.

Definition at line 382 of file plane_supported_cuboid_estimator.h.

Definition at line 383 of file plane_supported_cuboid_estimator.h.

Definition at line 384 of file plane_supported_cuboid_estimator.h.

Definition at line 380 of file plane_supported_cuboid_estimator.h.

Definition at line 379 of file plane_supported_cuboid_estimator.h.

Definition at line 376 of file plane_supported_cuboid_estimator.h.

Definition at line 377 of file plane_supported_cuboid_estimator.h.

Definition at line 381 of file plane_supported_cuboid_estimator.h.

Definition at line 378 of file plane_supported_cuboid_estimator.h.

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.

Definition at line 326 of file plane_supported_cuboid_estimator.h.

Definition at line 341 of file plane_supported_cuboid_estimator.h.

Definition at line 396 of file plane_supported_cuboid_estimator.h.

Definition at line 343 of file plane_supported_cuboid_estimator.h.

Definition at line 394 of file plane_supported_cuboid_estimator.h.

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.

Definition at line 362 of file plane_supported_cuboid_estimator.h.

Definition at line 390 of file plane_supported_cuboid_estimator.h.

Definition at line 353 of file plane_supported_cuboid_estimator.h.

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 Tue Jul 2 2019 19:41:47