Typedefs | |
typedef boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > | CoefficientsPair |
typedef boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > | CoefficientsTriple |
typedef pcl::PointXYZI | HeightMapPointType |
typedef boost::tuple< IndicesTriple, CoefficientsTriple > | IndicesCoefficientsTriple |
typedef boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > | IndicesPair |
typedef boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > | IndicesTriple |
typedef pcl::PointXYZI | PointType |
typedef occupancy_map_monitor::ShapeHandle | ShapeHandle |
typedef occupancy_map_monitor::ShapeTransformCache | ShapeTransformCache |
Functions | |
double | binaryLikelihood (double v, double min, double max) |
return 1.0 if v satisfies min < v < max, return 0 otherwise. More... | |
template<class PARTICLE_T > | |
bool | compareParticleWeight (const PARTICLE_T &a, const PARTICLE_T &b) |
template<class Config > | |
double | 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) |
void | convertHeightMapToPCL (const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_) |
void | convertHeightMapToPCLOrganize (const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_) |
double | count (const OneDataStat &d) |
wrapper function for count method for boost::function More... | |
template<class Config > | |
double | distanceFromPlaneBasedError (const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::KdTreeFLANN< pcl::PointXYZ > &tree, const Eigen::Vector3f &viewpoint, const Config &config) |
std::string | getHeightmapConfigTopic (const std::string &base_topic) |
double | max (const OneDataStat &d) |
wrapper function for max method for boost::function More... | |
double | mean (const OneDataStat &d) |
wrapper function for mean method for boost::function More... | |
double | min (const OneDataStat &d) |
wrapper function for min method for boost::function More... | |
template<class Config > | |
double | planeLikelihood (const pcl::tracking::ParticleCuboid &p, const std::vector< float > &polygon_likelihood, const Config &config) |
void | PointCloudXYZRGBtoXYZI (pcl::PointCloud< pcl::PointXYZRGB > &in, pcl::PointCloud< pcl::PointXYZI > &out) |
void | PointXYZRGBtoXYZI (pcl::PointXYZRGB &in, pcl::PointXYZI &out) |
template<class Config > | |
double | rangeLikelihood (const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, const std::vector< Polygon::Ptr > &planes, const Config &config) |
double | stddev (const OneDataStat &d) |
wrapper function for stddev method for boost::function More... | |
template<class Config > | |
double | supportPlaneAngularLikelihood (const pcl::tracking::ParticleCuboid &p, const std::vector< Polygon::Ptr > &planes, const Config &config) |
template<class Config > | |
double | surfaceAreaLikelihood (const pcl::tracking::ParticleCuboid &p, const Config &config) |
double | variance (const OneDataStat &d) |
wrapper function for variance method for boost::function More... | |
typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr> jsk_pcl_ros::CoefficientsPair |
Definition at line 70 of file edgebased_cube_finder.h.
typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr> jsk_pcl_ros::CoefficientsTriple |
Definition at line 75 of file edgebased_cube_finder.h.
typedef pcl::PointXYZI jsk_pcl_ros::HeightMapPointType |
Definition at line 45 of file heightmap_utils.h.
typedef boost::tuple<IndicesTriple, CoefficientsTriple> jsk_pcl_ros::IndicesCoefficientsTriple |
Definition at line 77 of file edgebased_cube_finder.h.
typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr> jsk_pcl_ros::IndicesPair |
Definition at line 68 of file edgebased_cube_finder.h.
typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr> jsk_pcl_ros::IndicesTriple |
Definition at line 73 of file edgebased_cube_finder.h.
typedef pcl::PointXYZI jsk_pcl_ros::PointType |
Definition at line 63 of file heightmap_time_accumulation.h.
Definition at line 62 of file pointcloud_moveit_filter.h.
Definition at line 63 of file pointcloud_moveit_filter.h.
|
inline |
return 1.0 if v satisfies min < v < max, return 0 otherwise.
Definition at line 75 of file plane_supported_cuboid_estimator.h.
bool jsk_pcl_ros::compareParticleWeight | ( | const PARTICLE_T & | a, |
const PARTICLE_T & | b | ||
) |
Definition at line 54 of file extract_cuboid_particles_top_n.h.
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 | ||
) |
Definition at line 244 of file plane_supported_cuboid_estimator.h.
|
inline |
Definition at line 52 of file heightmap_utils.h.
|
inline |
Definition at line 77 of file heightmap_utils.h.
double jsk_pcl_ros::count | ( | const OneDataStat & | d | ) |
wrapper function for count method for boost::function
Definition at line 112 of file one_data_stat.h.
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 | ||
) |
Definition at line 149 of file plane_supported_cuboid_estimator.h.
|
inline |
Definition at line 47 of file heightmap_utils.h.
double jsk_pcl_ros::max | ( | const OneDataStat & | d | ) |
wrapper function for max method for boost::function
Definition at line 103 of file one_data_stat.h.
double jsk_pcl_ros::mean | ( | const OneDataStat & | d | ) |
wrapper function for mean method for boost::function
Definition at line 85 of file one_data_stat.h.
double jsk_pcl_ros::min | ( | const OneDataStat & | d | ) |
wrapper function for min method for boost::function
Definition at line 94 of file one_data_stat.h.
double jsk_pcl_ros::planeLikelihood | ( | const pcl::tracking::ParticleCuboid & | p, |
const std::vector< float > & | polygon_likelihood, | ||
const Config & | config | ||
) |
Definition at line 231 of file plane_supported_cuboid_estimator.h.
|
inline |
Definition at line 63 of file bilateral_filter.h.
|
inline |
Definition at line 54 of file bilateral_filter.h.
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 | ||
) |
Definition at line 89 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::stddev | ( | const OneDataStat & | d | ) |
wrapper function for stddev method for boost::function
Definition at line 130 of file one_data_stat.h.
double jsk_pcl_ros::supportPlaneAngularLikelihood | ( | const pcl::tracking::ParticleCuboid & | p, |
const std::vector< Polygon::Ptr > & | planes, | ||
const Config & | config | ||
) |
Definition at line 115 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::surfaceAreaLikelihood | ( | const pcl::tracking::ParticleCuboid & | p, |
const Config & | config | ||
) |
Definition at line 135 of file plane_supported_cuboid_estimator.h.
double jsk_pcl_ros::variance | ( | const OneDataStat & | d | ) |
wrapper function for variance method for boost::function
Definition at line 121 of file one_data_stat.h.