, including all inherited members.
angular_resolution_x_ | pcl::RangeImage | [protected] |
angular_resolution_x_reciprocal_ | pcl::RangeImage | [protected] |
angular_resolution_y_ | pcl::RangeImage | [protected] |
angular_resolution_y_reciprocal_ | pcl::RangeImage | [protected] |
asin_lookup_table | pcl::RangeImage | [protected, static] |
asinLookUp(float value) | pcl::RangeImage | [inline, protected, static] |
at(int column, int row) const | pcl::PointCloud< PointWithRange > | [inline] |
at(int column, int row) | pcl::PointCloud< PointWithRange > | [inline] |
at(size_t n) const | pcl::PointCloud< PointWithRange > | [inline] |
at(size_t n) | pcl::PointCloud< PointWithRange > | [inline] |
atan2LookUp(float y, float x) | pcl::RangeImage | [inline, protected, static] |
atan_lookup_table | pcl::RangeImage | [protected, static] |
back() const | pcl::PointCloud< PointWithRange > | [inline] |
back() | pcl::PointCloud< PointWithRange > | [inline] |
BaseClass typedef | pcl::RangeImagePlanar | |
begin() | pcl::PointCloud< PointWithRange > | [inline] |
begin() const | pcl::PointCloud< PointWithRange > | [inline] |
calculate3DPoint(float image_x, float image_y, float range, Eigen::Vector3f &point) const | pcl::RangeImagePlanar | [inline, virtual] |
pcl::RangeImage::calculate3DPoint(float image_x, float image_y, float range, PointWithRange &point) const | pcl::RangeImage | [inline] |
pcl::RangeImage::calculate3DPoint(float image_x, float image_y, PointWithRange &point) const | pcl::RangeImage | [inline] |
pcl::RangeImage::calculate3DPoint(float image_x, float image_y, Eigen::Vector3f &point) const | pcl::RangeImage | [inline] |
CAMERA_FRAME enum value | pcl::RangeImage | |
center_x_ | pcl::RangeImagePlanar | [protected] |
center_y_ | pcl::RangeImagePlanar | [protected] |
change3dPointsToLocalCoordinateFrame() | pcl::RangeImage | |
checkPoint(const Eigen::Vector3f &point, PointWithRange &point_in_image) const | pcl::RangeImage | [inline] |
clear() | pcl::PointCloud< PointWithRange > | [inline] |
CloudVectorType typedef | pcl::PointCloud< PointWithRange > | |
const_iterator typedef | pcl::PointCloud< PointWithRange > | |
ConstPtr typedef | pcl::RangeImagePlanar | |
CoordinateFrame enum name | pcl::RangeImage | |
copyTo(RangeImage &other) const | pcl::RangeImagePlanar | [virtual] |
cos_lookup_table | pcl::RangeImage | [protected, static] |
cosLookUp(float value) | pcl::RangeImage | [inline, protected, static] |
createEmpty(float angular_resolution, const Eigen::Affine3f &sensor_pose=Eigen::Affine3f::Identity(), RangeImage::CoordinateFrame coordinate_frame=CAMERA_FRAME, float angle_width=pcl::deg2rad(360.0f), float angle_height=pcl::deg2rad(180.0f)) | pcl::RangeImage | |
createEmpty(float angular_resolution_x, float angular_resolution_y, const Eigen::Affine3f &sensor_pose=Eigen::Affine3f::Identity(), RangeImage::CoordinateFrame coordinate_frame=CAMERA_FRAME, float angle_width=pcl::deg2rad(360.0f), float angle_height=pcl::deg2rad(180.0f)) | pcl::RangeImage | |
createFromPointCloud(const PointCloudType &point_cloud, float angular_resolution=pcl::deg2rad(0.5f), float max_angle_width=pcl::deg2rad(360.0f), float max_angle_height=pcl::deg2rad(180.0f), const Eigen::Affine3f &sensor_pose=Eigen::Affine3f::Identity(), CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | |
createFromPointCloud(const PointCloudType &point_cloud, float angular_resolution_x=pcl::deg2rad(0.5f), float angular_resolution_y=pcl::deg2rad(0.5f), float max_angle_width=pcl::deg2rad(360.0f), float max_angle_height=pcl::deg2rad(180.0f), const Eigen::Affine3f &sensor_pose=Eigen::Affine3f::Identity(), CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | |
createFromPointCloudWithFixedSize(const PointCloudType &point_cloud, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, const Eigen::Affine3f &sensor_pose, CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f) | pcl::RangeImagePlanar | |
createFromPointCloudWithKnownSize(const PointCloudType &point_cloud, float angular_resolution, const Eigen::Vector3f &point_cloud_center, float point_cloud_radius, const Eigen::Affine3f &sensor_pose=Eigen::Affine3f::Identity(), CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | |
createFromPointCloudWithKnownSize(const PointCloudType &point_cloud, float angular_resolution_x, float angular_resolution_y, const Eigen::Vector3f &point_cloud_center, float point_cloud_radius, const Eigen::Affine3f &sensor_pose=Eigen::Affine3f::Identity(), CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f, int border_size=0) | pcl::RangeImage | |
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 | |
createFromPointCloudWithViewpoints(const PointCloudTypeWithViewpoints &point_cloud, float angular_resolution_x, float angular_resolution_y, 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 | |
createLookupTables() | pcl::RangeImage | [protected, static] |
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(pcl::PointCloud< PointWithRange > &p) | pcl::PointCloud< PointWithRange > | [friend] |
doZBuffer(const PointCloudType &point_cloud, float noise_level, float min_range, int &top, int &right, int &bottom, int &left) | pcl::RangeImage | |
empty() const | pcl::PointCloud< PointWithRange > | [inline] |
end() | pcl::PointCloud< PointWithRange > | [inline] |
end() const | pcl::PointCloud< PointWithRange > | [inline] |
erase(iterator position) | pcl::PointCloud< PointWithRange > | [inline] |
erase(iterator first, iterator last) | pcl::PointCloud< PointWithRange > | [inline] |
extractFarRanges(const pcl::PCLPointCloud2 &point_cloud_data, PointCloud< PointWithViewpoint > &far_ranges) | pcl::RangeImage | [static] |
focal_length_x_ | pcl::RangeImagePlanar | [protected] |
focal_length_x_reciprocal_ | pcl::RangeImagePlanar | [protected] |
focal_length_y_ | pcl::RangeImagePlanar | [protected] |
focal_length_y_reciprocal_ | pcl::RangeImagePlanar | [protected] |
front() const | pcl::PointCloud< PointWithRange > | [inline] |
front() | pcl::PointCloud< PointWithRange > | [inline] |
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] |
getAngularResolution(float &angular_resolution_x, float &angular_resolution_y) const | pcl::RangeImage | [inline] |
getAngularResolutionX() const | pcl::RangeImage | [inline] |
getAngularResolutionY() 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 | [static] |
getBlurredImage(int blur_radius, RangeImage &range_image) const | pcl::RangeImage | [virtual] |
getBlurredImageUsingIntegralImage(int blur_radius, float *integral_image, int *valid_points_num_image, RangeImage &range_image) const | pcl::RangeImage | |
getCenterX() const | pcl::RangeImagePlanar | [inline] |
getCenterY() const | pcl::RangeImagePlanar | [inline] |
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] |
getFocalLengthX() const | pcl::RangeImagePlanar | [inline] |
getFocalLengthY() const | pcl::RangeImagePlanar | [inline] |
getHalfImage(RangeImage &half_image) const | pcl::RangeImagePlanar | [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::RangeImagePlanar | [inline, virtual] |
pcl::RangeImage::getImagePoint(const Eigen::Vector3f &point, int &image_x, int &image_y, float &range) const | pcl::RangeImage | [inline] |
pcl::RangeImage::getImagePoint(const Eigen::Vector3f &point, float &image_x, float &image_y) const | pcl::RangeImage | [inline] |
pcl::RangeImage::getImagePoint(const Eigen::Vector3f &point, int &image_x, int &image_y) const | pcl::RangeImage | [inline] |
pcl::RangeImage::getImagePoint(float x, float y, float z, float &image_x, float &image_y, float &range) const | pcl::RangeImage | [inline] |
pcl::RangeImage::getImagePoint(float x, float y, float z, float &image_x, float &image_y) const | pcl::RangeImage | [inline] |
pcl::RangeImage::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 | |
getMatrixXfMap(int dim, int stride, int offset) | pcl::PointCloud< PointWithRange > | [inline] |
getMatrixXfMap(int dim, int stride, int offset) const | pcl::PointCloud< PointWithRange > | [inline] |
getMatrixXfMap() | pcl::PointCloud< PointWithRange > | [inline] |
getMatrixXfMap() const | pcl::PointCloud< PointWithRange > | [inline] |
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::RangeImagePlanar | [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] |
getOverlap(const RangeImage &other_range_image, const Eigen::Affine3f &relative_transformation, int search_radius, float max_distance, int pixel_step=1) const | pcl::RangeImage | |
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] |
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::RangeImagePlanar | [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] |
insert(iterator position, const PointWithRange &pt) | pcl::PointCloud< PointWithRange > | [inline] |
insert(iterator position, size_t n, const PointWithRange &pt) | pcl::PointCloud< PointWithRange > | [inline] |
insert(iterator position, InputIterator first, InputIterator last) | pcl::PointCloud< PointWithRange > | [inline] |
integrateFarRanges(const PointCloudType &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] |
isOrganized() const | pcl::PointCloud< PointWithRange > | [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 | |
lookup_table_size | pcl::RangeImage | [protected, static] |
makeShared() | pcl::RangeImagePlanar | [inline] |
PointCloud< PointWithRange >::makeShared() const | pcl::PointCloud< PointWithRange > | [inline] |
mapping_ | pcl::PointCloud< PointWithRange > | [protected] |
max_no_of_threads | pcl::RangeImage | [static] |
operator()(size_t column, size_t row) const | pcl::PointCloud< PointWithRange > | [inline] |
operator()(size_t column, size_t row) | pcl::PointCloud< PointWithRange > | [inline] |
operator+(const PointCloud &rhs) | pcl::PointCloud< PointWithRange > | [inline] |
operator+=(const PointCloud &rhs) | pcl::PointCloud< PointWithRange > | [inline] |
operator[](size_t n) const | pcl::PointCloud< PointWithRange > | [inline] |
operator[](size_t n) | pcl::PointCloud< PointWithRange > | [inline] |
PointCloud() | pcl::PointCloud< PointWithRange > | [inline] |
PointCloud(PointCloud< PointWithRange > &pc) | pcl::PointCloud< PointWithRange > | [inline] |
PointCloud(const PointCloud< PointWithRange > &pc) | pcl::PointCloud< PointWithRange > | [inline] |
PointCloud(const PointCloud< PointWithRange > &pc, const std::vector< int > &indices) | pcl::PointCloud< PointWithRange > | [inline] |
PointCloud(uint32_t width_, uint32_t height_, const PointWithRange &value_=PointWithRange()) | pcl::PointCloud< PointWithRange > | [inline] |
points | pcl::PointCloud< PointWithRange > | |
PointType typedef | pcl::PointCloud< PointWithRange > | |
Ptr typedef | pcl::RangeImagePlanar | |
push_back(const PointWithRange &pt) | pcl::PointCloud< PointWithRange > | [inline] |
RangeImage() | pcl::RangeImage | |
RangeImagePlanar() | pcl::RangeImagePlanar | |
real2DToInt2D(float x, float y, int &xInt, int &yInt) const | pcl::RangeImage | [inline] |
recalculate3DPointPositions() | pcl::RangeImage | |
reserve(size_t n) | pcl::PointCloud< PointWithRange > | [inline] |
reset() | pcl::RangeImage | |
resize(size_t n) | pcl::PointCloud< PointWithRange > | [inline] |
sensor_orientation_ | pcl::PointCloud< PointWithRange > | |
sensor_origin_ | pcl::PointCloud< PointWithRange > | |
setAngularResolution(float angular_resolution) | pcl::RangeImage | [inline] |
setAngularResolution(float angular_resolution_x, float angular_resolution_y) | pcl::RangeImage | [inline] |
setDepthImage(const float *depth_image, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1) | pcl::RangeImagePlanar | |
setDepthImage(const unsigned short *depth_image, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1) | pcl::RangeImagePlanar | |
setDisparityImage(const float *disparity_image, int di_width, int di_height, float focal_length, float base_line, float desired_angular_resolution=-1) | pcl::RangeImagePlanar | |
setImageOffsets(int offset_x, int offset_y) | pcl::RangeImage | [inline] |
setTransformationToRangeImageSystem(const Eigen::Affine3f &to_range_image_system) | pcl::RangeImage | [inline] |
setUnseenToMaxRange() | pcl::RangeImage | |
size() const | pcl::PointCloud< PointWithRange > | [inline] |
swap(PointCloud< PointWithRange > &rhs) | 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 > | |
~PointCloud() | pcl::PointCloud< PointWithRange > | [inline, virtual] |
~RangeImage() | pcl::RangeImage | [virtual] |
~RangeImagePlanar() | pcl::RangeImagePlanar | [virtual] |