, including all inherited members.
| angular_resolution_ | pcl::RangeImage | [protected] |
| angular_resolution_reciprocal_ | pcl::RangeImage | [protected] |
| at(int u, int v) const | pcl::PointCloud< PointWithRange > | [inline] |
| BaseClass typedef | pcl::RangeImage | |
| begin() | pcl::PointCloud< PointWithRange > | [inline] |
| begin() const | pcl::PointCloud< PointWithRange > | [inline] |
| calculate3DPoint(float image_x, float image_y, float range, PointWithRange &point) const | pcl::RangeImage | [inline] |
| calculate3DPoint(float image_x, float image_y, PointWithRange &point) const | pcl::RangeImage | [inline] |
| calculate3DPoint(float image_x, float image_y, float range, Eigen::Vector3f &point) const | pcl::RangeImage | [inline, virtual] |
| calculate3DPoint(float image_x, float image_y, Eigen::Vector3f &point) const | pcl::RangeImage | [inline] |
| CAMERA_FRAME enum value | pcl::RangeImage | |
| change3dPointsToLocalCoordinateFrame() | pcl::RangeImage | |
| checkPoint(const Eigen::Vector3f &point, PointWithRange &point_in_image) const | pcl::RangeImage | [inline] |
| const_iterator typedef | pcl::PointCloud< PointWithRange > | |
| ConstPtr typedef | pcl::PointCloud< PointWithRange > | |
| CoordinateFrame enum name | pcl::RangeImage | |
| createFromPointCloud(const PointCloudType &point_cloud, float angular_resolution, float max_angle_width, float max_angle_height, const Eigen::Affine3f &sensor_pose, CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | [inline] |
| createFromPointCloudWithKnownSize(const PointCloudType &point_cloud, float angular_resolution, const Eigen::Vector3f &point_cloud_center, float point_cloud_radius, const Eigen::Affine3f &sensor_pose, CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | [inline] |
| createFromPointCloudWithViewpoints(const PointCloudTypeWithViewpoints &point_cloud, float angular_resolution, float max_angle_width, float max_angle_height, CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | [inline] |
| cropImage(int border_size=0, int top=-1, int right=-1, int bottom=-1, int left=-1) | pcl::RangeImage | |
| debug | pcl::RangeImage | [static] |
| detail::getMapping(PointCloud &p) | pcl::PointCloud< PointWithRange > | [friend] |
| doIcp(const VectorOfEigenVector3f &points, const Eigen::Affine3f &initial_guess, int search_radius, float max_distance_start, float max_distance_end, int num_iterations) const | pcl::RangeImage | |
| doZBuffer(const PointCloudType &point_cloud, float noise_level, float min_range, int &top, int &right, int &bottom, int &left) | pcl::RangeImage | [inline, protected] |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | pcl::PointCloud< PointWithRange > | |
| end() | pcl::PointCloud< PointWithRange > | [inline] |
| end() const | pcl::PointCloud< PointWithRange > | [inline] |
| extractFarRanges(const sensor_msgs::PointCloud2 &point_cloud_data, PointCloud< PointWithViewpoint > &far_ranges) | pcl::RangeImage | [static] |
| get1dPointAverage(int x, int y, int delta_x, int delta_y, int no_of_points, PointWithRange &average_point) const | pcl::RangeImage | [inline] |
| getAcutenessValue(const PointWithRange &point1, const PointWithRange &point2) const | pcl::RangeImage | [inline] |
| getAcutenessValue(int x1, int y1, int x2, int y2) const | pcl::RangeImage | [inline] |
| getAcutenessValueImages(int pixel_distance, float *´ness_value_image_x, float *´ness_value_image_y) const | pcl::RangeImage | |
| getAnglesFromImagePoint(float image_x, float image_y, float &angle_x, float &angle_y) const | pcl::RangeImage | [inline] |
| getAngularResolution() const | pcl::RangeImage | [inline] |
| getAverageEuclideanDistance(int x, int y, int offset_x, int offset_y, int max_steps) const | pcl::RangeImage | [inline] |
| getAverageViewPoint(const PointCloudTypeWithViewpoints &point_cloud) | pcl::RangeImage | [inline, static] |
| getBlurredImage(int blur_radius, RangeImage &range_image) const | pcl::RangeImage | |
| getBlurredImageUsingIntegralImage(int blur_radius, float *integral_image, int *valid_points_num_image, RangeImage &range_image) const | pcl::RangeImage | |
| getCoordinateFrameTransformation(RangeImage::CoordinateFrame coordinate_frame, Eigen::Affine3f &transformation) | pcl::RangeImage | [static] |
| getCurvature(int x, int y, int radius, int step_size) const | pcl::RangeImage | [inline] |
| getEigenVector3f(const PointWithRange &point) | pcl::RangeImage | [inline, static] |
| getEigenVector3f(int x, int y) const | pcl::RangeImage | [inline] |
| getEigenVector3f(int index) const | pcl::RangeImage | [inline] |
| getEuclideanDistanceSquared(int x1, int y1, int x2, int y2) const | pcl::RangeImage | [inline] |
| getHalfImage(RangeImage &half_image) const | pcl::RangeImage | [virtual] |
| getImageOffsetX() const | pcl::RangeImage | [inline] |
| getImageOffsetY() const | pcl::RangeImage | [inline] |
| getImagePoint(const Eigen::Vector3f &point, float &image_x, float &image_y, float &range) const | pcl::RangeImage | [inline, virtual] |
| getImagePoint(const Eigen::Vector3f &point, int &image_x, int &image_y, float &range) const | pcl::RangeImage | [inline] |
| getImagePoint(const Eigen::Vector3f &point, float &image_x, float &image_y) const | pcl::RangeImage | [inline] |
| getImagePoint(const Eigen::Vector3f &point, int &image_x, int &image_y) const | pcl::RangeImage | [inline] |
| getImagePoint(float x, float y, float z, float &image_x, float &image_y, float &range) const | pcl::RangeImage | [inline] |
| getImagePoint(float x, float y, float z, float &image_x, float &image_y) const | pcl::RangeImage | [inline] |
| getImagePoint(float x, float y, float z, int &image_x, int &image_y) const | pcl::RangeImage | [inline] |
| getImagePointFromAngles(float angle_x, float angle_y, float &image_x, float &image_y) const | pcl::RangeImage | [inline] |
| getImpactAngle(const PointWithRange &point1, const PointWithRange &point2) const | pcl::RangeImage | [inline] |
| getImpactAngle(int x1, int y1, int x2, int y2) const | pcl::RangeImage | [inline] |
| getImpactAngleBasedOnLocalNormal(int x, int y, int radius) const | pcl::RangeImage | [inline] |
| getImpactAngleImageBasedOnLocalNormals(int radius) const | pcl::RangeImage | |
| getIntegralImage(float *&integral_image, int *&valid_points_num_image) const | pcl::RangeImage | |
| getInterpolatedSurfaceProjection(const Eigen::Affine3f &pose, int pixel_size, float world_size) const | pcl::RangeImage | |
| getInterpolatedSurfaceProjection(const Eigen::Vector3f &point, int pixel_size, float world_size) const | pcl::RangeImage | |
| getMaxAngleSize(const Eigen::Affine3f &viewer_pose, const Eigen::Vector3f ¢er, float radius) | pcl::RangeImage | [inline, static] |
| getMinMaxRanges(float &min_range, float &max_range) const | pcl::RangeImage | |
| getNew() const | pcl::RangeImage | [inline, virtual] |
| getNormal(int x, int y, int radius, Eigen::Vector3f &normal, int step_size=1) const | pcl::RangeImage | [inline] |
| getNormalBasedAcutenessValue(int x, int y, int radius) const | pcl::RangeImage | [inline] |
| getNormalBasedUprightTransformation(const Eigen::Vector3f &point, float max_dist, Eigen::Affine3f &transformation) const | pcl::RangeImage | |
| getNormalForClosestNeighbors(int x, int y, int radius, const PointWithRange &point, int no_of_nearest_neighbors, Eigen::Vector3f &normal, int step_size=1) const | pcl::RangeImage | [inline] |
| getNormalForClosestNeighbors(int x, int y, int radius, const Eigen::Vector3f &point, int no_of_nearest_neighbors, Eigen::Vector3f &normal, Eigen::Vector3f *point_on_plane=NULL, int step_size=1) const | pcl::RangeImage | [inline] |
| getNormalForClosestNeighbors(int x, int y, Eigen::Vector3f &normal, int radius=2) const | pcl::RangeImage | [inline] |
| getPoint(int image_x, int image_y) const | pcl::RangeImage | [inline] |
| getPoint(int image_x, int image_y) | pcl::RangeImage | [inline] |
| getPoint(float image_x, float image_y) const | pcl::RangeImage | [inline] |
| getPoint(float image_x, float image_y) | pcl::RangeImage | [inline] |
| getPoint(int image_x, int image_y, Eigen::Vector3f &point) const | pcl::RangeImage | [inline] |
| getPoint(int index, Eigen::Vector3f &point) const | pcl::RangeImage | [inline] |
| getPoint(int index) const | pcl::RangeImage | [inline] |
| getPointConsideringWrapAround(int image_x, int image_y) const | pcl::RangeImage | [inline] |
| getPointNoCheck(int image_x, int image_y) const | pcl::RangeImage | [inline] |
| getPointNoCheck(int image_x, int image_y) | pcl::RangeImage | [inline] |
| getRangeDifference(const Eigen::Vector3f &point) const | pcl::RangeImage | [inline] |
| getRangeImageWithSmoothedSurface(int radius, RangeImage &smoothed_range_image) const | pcl::RangeImage | |
| getRangesArray() const | pcl::RangeImage | |
| getRotationToViewerCoordinateFrame(const Eigen::Vector3f &point, Eigen::Affine3f &transformation) const | pcl::RangeImage | [inline] |
| getSensorPos() const | pcl::RangeImage | [inline] |
| getSquaredDistanceOfNthNeighbor(int x, int y, int radius, int n, int step_size) const | pcl::RangeImage | [inline] |
| getSubImage(int sub_image_image_offset_x, int sub_image_image_offset_y, int sub_image_width, int sub_image_height, int combine_pixels, RangeImage &sub_image) const | pcl::RangeImage | [virtual] |
| getSurfaceAngleChange(int x, int y, int radius, float &angle_change_x, float &angle_change_y) const | pcl::RangeImage | [inline] |
| getSurfaceAngleChangeImages(int radius, float *&angle_change_image_x, float *&angle_change_image_y) const | pcl::RangeImage | |
| getSurfaceChange(int x, int y, int radius) const | pcl::RangeImage | |
| getSurfaceChangeImage(int radius) const | pcl::RangeImage | |
| getSurfaceInformation(int x, int y, int radius, const Eigen::Vector3f &point, int no_of_closest_neighbors, int step_size, float &max_closest_neighbor_distance_squared, Eigen::Vector3f &normal, Eigen::Vector3f &mean, Eigen::Vector3f &eigen_values, Eigen::Vector3f *normal_all_neighbors=NULL, Eigen::Vector3f *mean_all_neighbors=NULL, Eigen::Vector3f *eigen_values_all_neighbors=NULL) const | pcl::RangeImage | [inline] |
| getTransformationToRangeImageSystem() const | pcl::RangeImage | [inline] |
| getTransformationToViewerCoordinateFrame(const Eigen::Vector3f &point) const | pcl::RangeImage | [inline] |
| getTransformationToViewerCoordinateFrame(const Eigen::Vector3f &point, Eigen::Affine3f &transformation) const | pcl::RangeImage | [inline] |
| getTransformationToWorldSystem() const | pcl::RangeImage | [inline] |
| getViewingDirection(int x, int y, Eigen::Vector3f &viewing_direction) const | pcl::RangeImage | [inline] |
| getViewingDirection(const Eigen::Vector3f &point, Eigen::Vector3f &viewing_direction) const | pcl::RangeImage | [inline] |
| header | pcl::PointCloud< PointWithRange > | |
| height | pcl::PointCloud< PointWithRange > | |
| image_offset_x_ | pcl::RangeImage | [protected] |
| image_offset_y_ | pcl::RangeImage | [protected] |
| integrateFarRanges(const PointCloud< PointWithViewpoint > &far_ranges) | pcl::RangeImage | |
| is_dense | pcl::PointCloud< PointWithRange > | |
| isInImage(int x, int y) const | pcl::RangeImage | [inline] |
| isMaxRange(int x, int y) const | pcl::RangeImage | [inline] |
| isObserved(int x, int y) const | pcl::RangeImage | [inline] |
| isValid(int x, int y) const | pcl::RangeImage | [inline] |
| isValid(int index) const | pcl::RangeImage | [inline] |
| iterator typedef | pcl::PointCloud< PointWithRange > | |
| LASER_FRAME enum value | pcl::RangeImage | |
| makeShared() const | pcl::PointCloud< PointWithRange > | [inline] |
| mapping_ | pcl::PointCloud< PointWithRange > | [protected] |
| operator()(int u, int v) const | pcl::PointCloud< PointWithRange > | [inline] |
| operator()(int u, int v) | pcl::PointCloud< PointWithRange > | [inline] |
| operator+=(const PointCloud &rhs) | pcl::PointCloud< PointWithRange > | [inline] |
| operator=(const PointCloud &rhs) | pcl::PointCloud< PointWithRange > | [inline] |
| PointCloud() | pcl::PointCloud< PointWithRange > | [inline] |
| points | pcl::PointCloud< PointWithRange > | |
| PointType typedef | pcl::PointCloud< PointWithRange > | |
| Ptr typedef | pcl::PointCloud< PointWithRange > | |
| push_back(const PointWithRange &p) | pcl::PointCloud< PointWithRange > | [inline] |
| RangeImage() | pcl::RangeImage | |
| real2DToInt2D(float x, float y, int &xInt, int &yInt) const | pcl::RangeImage | [inline] |
| recalculate3DPointPositions() | pcl::RangeImage | |
| reset() | pcl::RangeImage | |
| sensor_orientation_ | pcl::PointCloud< PointWithRange > | |
| sensor_origin_ | pcl::PointCloud< PointWithRange > | |
| setAngularResolution(float angular_resolution) | pcl::RangeImage | [inline] |
| setUnseenToMaxRange() | pcl::RangeImage | |
| size() const | pcl::PointCloud< PointWithRange > | [inline] |
| to_range_image_system_ | pcl::RangeImage | [protected] |
| to_world_system_ | pcl::RangeImage | [protected] |
| unobserved_point | pcl::RangeImage | [protected] |
| VectorOfEigenVector3f typedef | pcl::RangeImage | |
| VectorType typedef | pcl::PointCloud< PointWithRange > | |
| width | pcl::PointCloud< PointWithRange > | |
| ~RangeImage() | pcl::RangeImage | |