Classes | Namespaces | Functions
plane_supported_cuboid_estimator.h File Reference
#include <jsk_topic_tools/diagnostic_nodelet.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/synchronizer.h>
#include <boost/random.hpp>
#include <dynamic_reconfigure/server.h>
#include "jsk_pcl_ros/geo_util.h"
#include "jsk_pcl_ros/pcl_conversion_util.h"
#include "jsk_pcl_ros/tf_listener_singleton.h"
#include <algorithm>
#include <jsk_recognition_msgs/PolygonArray.h>
#include <jsk_recognition_msgs/BoundingBoxArray.h>
#include <jsk_recognition_msgs/ModelCoefficientsArray.h>
#include <jsk_recognition_msgs/HistogramWithRange.h>
#include <jsk_pcl_ros/PlaneSupportedCuboidEstimatorConfig.h>
#include <sensor_msgs/PointCloud2.h>
#include <std_srvs/Empty.h>
#include <pcl/tracking/tracking.h>
#include "jsk_pcl_ros/pcl/simple_particle_filter.h"
#include "jsk_pcl_ros/pcl/particle_cuboid.h"
#include <pcl/kdtree/kdtree_flann.h>
Include dependency graph for plane_supported_cuboid_estimator.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  jsk_pcl_ros::PlaneSupportedCuboidEstimator

Namespaces

namespace  jsk_pcl_ros

Functions

double jsk_pcl_ros::binaryLikelihood (double v, double min, double max)
 return 1.0 if v satisfies min < v < max, return 0 otherwise.
template<class Config >
double jsk_pcl_ros::computeLikelihood (const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::KdTreeFLANN< pcl::PointXYZ > &tree, const Eigen::Vector3f &viewpoint, const std::vector< Polygon::Ptr > &polygons, const std::vector< float > &polygon_likelihood, const Config &config)
template<class Config >
double jsk_pcl_ros::distanceFromPlaneBasedError (const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::KdTreeFLANN< pcl::PointXYZ > &tree, const Eigen::Vector3f &viewpoint, const Config &config)
template<class Config >
double jsk_pcl_ros::planeLikelihood (const pcl::tracking::ParticleCuboid &p, const std::vector< float > &polygon_likelihood, const Config &config)
template<class Config >
double jsk_pcl_ros::rangeLikelihood (const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, const std::vector< Polygon::Ptr > &planes, const Config &config)
template<class Config >
double jsk_pcl_ros::supportPlaneAngularLikelihood (const pcl::tracking::ParticleCuboid &p, const std::vector< Polygon::Ptr > &planes, const Config &config)
template<class Config >
double jsk_pcl_ros::surfaceAreaLikelihood (const pcl::tracking::ParticleCuboid &p, const Config &config)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49