#include <plane_supported_cuboid_estimator.h>
◆ Config
◆ Particle
◆ ParticleCloud
◆ PolygonSyncPolicy
◆ Ptr
◆ PlaneSupportedCuboidEstimator()
| jsk_pcl_ros::PlaneSupportedCuboidEstimator::PlaneSupportedCuboidEstimator |
( |
| ) |
|
|
inline |
◆ ~PlaneSupportedCuboidEstimator()
| jsk_pcl_ros::PlaneSupportedCuboidEstimator::~PlaneSupportedCuboidEstimator |
( |
| ) |
|
|
virtual |
◆ 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()
◆ initParticles()
◆ likelihood()
◆ onInit()
| void jsk_pcl_ros::PlaneSupportedCuboidEstimator::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ 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()
◆ subscribe()
| void jsk_pcl_ros::PlaneSupportedCuboidEstimator::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ 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.
◆ candidate_cloud_
| pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::candidate_cloud_ |
|
protected |
◆ config_
| Config jsk_pcl_ros::PlaneSupportedCuboidEstimator::config_ |
|
protected |
◆ disable_init_pitch_
| bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_pitch_ |
|
protected |
◆ disable_init_roll_
| bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::disable_init_roll_ |
|
protected |
◆ fast_cloud_threshold_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::fast_cloud_threshold_ |
|
protected |
◆ init_dx_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_mean_ |
|
protected |
◆ init_dx_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_variance_ |
|
protected |
◆ init_dy_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_mean_ |
|
protected |
◆ init_dy_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_variance_ |
|
protected |
◆ init_dz_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_mean_ |
|
protected |
◆ init_dz_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_variance_ |
|
protected |
◆ init_global_orientation_yaw_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_mean_ |
|
protected |
◆ init_global_orientation_yaw_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_global_orientation_yaw_variance_ |
|
protected |
◆ init_local_orientation_pitch_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_mean_ |
|
protected |
◆ init_local_orientation_pitch_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_variance_ |
|
protected |
◆ init_local_orientation_roll_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_mean_ |
|
protected |
◆ init_local_orientation_roll_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_variance_ |
|
protected |
◆ init_local_orientation_yaw_mean_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_mean_ |
|
protected |
◆ init_local_orientation_yaw_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_variance_ |
|
protected |
◆ init_local_position_z_max_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_max_ |
|
protected |
◆ init_local_position_z_min_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_min_ |
|
protected |
◆ init_world_position_z_max_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_max_ |
|
protected |
◆ init_world_position_z_min_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_min_ |
|
protected |
◆ latest_coefficients_msg_
| jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_coefficients_msg_ |
|
protected |
◆ latest_polygon_msg_
| jsk_recognition_msgs::PolygonArray::ConstPtr jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_polygon_msg_ |
|
protected |
◆ min_dx_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dx_ |
|
protected |
◆ min_dy_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dy_ |
|
protected |
◆ min_dz_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dz_ |
|
protected |
◆ mutex_
| boost::mutex jsk_pcl_ros::PlaneSupportedCuboidEstimator::mutex_ |
|
protected |
◆ particle_num_
| int jsk_pcl_ros::PlaneSupportedCuboidEstimator::particle_num_ |
|
protected |
◆ polygons_
◆ pub_candidate_cloud_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_candidate_cloud_ |
|
protected |
◆ pub_histogram_dx_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dx_ |
|
protected |
◆ pub_histogram_dy_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dy_ |
|
protected |
◆ pub_histogram_dz_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_dz_ |
|
protected |
◆ pub_histogram_global_pitch_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_pitch_ |
|
protected |
◆ pub_histogram_global_roll_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_roll_ |
|
protected |
◆ pub_histogram_global_x_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_x_ |
|
protected |
◆ pub_histogram_global_y_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_y_ |
|
protected |
◆ pub_histogram_global_yaw_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_yaw_ |
|
protected |
◆ pub_histogram_global_z_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_histogram_global_z_ |
|
protected |
◆ pub_particles_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_particles_ |
|
protected |
◆ pub_result_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_result_ |
|
protected |
◆ pub_result_pose_
| ros::Publisher jsk_pcl_ros::PlaneSupportedCuboidEstimator::pub_result_pose_ |
|
protected |
◆ random_generator_
| boost::mt19937 jsk_pcl_ros::PlaneSupportedCuboidEstimator::random_generator_ |
|
protected |
◆ sensor_frame_
| std::string jsk_pcl_ros::PlaneSupportedCuboidEstimator::sensor_frame_ |
|
protected |
◆ srv_
◆ srv_reset_
◆ step_dx_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dx_variance_ |
|
protected |
◆ step_dy_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dy_variance_ |
|
protected |
◆ step_dz_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dz_variance_ |
|
protected |
◆ step_pitch_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_pitch_variance_ |
|
protected |
◆ step_roll_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_roll_variance_ |
|
protected |
◆ step_x_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_x_variance_ |
|
protected |
◆ step_y_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_y_variance_ |
|
protected |
◆ step_yaw_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_yaw_variance_ |
|
protected |
◆ step_z_variance_
| double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_z_variance_ |
|
protected |
◆ sub_cloud_
◆ sub_coefficients_
| message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_coefficients_ |
|
protected |
◆ sub_fast_cloud_
| ros::Subscriber jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_fast_cloud_ |
|
protected |
◆ sub_polygon_
◆ support_plane_updated_
| bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::support_plane_updated_ |
|
protected |
◆ sync_polygon_
◆ tf_
◆ tracker_
◆ tree_
| pcl::KdTreeFLANN<pcl::PointXYZ> jsk_pcl_ros::PlaneSupportedCuboidEstimator::tree_ |
|
protected |
◆ use_global_init_yaw_
| bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_global_init_yaw_ |
|
protected |
◆ use_init_polygon_likelihood_
| bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_polygon_likelihood_ |
|
protected |
◆ use_init_world_position_z_model_
| bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::use_init_world_position_z_model_ |
|
protected |
◆ viewpoint_
The documentation for this class was generated from the following files: