#include <plane_supported_cuboid_estimator.h>
Definition at line 243 of file plane_supported_cuboid_estimator.h.
typedef PlaneSupportedCuboidEstimatorConfig jsk_pcl_ros::PlaneSupportedCuboidEstimator::Config |
Definition at line 249 of file plane_supported_cuboid_estimator.h.
Definition at line 246 of file plane_supported_cuboid_estimator.h.
Definition at line 247 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 252 of file plane_supported_cuboid_estimator.h.
typedef boost::shared_ptr<PlaneSupportedCuboidEstimator> jsk_pcl_ros::PlaneSupportedCuboidEstimator::Ptr |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 248 of file plane_supported_cuboid_estimator.h.
Definition at line 254 of file plane_supported_cuboid_estimator.h.
size_t jsk_pcl_ros::PlaneSupportedCuboidEstimator::chooseUniformRandomPlaneIndex | ( | const std::vector< Polygon::Ptr > & | polygons | ) | [protected, virtual] |
Definition at line 318 of file plane_supported_cuboid_estimator_nodelet.cpp.
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::cloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [protected, virtual] |
Definition at line 137 of file plane_supported_cuboid_estimator_nodelet.cpp.
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 384 of file plane_supported_cuboid_estimator_nodelet.cpp.
size_t jsk_pcl_ros::PlaneSupportedCuboidEstimator::getNearestPolygon | ( | const Particle & | p, |
const std::vector< ConvexPolygon::Ptr > & | polygons | ||
) | [protected, virtual] |
Compute the nearest polygon to the particle `p'.
Definition at line 92 of file plane_supported_cuboid_estimator_nodelet.cpp.
pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::initParticles | ( | ) | [protected, virtual] |
Definition at line 343 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] |
Definition at line 300 of file plane_supported_cuboid_estimator_nodelet.cpp.
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::onInit | ( | void | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 50 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] |
Definition at line 308 of file plane_supported_cuboid_estimator_nodelet.cpp.
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::publishHistogram | ( | ParticleCloud::Ptr | particles, |
int | index, | ||
ros::Publisher & | pub, | ||
const std_msgs::Header & | header | ||
) | [protected, virtual] |
Definition at line 239 of file plane_supported_cuboid_estimator_nodelet.cpp.
bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::resetCallback | ( | std_srvs::EmptyRequest & | req, |
std_srvs::EmptyResponse & | res | ||
) | [protected, virtual] |
Definition at line 419 of file plane_supported_cuboid_estimator_nodelet.cpp.
pcl::tracking::ParticleCuboid jsk_pcl_ros::PlaneSupportedCuboidEstimator::sample | ( | const pcl::tracking::ParticleCuboid & | p | ) | [protected, virtual] |
Definition at line 271 of file plane_supported_cuboid_estimator_nodelet.cpp.
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 82 of file plane_supported_cuboid_estimator_nodelet.cpp.
void jsk_pcl_ros::PlaneSupportedCuboidEstimator::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 87 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 112 of file plane_supported_cuboid_estimator_nodelet.cpp.
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::PlaneSupportedCuboidEstimator::candidate_cloud_ [protected] |
Definition at line 315 of file plane_supported_cuboid_estimator.h.
Definition at line 319 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_mean_ [protected] |
Definition at line 331 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dx_variance_ [protected] |
Definition at line 332 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_mean_ [protected] |
Definition at line 333 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dy_variance_ [protected] |
Definition at line 334 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_mean_ [protected] |
Definition at line 335 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_dz_variance_ [protected] |
Definition at line 336 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_pitch_variance_ [protected] |
Definition at line 326 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_roll_variance_ [protected] |
Definition at line 325 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_orientation_yaw_mean_ [protected] |
Definition at line 328 of file plane_supported_cuboid_estimator.h.
Definition at line 329 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_max_ [protected] |
Definition at line 321 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_local_position_z_min_ [protected] |
Definition at line 320 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_max_ [protected] |
Definition at line 324 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::init_world_position_z_min_ [protected] |
Definition at line 323 of file plane_supported_cuboid_estimator.h.
jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_coefficients_msg_ [protected] |
Definition at line 314 of file plane_supported_cuboid_estimator.h.
jsk_recognition_msgs::PolygonArray::ConstPtr jsk_pcl_ros::PlaneSupportedCuboidEstimator::latest_polygon_msg_ [protected] |
Definition at line 313 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dx_ [protected] |
Definition at line 348 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dy_ [protected] |
Definition at line 349 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::min_dz_ [protected] |
Definition at line 350 of file plane_supported_cuboid_estimator.h.
Definition at line 295 of file plane_supported_cuboid_estimator.h.
int jsk_pcl_ros::PlaneSupportedCuboidEstimator::particle_num_ [protected] |
Definition at line 352 of file plane_supported_cuboid_estimator.h.
Definition at line 359 of file plane_supported_cuboid_estimator.h.
Definition at line 299 of file plane_supported_cuboid_estimator.h.
Definition at line 306 of file plane_supported_cuboid_estimator.h.
Definition at line 307 of file plane_supported_cuboid_estimator.h.
Definition at line 308 of file plane_supported_cuboid_estimator.h.
Definition at line 304 of file plane_supported_cuboid_estimator.h.
Definition at line 303 of file plane_supported_cuboid_estimator.h.
Definition at line 300 of file plane_supported_cuboid_estimator.h.
Definition at line 301 of file plane_supported_cuboid_estimator.h.
Definition at line 305 of file plane_supported_cuboid_estimator.h.
Definition at line 302 of file plane_supported_cuboid_estimator.h.
Definition at line 298 of file plane_supported_cuboid_estimator.h.
Definition at line 297 of file plane_supported_cuboid_estimator.h.
boost::mt19937 jsk_pcl_ros::PlaneSupportedCuboidEstimator::random_generator_ [protected] |
Definition at line 354 of file plane_supported_cuboid_estimator.h.
Definition at line 353 of file plane_supported_cuboid_estimator.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PlaneSupportedCuboidEstimator::srv_ [protected] |
Definition at line 316 of file plane_supported_cuboid_estimator.h.
Definition at line 309 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dx_variance_ [protected] |
Definition at line 344 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dy_variance_ [protected] |
Definition at line 345 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_dz_variance_ [protected] |
Definition at line 346 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_pitch_variance_ [protected] |
Definition at line 342 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_roll_variance_ [protected] |
Definition at line 341 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_x_variance_ [protected] |
Definition at line 338 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_y_variance_ [protected] |
Definition at line 339 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_yaw_variance_ [protected] |
Definition at line 343 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::PlaneSupportedCuboidEstimator::step_z_variance_ [protected] |
Definition at line 340 of file plane_supported_cuboid_estimator.h.
Definition at line 296 of file plane_supported_cuboid_estimator.h.
message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_coefficients_ [protected] |
Definition at line 311 of file plane_supported_cuboid_estimator.h.
message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::PlaneSupportedCuboidEstimator::sub_polygon_ [protected] |
Definition at line 310 of file plane_supported_cuboid_estimator.h.
bool jsk_pcl_ros::PlaneSupportedCuboidEstimator::support_plane_updated_ [protected] |
Definition at line 357 of file plane_supported_cuboid_estimator.h.
boost::shared_ptr<message_filters::Synchronizer<PolygonSyncPolicy> > jsk_pcl_ros::PlaneSupportedCuboidEstimator::sync_polygon_ [protected] |
Definition at line 312 of file plane_supported_cuboid_estimator.h.
Definition at line 355 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 358 of file plane_supported_cuboid_estimator.h.
pcl::KdTreeFLANN<pcl::PointXYZ> jsk_pcl_ros::PlaneSupportedCuboidEstimator::tree_ [protected] |
Definition at line 360 of file plane_supported_cuboid_estimator.h.
Definition at line 351 of file plane_supported_cuboid_estimator.h.
Definition at line 322 of file plane_supported_cuboid_estimator.h.
Eigen::Vector3f jsk_pcl_ros::PlaneSupportedCuboidEstimator::viewpoint_ [protected] |
Definition at line 356 of file plane_supported_cuboid_estimator.h.