Classes | Typedefs | Functions
jsk_pcl_ros Namespace Reference

Classes

class  AddColorFromImage
class  AddColorFromImageToOrganized
class  AttentionClipper
class  BilateralFilter
class  BorderEstimator
class  BoundingBoxFilter
class  BoundingBoxOcclusionRejector
class  CapturedSamplePointCloud
class  CaptureStereoSynchronizer
class  ClusterPointIndicesDecomposer
class  ClusterPointIndicesDecomposerZAxis
class  CollisionDetector
class  ColorBasedRegionGrowingSegmentation
class  ColorFilter
class  ColorHistogram
class  ColorHistogramClassifier
class  ColorHistogramFilter
class  ColorHistogramMatcher
class  ColorizeMapRandomForest
class  ColorizeRandomForest
class  ConvexConnectedVoxels
class  CubeHypothesis
class  DepthCalibration
class  DepthImageCreator
class  DiagnoalCubeHypothesis
class  EdgebasedCubeFinder
class  EdgeDepthRefinement
class  EnvironmentPlaneModeling
 Nodelet implementation of jsk_pcl/EnvironmentPlaneModeling. More...
class  EuclideanClustering
class  ExtractCuboidParticlesTopN
class  ExtractIndices
class  FeatureRegistration
 Nodelet implementation of jsk_pcl/FeatureRegistration. More...
class  FindObjectOnPlane
class  FisheyeSpherePublisher
class  FuseDepthImages
class  FuseImages
class  FuseRGBImages
class  GeometricConsistencyGrouping
 Nodelet implementation of jsk_pcl/GeometricConsistencyGrouping. More...
class  GridSampler
class  HandleEstimator
class  HeightmapConverter
class  HeightmapMorphologicalFiltering
class  HeightmapTimeAccumulation
class  HeightmapToPointCloud
class  HintedHandleEstimator
class  HintedPlaneDetector
class  HintedStickFinder
class  HSIColorFilter
class  ICPRegistration
class  ImageRotateNodelet
class  IncrementalModelRegistration
class  InteractiveCuboidLikelihood
class  IntermittentImageAnnotator
class  JointStateStaticFilter
class  KeypointsPublisher
class  Kinfu
class  LINEMODDetector
class  LINEMODTrainer
class  LineSegment
class  LineSegmentCluster
class  LineSegmentCollector
class  LineSegmentDetector
class  MaskImageClusterFilter
class  MaskImageFilter
class  MovingLeastSquareSmoothing
class  MultiPlaneExtraction
class  MultiPlaneSACSegmentation
class  NormalDirectionFilter
class  NormalEstimationIntegralImage
class  NormalEstimationOMP
class  OctomapServerContact
class  OctreeChangePublisher
 Realtime change detection of pointcloud using octree. See paper below: More...
class  OctreeVoxelGrid
class  OneDataStat
 class to store sensor value and compute mean, error and stddev and so on. More...
class  OrganizedEdgeDetector
class  OrganizedMultiPlaneSegmentation
class  OrganizedPassThrough
class  OrganizePointCloud
class  ParallelEdgeFinder
class  ParticleFilterTracking
class  PeopleDetection
class  PlanarCubeHypothesis
class  PlaneSupportedCuboidEstimator
class  PointCloudData
class  PointcloudDatabaseServer
class  PointCloudLocalization
class  PointCloudMoveitFilter
class  PointcloudScreenpoint
class  PPFRegistration
class  PrimitiveShapeClassifier
class  RearrangeBoundingBox
class  RegionAdjacencyGraph
class  RegionGrowingMultiplePlaneSegmentation
class  RegionGrowingSegmentation
class  ResizePointsPublisher
class  RGBColorFilter
class  ROIClipper
class  SelectedClusterPublisher
class  SnapIt
class  SnapshotInformation
class  StampedJointAngle
class  SupervoxelSegmentation
class  TargetAdaptiveTracking
class  TiltLaserListener
class  TimeStampedVector
class  TorusFinder
class  UniformSampling
class  ViewpointSampler
class  VoxelGridDownsampleDecoder
class  VoxelGridDownsampleManager
class  VoxelGridLargeScale

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.
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
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
double mean (const OneDataStat &d)
 wrapper function for mean method for boost::function
double min (const OneDataStat &d)
 wrapper function for min method for boost::function
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
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

Typedef Documentation

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.

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 61 of file pointcloud_moveit_filter.h.

Definition at line 62 of file pointcloud_moveit_filter.h.


Function Documentation

double jsk_pcl_ros::binaryLikelihood ( double  v,
double  min,
double  max 
) [inline]

return 1.0 if v satisfies min < v < max, return 0 otherwise.

Definition at line 75 of file plane_supported_cuboid_estimator.h.

template<class PARTICLE_T >
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.

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 
)

Definition at line 244 of file plane_supported_cuboid_estimator.h.

void jsk_pcl_ros::convertHeightMapToPCL ( const cv::Mat &  float_image,
pcl::PointCloud< HeightMapPointType > &  cloud,
float  max_x_,
float  min_x_,
float  max_y_,
float  min_y_ 
) [inline]

Definition at line 52 of file heightmap_utils.h.

void jsk_pcl_ros::convertHeightMapToPCLOrganize ( const cv::Mat &  float_image,
pcl::PointCloud< HeightMapPointType > &  cloud,
float  max_x_,
float  min_x_,
float  max_y_,
float  min_y_ 
) [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.

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 
)

Definition at line 149 of file plane_supported_cuboid_estimator.h.

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.

template<class Config >
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.

void jsk_pcl_ros::PointCloudXYZRGBtoXYZI ( pcl::PointCloud< pcl::PointXYZRGB > &  in,
pcl::PointCloud< pcl::PointXYZI > &  out 
) [inline]

Definition at line 63 of file bilateral_filter.h.

void jsk_pcl_ros::PointXYZRGBtoXYZI ( pcl::PointXYZRGB &  in,
pcl::PointXYZI &  out 
) [inline]

Definition at line 54 of file bilateral_filter.h.

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 
)

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.

template<class Config >
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.

template<class Config >
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.



jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:46