Classes | Typedefs | Functions
jsk_pcl_ros Namespace Reference

Classes

class  AddColorFromImage
class  AddPointIndices
class  AttentionClipper
class  BilateralFilter
class  BorderEstimator
class  BoundingBoxFilter
class  BoundingBoxOcclusionRejector
class  CapturedSamplePointCloud
class  CaptureStereoSynchronizer
class  CentroidPublisher
class  ClusterPointIndicesDecomposer
class  ClusterPointIndicesDecomposerZAxis
class  ColorFilter
class  ColorHistogramMatcher
class  ColorizeDistanceFromPlane
class  ColorizeHeight2DMapping
class  ColorizeMapRandomForest
class  ColorizeRandomForest
class  ConvexConnectedVoxels
class  CubeHypothesis
class  DelayPointCloud
class  DepthCalibration
class  DepthImageCreator
class  DepthImageError
class  DiagnoalCubeHypothesis
class  EdgebasedCubeFinder
class  EdgeDepthRefinement
class  EnvironmentPlaneModeling
 Nodelet implementation of jsk_pcl/EnvironmentPlaneModeling. More...
class  EuclideanClustering
class  ExtractCuboidParticlesTopN
class  FeatureRegistration
 Nodelet implementation of jsk_pcl/FeatureRegistration. More...
class  FindObjectOnPlane
class  FisheyeSpherePublisher
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  MaskImageToDepthConsideredMaskImage
class  MaskImageToPointIndices
class  MultiPlaneExtraction
class  MultiPlaneSACSegmentation
class  NormalConcatenater
class  NormalDirectionFilter
class  NormalEstimationIntegralImage
class  NormalEstimationOMP
class  NormalFlipToFrame
class  OctreeChangePublisher
class  OneDataStat
 class to store sensor value and compute mean, error and stddev and so on. More...
class  OrganizedEdgeDetector
class  OrganizedMultiPlaneSegmentation
class  OrganizedPassThrough
class  OrganizedPointCloudToPointIndices
class  OrganizePointCloud
class  ParallelEdgeFinder
class  ParticleFilterTracking
class  PCDReaderWithPose
class  PlanarCubeHypothesis
class  PlanarPointCloudSimulator
 Utility class to generate pointcloud of depth camera and stereo camera. More...
class  PlanarPointCloudSimulatorNodelet
 Nodelet implementation of jsk_pcl/PlanarPointCloudSimulator. More...
class  PlaneConcatenator
class  PlaneReasoner
class  PlaneRejector
class  PlaneSupportedCuboidEstimator
class  PointCloudData
class  PointcloudDatabaseServer
class  PointCloudLocalization
class  PointCloudMoveitFilter
class  PointcloudScreenpoint
class  PointCloudToClusterPointIndices
class  PointCloudToSTL
class  PointIndicesToMaskImage
class  PolygonAppender
class  PolygonArrayAngleLikelihood
class  PolygonArrayAreaLikelihood
class  PolygonArrayDistanceLikelihood
class  PolygonArrayTransformer
class  PolygonArrayWrapper
class  PolygonFlipper
class  PolygonMagnifier
class  PolygonPointsSampler
class  PoseWithCovarianceStampedToGaussianPointCloud
class  RegionAdjacencyGraph
class  RegionGrowingMultiplePlaneSegmentation
class  RegionGrowingSegmentation
class  ResizePointsPublisher
class  RGBColorFilter
class  ROIClipper
class  SelectedClusterPublisher
class  SnapIt
class  SnapshotInformation
class  SphericalPointCloudSimulator
 This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet. More...
class  StampedJointAngle
class  StaticPolygonArrayPublisher
class  SupervoxelSegmentation
class  TfTransformBoundingBox
class  TfTransformBoundingBoxArray
class  TfTransformCloud
class  TiltLaserListener
class  TimeStampedVector
class  TorusFinder
class  TransformPointcloudInBoundingBox
class  UniformSampling
class  ViewpointSampler
class  VoxelGridDownsampleDecoder
class  VoxelGridDownsampleManager

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 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 boost::tuple
< pcl::PointIndices::Ptr,
pcl::ModelCoefficients::Ptr,
Plane::Ptr,
geometry_msgs::PolygonStamped > 
PlaneInfoContainer
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)
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)
template<class PointT >
void transformPointcloudInBoundingBox (const jsk_recognition_msgs::BoundingBox &box_msg, const sensor_msgs::PointCloud2 &cloud_msg, pcl::PointCloud< PointT > &output, Eigen::Affine3f &offset, tf::TransformListener &tf_listener)
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.

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 boost::tuple<pcl::PointIndices::Ptr, pcl::ModelCoefficients::Ptr, Plane::Ptr, geometry_msgs::PolygonStamped> jsk_pcl_ros::PlaneInfoContainer

Definition at line 61 of file plane_reasoner.h.

Definition at line 57 of file pointcloud_moveit_filter.h.

Definition at line 58 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 219 of file plane_supported_cuboid_estimator.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 148 of file plane_supported_cuboid_estimator.h.

Definition at line 44 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 206 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 134 of file plane_supported_cuboid_estimator.h.

template<class PointT >
void jsk_pcl_ros::transformPointcloudInBoundingBox ( const jsk_recognition_msgs::BoundingBox &  box_msg,
const sensor_msgs::PointCloud2 &  cloud_msg,
pcl::PointCloud< PointT > &  output,
Eigen::Affine3f &  offset,
tf::TransformListener tf_listener 
)

Definition at line 53 of file transform_pointcloud_in_bounding_box.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 Wed Sep 16 2015 04:36:49