Point Cloud Library (PCL)  1.14.0-dev
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
pcl::RangeImage Class Reference

RangeImage is derived from pcl/PointCloud and provides functionalities with focus on situations where a 3D scene was captured from a specific view point. More...

#include <pcl/range_image/range_image.h>

+ Inheritance diagram for pcl::RangeImage:
+ Collaboration diagram for pcl::RangeImage:

Public Types

enum  CoordinateFrame { CAMERA_FRAME = 0 , LASER_FRAME = 1 }
 
using BaseClass = pcl::PointCloud< PointWithRange >
 
using VectorOfEigenVector3f = std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > >
 
using Ptr = shared_ptr< RangeImage >
 
using ConstPtr = shared_ptr< const RangeImage >
 
- Public Types inherited from pcl::PointCloud< PointWithRange >
using PointType = PointWithRange
 
using VectorType = std::vector< PointWithRange, Eigen::aligned_allocator< PointWithRange > >
 
using CloudVectorType = std::vector< PointCloud< PointWithRange >, Eigen::aligned_allocator< PointCloud< PointWithRange > > >
 
using Ptr = shared_ptr< PointCloud< PointWithRange > >
 
using ConstPtr = shared_ptr< const PointCloud< PointWithRange > >
 
using value_type = PointWithRange
 
using reference = PointWithRange &
 
using const_reference = const PointWithRange &
 
using difference_type = typename VectorType::difference_type
 
using size_type = typename VectorType::size_type
 
using iterator = typename VectorType::iterator
 
using const_iterator = typename VectorType::const_iterator
 
using reverse_iterator = typename VectorType::reverse_iterator
 
using const_reverse_iterator = typename VectorType::const_reverse_iterator
 

Public Member Functions

PCL_EXPORTS RangeImage ()
 Constructor. More...
 
virtual PCL_EXPORTS ~RangeImage ()=default
 Destructor. More...
 
Ptr makeShared ()
 Get a boost shared pointer of a copy of this. More...
 
PCL_EXPORTS void reset ()
 Reset all values to an empty range image. More...
 
template<typename PointCloudType >
void 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)
 Create the depth image from a point cloud. More...
 
template<typename PointCloudType >
void 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)
 Create the depth image from a point cloud. More...
 
template<typename PointCloudType >
void 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)
 Create the depth image from a point cloud, getting a hint about the size of the scene for faster calculation. More...
 
template<typename PointCloudType >
void 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)
 Create the depth image from a point cloud, getting a hint about the size of the scene for faster calculation. More...
 
template<typename PointCloudTypeWithViewpoints >
void 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)
 Create the depth image from a point cloud, using the average viewpoint of the points (vp_x,vp_y,vp_z in the point type) in the point cloud as sensor pose (assuming a rotation of (0,0,0)). More...
 
template<typename PointCloudTypeWithViewpoints >
void 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)
 Create the depth image from a point cloud, using the average viewpoint of the points (vp_x,vp_y,vp_z in the point type) in the point cloud as sensor pose (assuming a rotation of (0,0,0)). More...
 
void 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))
 Create an empty depth image (filled with unobserved points) More...
 
void 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))
 Create an empty depth image (filled with unobserved points) More...
 
template<typename PointCloudType >
void doZBuffer (const PointCloudType &point_cloud, float noise_level, float min_range, int &top, int &right, int &bottom, int &left)
 Integrate the given point cloud into the current range image using a z-buffer. More...
 
template<typename PointCloudType >
void integrateFarRanges (const PointCloudType &far_ranges)
 Integrates the given far range measurements into the range image. More...
 
PCL_EXPORTS void cropImage (int border_size=0, int top=-1, int right=-1, int bottom=-1, int left=-1)
 Cut the range image to the minimal size so that it still contains all actual range readings. More...
 
PCL_EXPORTS float * getRangesArray () const
 Get all the range values in one float array of size width*height. More...
 
const Eigen::Affine3f & getTransformationToRangeImageSystem () const
 Getter for the transformation from the world system into the range image system (the sensor coordinate frame) More...
 
void setTransformationToRangeImageSystem (const Eigen::Affine3f &to_range_image_system)
 Setter for the transformation from the range image system (the sensor coordinate frame) into the world system. More...
 
const Eigen::Affine3f & getTransformationToWorldSystem () const
 Getter for the transformation from the range image system (the sensor coordinate frame) into the world system. More...
 
float getAngularResolution () const
 Getter for the angular resolution of the range image in x direction in radians per pixel. More...
 
float getAngularResolutionX () const
 Getter for the angular resolution of the range image in x direction in radians per pixel. More...
 
float getAngularResolutionY () const
 Getter for the angular resolution of the range image in y direction in radians per pixel. More...
 
void getAngularResolution (float &angular_resolution_x, float &angular_resolution_y) const
 Getter for the angular resolution of the range image in x and y direction (in radians). More...
 
void setAngularResolution (float angular_resolution)
 Set the angular resolution of the range image. More...
 
void setAngularResolution (float angular_resolution_x, float angular_resolution_y)
 Set the angular resolution of the range image. More...
 
const PointWithRangegetPoint (int image_x, int image_y) const
 Return the 3D point with range at the given image position. More...
 
PointWithRangegetPoint (int image_x, int image_y)
 Non-const-version of getPoint. More...
 
const PointWithRangegetPoint (float image_x, float image_y) const
 Return the 3d point with range at the given image position. More...
 
PointWithRangegetPoint (float image_x, float image_y)
 Non-const-version of the above. More...
 
const PointWithRangegetPointNoCheck (int image_x, int image_y) const
 Return the 3D point with range at the given image position. More...
 
PointWithRangegetPointNoCheck (int image_x, int image_y)
 Non-const-version of getPointNoCheck. More...
 
void getPoint (int image_x, int image_y, Eigen::Vector3f &point) const
 Same as above. More...
 
void getPoint (int index, Eigen::Vector3f &point) const
 Same as above. More...
 
const Eigen::Map< const Eigen::Vector3f > getEigenVector3f (int x, int y) const
 Same as above. More...
 
const Eigen::Map< const Eigen::Vector3f > getEigenVector3f (int index) const
 Same as above. More...
 
const PointWithRangegetPoint (int index) const
 Return the 3d point with range at the given index (whereas index=y*width+x) More...
 
void calculate3DPoint (float image_x, float image_y, float range, PointWithRange &point) const
 Calculate the 3D point according to the given image point and range. More...
 
void calculate3DPoint (float image_x, float image_y, PointWithRange &point) const
 Calculate the 3D point according to the given image point and the range value at the closest pixel. More...
 
virtual void calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f &point) const
 Calculate the 3D point according to the given image point and range. More...
 
void calculate3DPoint (float image_x, float image_y, Eigen::Vector3f &point) const
 Calculate the 3D point according to the given image point and the range value at the closest pixel. More...
 
PCL_EXPORTS void recalculate3DPointPositions ()
 Recalculate all 3D point positions according to their pixel position and range. More...
 
virtual void getImagePoint (const Eigen::Vector3f &point, float &image_x, float &image_y, float &range) const
 Get imagePoint from 3D point in world coordinates. More...
 
void getImagePoint (const Eigen::Vector3f &point, int &image_x, int &image_y, float &range) const
 Same as above. More...
 
void getImagePoint (const Eigen::Vector3f &point, float &image_x, float &image_y) const
 Same as above. More...
 
void getImagePoint (const Eigen::Vector3f &point, int &image_x, int &image_y) const
 Same as above. More...
 
void getImagePoint (float x, float y, float z, float &image_x, float &image_y, float &range) const
 Same as above. More...
 
void getImagePoint (float x, float y, float z, float &image_x, float &image_y) const
 Same as above. More...
 
void getImagePoint (float x, float y, float z, int &image_x, int &image_y) const
 Same as above. More...
 
float checkPoint (const Eigen::Vector3f &point, PointWithRange &point_in_image) const
 point_in_image will be the point in the image at the position the given point would be. More...
 
float getRangeDifference (const Eigen::Vector3f &point) const
 Returns the difference in range between the given point and the range of the point in the image at the position the given point would be. More...
 
void getImagePointFromAngles (float angle_x, float angle_y, float &image_x, float &image_y) const
 Get the image point corresponding to the given angles. More...
 
void getAnglesFromImagePoint (float image_x, float image_y, float &angle_x, float &angle_y) const
 Get the angles corresponding to the given image point. More...
 
void real2DToInt2D (float x, float y, int &xInt, int &yInt) const
 Transforms an image point in float values to an image point in int values. More...
 
bool isInImage (int x, int y) const
 Check if a point is inside of the image. More...
 
bool isValid (int x, int y) const
 Check if a point is inside of the image and has a finite range. More...
 
bool isValid (int index) const
 Check if a point has a finite range. More...
 
bool isObserved (int x, int y) const
 Check if a point is inside of the image and has either a finite range or a max reading (range=INFINITY) More...
 
bool isMaxRange (int x, int y) const
 Check if a point is a max range (range=INFINITY) - please check isInImage or isObserved first! More...
 
bool getNormal (int x, int y, int radius, Eigen::Vector3f &normal, int step_size=1) const
 Calculate the normal of an image point using the neighbors with a maximum pixel distance of radius. More...
 
bool getNormalForClosestNeighbors (int x, int y, int radius, const PointWithRange &point, int no_of_nearest_neighbors, Eigen::Vector3f &normal, int step_size=1) const
 Same as above, but only the no_of_nearest_neighbors points closest to the given point are considered. More...
 
bool getNormalForClosestNeighbors (int x, int y, int radius, const Eigen::Vector3f &point, int no_of_nearest_neighbors, Eigen::Vector3f &normal, Eigen::Vector3f *point_on_plane=nullptr, int step_size=1) const
 Same as above. More...
 
bool getNormalForClosestNeighbors (int x, int y, Eigen::Vector3f &normal, int radius=2) const
 Same as above, using default values. More...
 
bool 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=nullptr, Eigen::Vector3f *mean_all_neighbors=nullptr, Eigen::Vector3f *eigen_values_all_neighbors=nullptr) const
 Same as above but extracts some more data and can also return the extracted information for all neighbors in radius if normal_all_neighbors is not NULL. More...
 
float getSquaredDistanceOfNthNeighbor (int x, int y, int radius, int n, int step_size) const
 
float getImpactAngle (const PointWithRange &point1, const PointWithRange &point2) const
 Calculate the impact angle based on the sensor position and the two given points - will return -INFINITY if one of the points is unobserved. More...
 
float getImpactAngle (int x1, int y1, int x2, int y2) const
 Same as above. More...
 
float getImpactAngleBasedOnLocalNormal (int x, int y, int radius) const
 Extract a local normal (with a heuristic not to include background points) and calculate the impact angle based on this. More...
 
PCL_EXPORTS float * getImpactAngleImageBasedOnLocalNormals (int radius) const
 Uses the above function for every point in the image. More...
 
float getNormalBasedAcutenessValue (int x, int y, int radius) const
 Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) This uses getImpactAngleBasedOnLocalNormal Will return -INFINITY if no normal could be calculated. More...
 
float getAcutenessValue (const PointWithRange &point1, const PointWithRange &point2) const
 Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) will return -INFINITY if one of the points is unobserved. More...
 
float getAcutenessValue (int x1, int y1, int x2, int y2) const
 Same as above. More...
 
PCL_EXPORTS void getAcutenessValueImages (int pixel_distance, float *&acuteness_value_image_x, float *&acuteness_value_image_y) const
 Calculate getAcutenessValue for every point. More...
 
PCL_EXPORTS float getSurfaceChange (int x, int y, int radius) const
 Calculates, how much the surface changes at a point. More...
 
PCL_EXPORTS float * getSurfaceChangeImage (int radius) const
 Uses the above function for every point in the image. More...
 
void getSurfaceAngleChange (int x, int y, int radius, float &angle_change_x, float &angle_change_y) const
 Calculates, how much the surface changes at a point. More...
 
PCL_EXPORTS void getSurfaceAngleChangeImages (int radius, float *&angle_change_image_x, float *&angle_change_image_y) const
 Uses the above function for every point in the image. More...
 
float getCurvature (int x, int y, int radius, int step_size) const
 Calculates the curvature in a point using pca. More...
 
const Eigen::Vector3f getSensorPos () const
 Get the sensor position. More...
 
PCL_EXPORTS void setUnseenToMaxRange ()
 Sets all -INFINITY values to INFINITY. More...
 
int getImageOffsetX () const
 Getter for image_offset_x_. More...
 
int getImageOffsetY () const
 Getter for image_offset_y_. More...
 
void setImageOffsets (int offset_x, int offset_y)
 Setter for image offsets. More...
 
virtual void 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
 Get a sub part of the complete image as a new range image. More...
 
virtual void getHalfImage (RangeImage &half_image) const
 Get a range image with half the resolution. More...
 
PCL_EXPORTS void getMinMaxRanges (float &min_range, float &max_range) const
 Find the minimum and maximum range in the image. More...
 
PCL_EXPORTS void change3dPointsToLocalCoordinateFrame ()
 This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame. More...
 
PCL_EXPORTS float * getInterpolatedSurfaceProjection (const Eigen::Affine3f &pose, int pixel_size, float world_size) const
 Calculate a range patch as the z values of the coordinate frame given by pose. More...
 
PCL_EXPORTS float * getInterpolatedSurfaceProjection (const Eigen::Vector3f &point, int pixel_size, float world_size) const
 Same as above, but using the local coordinate frame defined by point and the viewing direction. More...
 
Eigen::Affine3f getTransformationToViewerCoordinateFrame (const Eigen::Vector3f &point) const
 Get the local coordinate frame with 0,0,0 in point, upright and Z as the viewing direction. More...
 
void getTransformationToViewerCoordinateFrame (const Eigen::Vector3f &point, Eigen::Affine3f &transformation) const
 Same as above, using a reference for the retrurn value. More...
 
void getRotationToViewerCoordinateFrame (const Eigen::Vector3f &point, Eigen::Affine3f &transformation) const
 Same as above, but only returning the rotation. More...
 
PCL_EXPORTS bool getNormalBasedUprightTransformation (const Eigen::Vector3f &point, float max_dist, Eigen::Affine3f &transformation) const
 Get a local coordinate frame at the given point based on the normal. More...
 
PCL_EXPORTS void getIntegralImage (float *&integral_image, int *&valid_points_num_image) const
 Get the integral image of the range values (used for fast blur operations). More...
 
PCL_EXPORTS void getBlurredImageUsingIntegralImage (int blur_radius, float *integral_image, int *valid_points_num_image, RangeImage &range_image) const
 Get a blurred version of the range image using box filters on the provided integral image. More...
 
virtual PCL_EXPORTS void getBlurredImage (int blur_radius, RangeImage &range_image) const
 Get a blurred version of the range image using box filters. More...
 
float getEuclideanDistanceSquared (int x1, int y1, int x2, int y2) const
 Get the squared euclidean distance between the two image points. More...
 
float getAverageEuclideanDistance (int x, int y, int offset_x, int offset_y, int max_steps) const
 Doing the above for some steps in the given direction and averaging. More...
 
PCL_EXPORTS void getRangeImageWithSmoothedSurface (int radius, RangeImage &smoothed_range_image) const
 Project all points on the local plane approximation, thereby smoothing the surface of the scan. More...
 
void get1dPointAverage (int x, int y, int delta_x, int delta_y, int no_of_points, PointWithRange &average_point) const
 Calculates the average 3D position of the no_of_points points described by the start point x,y in the direction delta. More...
 
PCL_EXPORTS float getOverlap (const RangeImage &other_range_image, const Eigen::Affine3f &relative_transformation, int search_radius, float max_distance, int pixel_step=1) const
 Calculates the overlap of two range images given the relative transformation (from the given image to *this) More...
 
bool getViewingDirection (int x, int y, Eigen::Vector3f &viewing_direction) const
 Get the viewing direction for the given point. More...
 
void getViewingDirection (const Eigen::Vector3f &point, Eigen::Vector3f &viewing_direction) const
 Get the viewing direction for the given point. More...
 
virtual PCL_EXPORTS RangeImagegetNew () const
 Return a newly created Range image. More...
 
virtual PCL_EXPORTS void copyTo (RangeImage &other) const
 Copy other to *this. More...
 
- Public Member Functions inherited from pcl::PointCloud< PointWithRange >
 PointCloud ()=default
 Default constructor. More...
 
 PointCloud (const PointCloud< PointWithRange > &pc, const Indices &indices)
 Copy constructor from point cloud subset. More...
 
 PointCloud (std::uint32_t width_, std::uint32_t height_, const PointWithRange &value_=PointWithRange())
 Allocate constructor from point cloud subset. More...
 
PointCloudoperator+= (const PointCloud &rhs)
 Add a point cloud to the current cloud. More...
 
PointCloud operator+ (const PointCloud &rhs)
 Add a point cloud to another cloud. More...
 
const PointWithRangeat (int column, int row) const
 Obtain the point given by the (column, row) coordinates. More...
 
PointWithRangeat (int column, int row)
 Obtain the point given by the (column, row) coordinates. More...
 
const PointWithRangeat (std::size_t n) const
 
PointWithRangeat (std::size_t n)
 
const PointWithRangeoperator() (std::size_t column, std::size_t row) const
 Obtain the point given by the (column, row) coordinates. More...
 
PointWithRangeoperator() (std::size_t column, std::size_t row)
 Obtain the point given by the (column, row) coordinates. More...
 
bool isOrganized () const
 Return whether a dataset is organized (e.g., arranged in a structured grid). More...
 
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap (int dim, int stride, int offset)
 Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud. More...
 
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap (int dim, int stride, int offset) const
 Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud. More...
 
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap ()
 
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap () const
 
iterator begin () noexcept
 
const_iterator begin () const noexcept
 
iterator end () noexcept
 
const_iterator end () const noexcept
 
const_iterator cbegin () const noexcept
 
const_iterator cend () const noexcept
 
reverse_iterator rbegin () noexcept
 
const_reverse_iterator rbegin () const noexcept
 
reverse_iterator rend () noexcept
 
const_reverse_iterator rend () const noexcept
 
const_reverse_iterator crbegin () const noexcept
 
const_reverse_iterator crend () const noexcept
 
std::size_t size () const
 
index_t max_size () const noexcept
 
void reserve (std::size_t n)
 
bool empty () const
 
PointWithRangedata () noexcept
 
const PointWithRangedata () const noexcept
 
void resize (std::size_t count)
 Resizes the container to contain count elements. More...
 
void resize (uindex_t new_width, uindex_t new_height)
 Resizes the container to contain new_width * new_height elements. More...
 
void resize (index_t count, const PointWithRange &value)
 Resizes the container to contain count elements. More...
 
void resize (index_t new_width, index_t new_height, const PointWithRange &value)
 Resizes the container to contain count elements. More...
 
const PointWithRangeoperator[] (std::size_t n) const
 
PointWithRangeoperator[] (std::size_t n)
 
const PointWithRangefront () const
 
PointWithRangefront ()
 
const PointWithRangeback () const
 
PointWithRangeback ()
 
void assign (index_t count, const PointWithRange &value)
 Replaces the points with count copies of value More...
 
void assign (index_t new_width, index_t new_height, const PointWithRange &value)
 Replaces the points with new_width * new_height copies of value More...
 
void assign (InputIterator first, InputIterator last)
 Replaces the points with copies of those in the range [first, last) More...
 
void assign (InputIterator first, InputIterator last, index_t new_width)
 Replaces the points with copies of those in the range [first, last) More...
 
void assign (std::initializer_list< PointWithRange > ilist)
 Replaces the points with the elements from the initializer list ilist More...
 
void assign (std::initializer_list< PointWithRange > ilist, index_t new_width)
 Replaces the points with the elements from the initializer list ilist More...
 
void push_back (const PointWithRange &pt)
 Insert a new point in the cloud, at the end of the container. More...
 
void transient_push_back (const PointWithRange &pt)
 Insert a new point in the cloud, at the end of the container. More...
 
reference emplace_back (Args &&...args)
 Emplace a new point in the cloud, at the end of the container. More...
 
reference transient_emplace_back (Args &&...args)
 Emplace a new point in the cloud, at the end of the container. More...
 
iterator insert (iterator position, const PointWithRange &pt)
 Insert a new point in the cloud, given an iterator. More...
 
void insert (iterator position, std::size_t n, const PointWithRange &pt)
 Insert a new point in the cloud N times, given an iterator. More...
 
void insert (iterator position, InputIterator first, InputIterator last)
 Insert a new range of points in the cloud, at a certain position. More...
 
iterator transient_insert (iterator position, const PointWithRange &pt)
 Insert a new point in the cloud, given an iterator. More...
 
void transient_insert (iterator position, std::size_t n, const PointWithRange &pt)
 Insert a new point in the cloud N times, given an iterator. More...
 
void transient_insert (iterator position, InputIterator first, InputIterator last)
 Insert a new range of points in the cloud, at a certain position. More...
 
iterator emplace (iterator position, Args &&...args)
 Emplace a new point in the cloud, given an iterator. More...
 
iterator transient_emplace (iterator position, Args &&...args)
 Emplace a new point in the cloud, given an iterator. More...
 
iterator erase (iterator position)
 Erase a point in the cloud. More...
 
iterator erase (iterator first, iterator last)
 Erase a set of points given by a (first, last) iterator pair. More...
 
iterator transient_erase (iterator position)
 Erase a point in the cloud. More...
 
iterator transient_erase (iterator first, iterator last)
 Erase a set of points given by a (first, last) iterator pair. More...
 
void swap (PointCloud< PointWithRange > &rhs)
 Swap a point cloud with another cloud. More...
 
void clear ()
 Removes all points in a cloud and sets the width and height to 0. More...
 
Ptr makeShared () const
 Copy the cloud to the heap and return a smart pointer Note that deep copy is performed, so avoid using this function on non-empty clouds. More...
 

Static Public Member Functions

static float getMaxAngleSize (const Eigen::Affine3f &viewer_pose, const Eigen::Vector3f &center, float radius)
 Get the size of a certain area when seen from the given pose. More...
 
static Eigen::Vector3f getEigenVector3f (const PointWithRange &point)
 Get Eigen::Vector3f from PointWithRange. More...
 
static PCL_EXPORTS void getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordinate_frame, Eigen::Affine3f &transformation)
 Get the transformation that transforms the given coordinate frame into CAMERA_FRAME. More...
 
template<typename PointCloudTypeWithViewpoints >
static Eigen::Vector3f getAverageViewPoint (const PointCloudTypeWithViewpoints &point_cloud)
 Get the average viewpoint of a point cloud where each point carries viewpoint information as vp_x, vp_y, vp_z. More...
 
static PCL_EXPORTS void extractFarRanges (const pcl::PCLPointCloud2 &point_cloud_data, PointCloud< PointWithViewpoint > &far_ranges)
 Check if the provided data includes far ranges and add them to far_ranges. More...
 
- Static Public Member Functions inherited from pcl::PointCloud< PointWithRange >
static bool concatenate (pcl::PointCloud< PointWithRange > &cloud1, const pcl::PointCloud< PointWithRange > &cloud2)
 
static bool concatenate (const pcl::PointCloud< PointWithRange > &cloud1, const pcl::PointCloud< PointWithRange > &cloud2, pcl::PointCloud< PointWithRange > &cloud_out)
 

Static Public Attributes

static int max_no_of_threads
 The maximum number of openmp threads that can be used in this class. More...
 
static bool debug
 Just for... More...
 

Static Protected Member Functions

static void createLookupTables ()
 Create lookup tables for trigonometric functions. More...
 
static float asinLookUp (float value)
 Query the asin lookup table. More...
 
static float atan2LookUp (float y, float x)
 Query the std::atan2 lookup table. More...
 
static float cosLookUp (float value)
 Query the cos lookup table. More...
 

Protected Attributes

Eigen::Affine3f to_range_image_system_
 Inverse of to_world_system_. More...
 
Eigen::Affine3f to_world_system_
 Inverse of to_range_image_system_. More...
 
float angular_resolution_x_ {0.0f}
 Angular resolution of the range image in x direction in radians per pixel. More...
 
float angular_resolution_y_ {0.0f}
 Angular resolution of the range image in y direction in radians per pixel. More...
 
float angular_resolution_x_reciprocal_ {0.0f}
 1.0/angular_resolution_x_ - provided for better performance of multiplication compared to division More...
 
float angular_resolution_y_reciprocal_ {0.0f}
 1.0/angular_resolution_y_ - provided for better performance of multiplication compared to division More...
 
int image_offset_x_ {0}
 
int image_offset_y_ {0}
 Position of the top left corner of the range image compared to an image of full size (360x180 degrees) More...
 
PointWithRange unobserved_point
 This point is used to be able to return a reference to a non-existing point. More...
 

Static Protected Attributes

static const int lookup_table_size
 
static std::vector< float > asin_lookup_table
 
static std::vector< float > atan_lookup_table
 
static std::vector< float > cos_lookup_table
 

Additional Inherited Members

- Public Attributes inherited from pcl::PointCloud< PointWithRange >
pcl::PCLHeader header
 The point cloud header. More...
 
std::vector< PointWithRange, Eigen::aligned_allocator< PointWithRange > > points
 The point data. More...
 
std::uint32_t width
 The point cloud width (if organized as an image-structure). More...
 
std::uint32_t height
 The point cloud height (if organized as an image-structure). More...
 
bool is_dense
 True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields). More...
 
Eigen::Vector4f sensor_origin_
 Sensor acquisition pose (origin/translation). More...
 
Eigen::Quaternionf sensor_orientation_
 Sensor acquisition pose (rotation). More...
 

Detailed Description

RangeImage is derived from pcl/PointCloud and provides functionalities with focus on situations where a 3D scene was captured from a specific view point.

Author
Bastian Steder

Definition at line 54 of file range_image.h.

Member Typedef Documentation

◆ BaseClass

Definition at line 58 of file range_image.h.

◆ ConstPtr

using pcl::RangeImage::ConstPtr = shared_ptr<const RangeImage>

Definition at line 61 of file range_image.h.

◆ Ptr

using pcl::RangeImage::Ptr = shared_ptr<RangeImage>

Definition at line 60 of file range_image.h.

◆ VectorOfEigenVector3f

using pcl::RangeImage::VectorOfEigenVector3f = std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> >

Definition at line 59 of file range_image.h.

Member Enumeration Documentation

◆ CoordinateFrame

Enumerator
CAMERA_FRAME 
LASER_FRAME 

Definition at line 63 of file range_image.h.

Constructor & Destructor Documentation

◆ RangeImage()

PCL_EXPORTS pcl::RangeImage::RangeImage ( )

Constructor.

Referenced by getNew().

◆ ~RangeImage()

virtual PCL_EXPORTS pcl::RangeImage::~RangeImage ( )
virtualdefault

Destructor.

Member Function Documentation

◆ asinLookUp()

float pcl::RangeImage::asinLookUp ( float  value)
inlinestaticprotected

Query the asin lookup table.

Definition at line 54 of file range_image.hpp.

References asin_lookup_table, lookup_table_size, and pcl_lrintf.

Referenced by getImagePoint(), and pcl::RangeImageSpherical::getImagePoint().

◆ atan2LookUp()

float pcl::RangeImage::atan2LookUp ( float  y,
float  x 
)
inlinestaticprotected

Query the std::atan2 lookup table.

Definition at line 64 of file range_image.hpp.

References atan_lookup_table, lookup_table_size, M_PI, and pcl_lrintf.

Referenced by getImagePoint(), and pcl::RangeImageSpherical::getImagePoint().

◆ calculate3DPoint() [1/4]

void pcl::RangeImage::calculate3DPoint ( float  image_x,
float  image_y,
Eigen::Vector3f &  point 
) const
inline

Calculate the 3D point according to the given image point and the range value at the closest pixel.

Definition at line 584 of file range_image.hpp.

References calculate3DPoint(), getPoint(), and pcl::_PointWithRange::range.

◆ calculate3DPoint() [2/4]

void pcl::RangeImage::calculate3DPoint ( float  image_x,
float  image_y,
float  range,
Eigen::Vector3f &  point 
) const
inlinevirtual

Calculate the 3D point according to the given image point and range.

Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.

Definition at line 571 of file range_image.hpp.

References getAnglesFromImagePoint(), and to_world_system_.

◆ calculate3DPoint() [3/4]

void pcl::RangeImage::calculate3DPoint ( float  image_x,
float  image_y,
float  range,
PointWithRange point 
) const
inline

Calculate the 3D point according to the given image point and range.

Definition at line 592 of file range_image.hpp.

References pcl::_PointWithRange::range.

Referenced by calculate3DPoint(), and pcl::RangeImageBorderExtractor::get3dDirection().

◆ calculate3DPoint() [4/4]

void pcl::RangeImage::calculate3DPoint ( float  image_x,
float  image_y,
PointWithRange point 
) const
inline

Calculate the 3D point according to the given image point and the range value at the closest pixel.

Definition at line 601 of file range_image.hpp.

References calculate3DPoint(), getPoint(), and pcl::_PointWithRange::range.

◆ change3dPointsToLocalCoordinateFrame()

PCL_EXPORTS void pcl::RangeImage::change3dPointsToLocalCoordinateFrame ( )

This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame.

◆ checkPoint()

float pcl::RangeImage::checkPoint ( const Eigen::Vector3f &  point,
PointWithRange point_in_image 
) const
inline

point_in_image will be the point in the image at the position the given point would be.

Returns the range of the given point.

Definition at line 401 of file range_image.hpp.

References getImagePoint(), getPoint(), isInImage(), and unobserved_point.

◆ copyTo()

virtual PCL_EXPORTS void pcl::RangeImage::copyTo ( RangeImage other) const
virtual

Copy other to *this.

Necessary for use in virtual functions that need to copy derived RangeImage classes (like RangeImagePlanar)

Reimplemented in pcl::RangeImagePlanar.

◆ cosLookUp()

float pcl::RangeImage::cosLookUp ( float  value)
inlinestaticprotected

Query the cos lookup table.

Definition at line 90 of file range_image.hpp.

References cos_lookup_table, lookup_table_size, M_PI, and pcl_lrintf.

Referenced by pcl::RangeImagePlanar::calculate3DPoint().

◆ createEmpty() [1/2]

void pcl::RangeImage::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) 
)

Create an empty depth image (filled with unobserved points)

Parameters
[in]angular_resolutionthe angle (in radians) between each sample in the depth image
[in]sensor_posean affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () )
[in]coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
[in]angle_widthan angle (in radians) defining the horizontal bounds of the sensor (defaults to 2*pi (360deg))
[in]angle_heightan angle (in radians) defining the vertical bounds of the sensor (defaults to pi (180deg))

◆ createEmpty() [2/2]

void 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) 
)

Create an empty depth image (filled with unobserved points)

Parameters
angular_resolution_xthe angular difference (in radians) between the individual pixels in the image in the x-direction
angular_resolution_ythe angular difference (in radians) between the individual pixels in the image in the y-direction
[in]sensor_posean affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () )
[in]coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
[in]angle_widthan angle (in radians) defining the horizontal bounds of the sensor (defaults to 2*pi (360deg))
[in]angle_heightan angle (in radians) defining the vertical bounds of the sensor (defaults to pi (180deg))

◆ createFromPointCloud() [1/2]

template<typename PointCloudType >
void 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 (),
RangeImage::CoordinateFrame  coordinate_frame = CAMERA_FRAME,
float  noise_level = 0.0f,
float  min_range = 0.0f,
int  border_size = 0 
)

Create the depth image from a point cloud.

Parameters
point_cloudthe input point cloud
angular_resolutionthe angular difference (in radians) between the individual pixels in the image
max_angle_widthan angle (in radians) defining the horizontal bounds of the sensor
max_angle_heightan angle (in radians) defining the vertical bounds of the sensor
sensor_posean affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () )
coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range (defaults to 0)
border_sizethe border size (defaults to 0). Set to std::numeric_limits<int>::min() to turn cropping off.

Definition at line 98 of file range_image.hpp.

Referenced by createFromPointCloudWithKnownSize(), and createFromPointCloudWithViewpoints().

◆ createFromPointCloud() [2/2]

template<typename PointCloudType >
void 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 (),
RangeImage::CoordinateFrame  coordinate_frame = CAMERA_FRAME,
float  noise_level = 0.0f,
float  min_range = 0.0f,
int  border_size = 0 
)

Create the depth image from a point cloud.

Parameters
point_cloudthe input point cloud
angular_resolution_xthe angular difference (in radians) between the individual pixels in the image in the x-direction
angular_resolution_ythe angular difference (in radians) between the individual pixels in the image in the y-direction
max_angle_widthan angle (in radians) defining the horizontal bounds of the sensor
max_angle_heightan angle (in radians) defining the vertical bounds of the sensor
sensor_posean affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () )
coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range (defaults to 0)
border_sizethe border size (defaults to 0). Set to std::numeric_limits<int>::min() to turn cropping off.

Definition at line 109 of file range_image.hpp.

References angular_resolution_x_reciprocal_, angular_resolution_y_reciprocal_, cropImage(), pcl::deg2rad(), doZBuffer(), getCoordinateFrameTransformation(), pcl::PointCloud< PointWithRange >::height, image_offset_x_, image_offset_y_, pcl::PointCloud< PointWithRange >::is_dense, pcl_lrint, pcl::PointCloud< PointWithRange >::points, recalculate3DPointPositions(), setAngularResolution(), pcl::PointCloud< PointWithRange >::size(), to_range_image_system_, to_world_system_, unobserved_point, and pcl::PointCloud< PointWithRange >::width.

◆ createFromPointCloudWithKnownSize() [1/2]

template<typename PointCloudType >
void pcl::RangeImage::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 (),
RangeImage::CoordinateFrame  coordinate_frame = CAMERA_FRAME,
float  noise_level = 0.0f,
float  min_range = 0.0f,
int  border_size = 0 
)

Create the depth image from a point cloud, getting a hint about the size of the scene for faster calculation.

Parameters
point_cloudthe input point cloud
angular_resolutionthe angle (in radians) between each sample in the depth image
point_cloud_centerthe center of bounding sphere
point_cloud_radiusthe radius of the bounding sphere
sensor_posean affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () )
coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range (defaults to 0)
border_sizethe border size (defaults to 0). Set to std::numeric_limits<int>::min() to turn cropping off.

Definition at line 148 of file range_image.hpp.

◆ createFromPointCloudWithKnownSize() [2/2]

template<typename PointCloudType >
void 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 (),
RangeImage::CoordinateFrame  coordinate_frame = CAMERA_FRAME,
float  noise_level = 0.0f,
float  min_range = 0.0f,
int  border_size = 0 
)

Create the depth image from a point cloud, getting a hint about the size of the scene for faster calculation.

Parameters
point_cloudthe input point cloud
angular_resolution_xthe angular difference (in radians) between the individual pixels in the image in the x-direction
angular_resolution_ythe angular difference (in radians) between the individual pixels in the image in the y-direction
point_cloud_centerthe center of bounding sphere
point_cloud_radiusthe radius of the bounding sphere
sensor_posean affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () )
coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range (defaults to 0)
border_sizethe border size (defaults to 0). Set to std::numeric_limits<int>::min() to turn cropping off.

Definition at line 159 of file range_image.hpp.

References angular_resolution_x_reciprocal_, angular_resolution_y_reciprocal_, createFromPointCloud(), cropImage(), pcl::deg2rad(), doZBuffer(), getCoordinateFrameTransformation(), getImagePoint(), getMaxAngleSize(), pcl::PointCloud< PointWithRange >::height, image_offset_x_, image_offset_y_, pcl::PointCloud< PointWithRange >::is_dense, pcl_lrint, pcl::PointCloud< PointWithRange >::points, recalculate3DPointPositions(), setAngularResolution(), to_range_image_system_, to_world_system_, unobserved_point, and pcl::PointCloud< PointWithRange >::width.

◆ createFromPointCloudWithViewpoints() [1/2]

template<typename PointCloudTypeWithViewpoints >
void pcl::RangeImage::createFromPointCloudWithViewpoints ( const PointCloudTypeWithViewpoints &  point_cloud,
float  angular_resolution,
float  max_angle_width,
float  max_angle_height,
RangeImage::CoordinateFrame  coordinate_frame = CAMERA_FRAME,
float  noise_level = 0.0f,
float  min_range = 0.0f,
int  border_size = 0 
)

Create the depth image from a point cloud, using the average viewpoint of the points (vp_x,vp_y,vp_z in the point type) in the point cloud as sensor pose (assuming a rotation of (0,0,0)).

Parameters
point_cloudthe input point cloud
angular_resolutionthe angle (in radians) between each sample in the depth image
max_angle_widthan angle (in radians) defining the horizontal bounds of the sensor
max_angle_heightan angle (in radians) defining the vertical bounds of the sensor
coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range (defaults to 0)
border_sizethe border size (defaults to 0). Set to std::numeric_limits<int>::min() to turn cropping off.
Note
If wrong_coordinate_system is true, the sensor pose will be rotated to change from a coordinate frame with x to the front, y to the left and z to the top to the coordinate frame we use here (x to the right, y to the bottom and z to the front)

Definition at line 211 of file range_image.hpp.

◆ createFromPointCloudWithViewpoints() [2/2]

template<typename PointCloudTypeWithViewpoints >
void pcl::RangeImage::createFromPointCloudWithViewpoints ( const PointCloudTypeWithViewpoints &  point_cloud,
float  angular_resolution_x,
float  angular_resolution_y,
float  max_angle_width,
float  max_angle_height,
RangeImage::CoordinateFrame  coordinate_frame = CAMERA_FRAME,
float  noise_level = 0.0f,
float  min_range = 0.0f,
int  border_size = 0 
)

Create the depth image from a point cloud, using the average viewpoint of the points (vp_x,vp_y,vp_z in the point type) in the point cloud as sensor pose (assuming a rotation of (0,0,0)).

Parameters
point_cloudthe input point cloud
angular_resolution_xthe angular difference (in radians) between the individual pixels in the image in the x-direction
angular_resolution_ythe angular difference (in radians) between the individual pixels in the image in the y-direction
max_angle_widthan angle (in radians) defining the horizontal bounds of the sensor
max_angle_heightan angle (in radians) defining the vertical bounds of the sensor
coordinate_framethe coordinate frame (defaults to CAMERA_FRAME)
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range (defaults to 0)
border_sizethe border size (defaults to 0). Set to std::numeric_limits<int>::min() to turn cropping off.
Note
If wrong_coordinate_system is true, the sensor pose will be rotated to change from a coordinate frame with x to the front, y to the left and z to the top to the coordinate frame we use here (x to the right, y to the bottom and z to the front)

Definition at line 224 of file range_image.hpp.

References createFromPointCloud(), and getAverageViewPoint().

◆ createLookupTables()

static void pcl::RangeImage::createLookupTables ( )
staticprotected

Create lookup tables for trigonometric functions.

◆ cropImage()

PCL_EXPORTS void pcl::RangeImage::cropImage ( int  border_size = 0,
int  top = -1,
int  right = -1,
int  bottom = -1,
int  left = -1 
)

Cut the range image to the minimal size so that it still contains all actual range readings.

Parameters
border_sizeallows increase from the minimal size by the specified number of pixels (defaults to 0)
topif positive, this value overrides the position of the top edge (defaults to -1)
rightif positive, this value overrides the position of the right edge (defaults to -1)
bottomif positive, this value overrides the position of the bottom edge (defaults to -1)
leftif positive, this value overrides the position of the left edge (defaults to -1)

Referenced by createFromPointCloud(), and createFromPointCloudWithKnownSize().

◆ doZBuffer()

template<typename PointCloudType >
void pcl::RangeImage::doZBuffer ( const PointCloudType &  point_cloud,
float  noise_level,
float  min_range,
int &  top,
int &  right,
int &  bottom,
int &  left 
)

Integrate the given point cloud into the current range image using a z-buffer.

Parameters
point_cloudthe input point cloud
noise_level- The distance in meters inside of which the z-buffer will not use the minimum, but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and will always take the minimum per cell.
min_rangethe minimum visible range
topreturns the minimum y pixel position in the image where a point was added
rightreturns the maximum x pixel position in the image where a point was added
bottomreturns the maximum y pixel position in the image where a point was added
leftreturns the minimum x pixel position in the image where a point was added

Definition at line 238 of file range_image.hpp.

References getImagePoint(), pcl::PointCloud< PointWithRange >::height, pcl::isFinite(), isInImage(), pcl_lrint, pcl::PointCloud< PointWithRange >::points, real2DToInt2D(), pcl::PointCloud< PointWithRange >::size(), and pcl::PointCloud< PointWithRange >::width.

Referenced by createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), and createFromPointCloudWithKnownSize().

◆ extractFarRanges()

static PCL_EXPORTS void pcl::RangeImage::extractFarRanges ( const pcl::PCLPointCloud2 point_cloud_data,
PointCloud< PointWithViewpoint > &  far_ranges 
)
static

Check if the provided data includes far ranges and add them to far_ranges.

Parameters
point_cloud_dataa PCLPointCloud2 message containing the input cloud
far_rangesthe resulting cloud containing those points with far ranges

◆ get1dPointAverage()

void pcl::RangeImage::get1dPointAverage ( int  x,
int  y,
int  delta_x,
int  delta_y,
int  no_of_points,
PointWithRange average_point 
) const
inline

Calculates the average 3D position of the no_of_points points described by the start point x,y in the direction delta.

Returns a max range point (range=INFINITY) if the first point is max range and an unobserved point (range=-INFINITY) if non of the points is observed.

Definition at line 809 of file range_image.hpp.

References getPoint(), getPointNoCheck(), isValid(), pcl::_PointWithRange::range, and unobserved_point.

Referenced by pcl::RangeImageBorderExtractor::getNeighborDistanceChangeScore().

◆ getAcutenessValue() [1/2]

float pcl::RangeImage::getAcutenessValue ( const PointWithRange point1,
const PointWithRange point2 
) const
inline

Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) will return -INFINITY if one of the points is unobserved.

Definition at line 659 of file range_image.hpp.

References getImpactAngle(), and M_PI.

Referenced by getAcutenessValue().

◆ getAcutenessValue() [2/2]

float pcl::RangeImage::getAcutenessValue ( int  x1,
int  y1,
int  x2,
int  y2 
) const
inline

Same as above.

Definition at line 674 of file range_image.hpp.

References getAcutenessValue(), getPoint(), and isInImage().

◆ getAcutenessValueImages()

PCL_EXPORTS void pcl::RangeImage::getAcutenessValueImages ( int  pixel_distance,
float *&  acuteness_value_image_x,
float *&  acuteness_value_image_y 
) const

Calculate getAcutenessValue for every point.

◆ getAnglesFromImagePoint()

void pcl::RangeImage::getAnglesFromImagePoint ( float  image_x,
float  image_y,
float &  angle_x,
float &  angle_y 
) const
inline

Get the angles corresponding to the given image point.

Definition at line 609 of file range_image.hpp.

References angular_resolution_x_, angular_resolution_y_, image_offset_x_, image_offset_y_, and M_PI.

Referenced by calculate3DPoint().

◆ getAngularResolution() [1/2]

float pcl::RangeImage::getAngularResolution ( ) const
inline

Getter for the angular resolution of the range image in x direction in radians per pixel.

Provided for downwards compatibility

Definition at line 352 of file range_image.h.

References angular_resolution_x_.

◆ getAngularResolution() [2/2]

void pcl::RangeImage::getAngularResolution ( float &  angular_resolution_x,
float &  angular_resolution_y 
) const
inline

Getter for the angular resolution of the range image in x and y direction (in radians).

Definition at line 1221 of file range_image.hpp.

References angular_resolution_x_, and angular_resolution_y_.

◆ getAngularResolutionX()

float pcl::RangeImage::getAngularResolutionX ( ) const
inline

Getter for the angular resolution of the range image in x direction in radians per pixel.

Definition at line 356 of file range_image.h.

References angular_resolution_x_.

Referenced by pcl::operator<<().

◆ getAngularResolutionY()

float pcl::RangeImage::getAngularResolutionY ( ) const
inline

Getter for the angular resolution of the range image in y direction in radians per pixel.

Definition at line 360 of file range_image.h.

References angular_resolution_y_.

Referenced by pcl::operator<<().

◆ getAverageEuclideanDistance()

float pcl::RangeImage::getAverageEuclideanDistance ( int  x,
int  y,
int  offset_x,
int  offset_y,
int  max_steps 
) const
inline

Doing the above for some steps in the given direction and averaging.

Definition at line 864 of file range_image.hpp.

References getEuclideanDistanceSquared().

◆ getAverageViewPoint()

template<typename PointCloudTypeWithViewpoints >
Eigen::Vector3f pcl::RangeImage::getAverageViewPoint ( const PointCloudTypeWithViewpoints &  point_cloud)
static

Get the average viewpoint of a point cloud where each point carries viewpoint information as vp_x, vp_y, vp_z.

Parameters
point_cloudthe input point cloud
Returns
the average viewpoint (as an Eigen::Vector3f)

Definition at line 1133 of file range_image.hpp.

Referenced by createFromPointCloudWithViewpoints().

◆ getBlurredImage()

virtual PCL_EXPORTS void pcl::RangeImage::getBlurredImage ( int  blur_radius,
RangeImage range_image 
) const
virtual

Get a blurred version of the range image using box filters.

◆ getBlurredImageUsingIntegralImage()

PCL_EXPORTS void pcl::RangeImage::getBlurredImageUsingIntegralImage ( int  blur_radius,
float *  integral_image,
int *  valid_points_num_image,
RangeImage range_image 
) const

Get a blurred version of the range image using box filters on the provided integral image.

◆ getCoordinateFrameTransformation()

static PCL_EXPORTS void pcl::RangeImage::getCoordinateFrameTransformation ( RangeImage::CoordinateFrame  coordinate_frame,
Eigen::Affine3f &  transformation 
)
static

Get the transformation that transforms the given coordinate frame into CAMERA_FRAME.

Parameters
coordinate_framethe input coordinate frame
transformationthe resulting transformation that warps coordinate_frame into CAMERA_FRAME

Referenced by createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), and createFromPointCloudWithKnownSize().

◆ getCurvature()

float pcl::RangeImage::getCurvature ( int  x,
int  y,
int  radius,
int  step_size 
) const
inline

◆ getEigenVector3f() [1/3]

Eigen::Vector3f pcl::RangeImage::getEigenVector3f ( const PointWithRange point)
inlinestatic

Get Eigen::Vector3f from PointWithRange.

Parameters
pointthe input point
Returns
an Eigen::Vector3f representation of the input point

Definition at line 802 of file range_image.hpp.

Referenced by getImpactAngleBasedOnLocalNormal().

◆ getEigenVector3f() [2/3]

const Eigen::Map< const Eigen::Vector3f > pcl::RangeImage::getEigenVector3f ( int  index) const
inline

Same as above.

Definition at line 564 of file range_image.hpp.

References getPoint().

◆ getEigenVector3f() [3/3]

const Eigen::Map< const Eigen::Vector3f > pcl::RangeImage::getEigenVector3f ( int  x,
int  y 
) const
inline

Same as above.

Definition at line 557 of file range_image.hpp.

References getPoint().

◆ getEuclideanDistanceSquared()

float pcl::RangeImage::getEuclideanDistanceSquared ( int  x1,
int  y1,
int  x2,
int  y2 
) const
inline

Get the squared euclidean distance between the two image points.

Returns -INFINITY if one of the points was not observed

Definition at line 849 of file range_image.hpp.

References getPoint(), isObserved(), pcl::_PointWithRange::range, and pcl::squaredEuclideanDistance().

Referenced by getAverageEuclideanDistance().

◆ getHalfImage()

virtual void pcl::RangeImage::getHalfImage ( RangeImage half_image) const
virtual

Get a range image with half the resolution.

Reimplemented in pcl::RangeImagePlanar.

◆ getImageOffsetX()

int pcl::RangeImage::getImageOffsetX ( ) const
inline

Getter for image_offset_x_.

Definition at line 630 of file range_image.h.

References image_offset_x_.

◆ getImageOffsetY()

int pcl::RangeImage::getImageOffsetY ( ) const
inline

Getter for image_offset_y_.

Definition at line 633 of file range_image.h.

References image_offset_y_.

◆ getImagePoint() [1/7]

void pcl::RangeImage::getImagePoint ( const Eigen::Vector3f &  point,
float &  image_x,
float &  image_y 
) const
inline

Same as above.

Definition at line 384 of file range_image.hpp.

References getImagePoint().

◆ getImagePoint() [2/7]

void pcl::RangeImage::getImagePoint ( const Eigen::Vector3f &  point,
float &  image_x,
float &  image_y,
float &  range 
) const
inlinevirtual

◆ getImagePoint() [3/7]

void pcl::RangeImage::getImagePoint ( const Eigen::Vector3f &  point,
int &  image_x,
int &  image_y 
) const
inline

Same as above.

Definition at line 392 of file range_image.hpp.

References getImagePoint(), and real2DToInt2D().

◆ getImagePoint() [4/7]

void pcl::RangeImage::getImagePoint ( const Eigen::Vector3f &  point,
int &  image_x,
int &  image_y,
float &  range 
) const
inline

Same as above.

Definition at line 376 of file range_image.hpp.

References getImagePoint(), and real2DToInt2D().

◆ getImagePoint() [5/7]

void pcl::RangeImage::getImagePoint ( float  x,
float  y,
float  z,
float &  image_x,
float &  image_y 
) const
inline

Same as above.

Definition at line 340 of file range_image.hpp.

References getImagePoint().

◆ getImagePoint() [6/7]

void pcl::RangeImage::getImagePoint ( float  x,
float  y,
float  z,
float &  image_x,
float &  image_y,
float &  range 
) const
inline

Same as above.

Definition at line 332 of file range_image.hpp.

References getImagePoint().

◆ getImagePoint() [7/7]

void pcl::RangeImage::getImagePoint ( float  x,
float  y,
float  z,
int &  image_x,
int &  image_y 
) const
inline

Same as above.

Definition at line 348 of file range_image.hpp.

References getImagePoint(), and real2DToInt2D().

◆ getImagePointFromAngles()

void pcl::RangeImage::getImagePointFromAngles ( float  angle_x,
float  angle_y,
float &  image_x,
float &  image_y 
) const
inline

Get the image point corresponding to the given angles.

Definition at line 434 of file range_image.hpp.

Referenced by getImagePoint().

◆ getImpactAngle() [1/2]

float pcl::RangeImage::getImpactAngle ( const PointWithRange point1,
const PointWithRange point2 
) const
inline

Calculate the impact angle based on the sensor position and the two given points - will return -INFINITY if one of the points is unobserved.

Definition at line 627 of file range_image.hpp.

References M_PI, pcl::_PointWithRange::range, and pcl::squaredEuclideanDistance().

Referenced by getAcutenessValue(), and getImpactAngle().

◆ getImpactAngle() [2/2]

float pcl::RangeImage::getImpactAngle ( int  x1,
int  y1,
int  x2,
int  y2 
) const
inline

Same as above.

Definition at line 618 of file range_image.hpp.

References getImpactAngle(), getPoint(), and isInImage().

◆ getImpactAngleBasedOnLocalNormal()

float pcl::RangeImage::getImpactAngleBasedOnLocalNormal ( int  x,
int  y,
int  radius 
) const
inline

Extract a local normal (with a heuristic not to include background points) and calculate the impact angle based on this.

Definition at line 891 of file range_image.hpp.

References pcl::deg2rad(), getEigenVector3f(), getNormalForClosestNeighbors(), getPoint(), getSensorPos(), and isValid().

Referenced by getNormalBasedAcutenessValue().

◆ getImpactAngleImageBasedOnLocalNormals()

PCL_EXPORTS float* pcl::RangeImage::getImpactAngleImageBasedOnLocalNormals ( int  radius) const

Uses the above function for every point in the image.

◆ getIntegralImage()

PCL_EXPORTS void pcl::RangeImage::getIntegralImage ( float *&  integral_image,
int *&  valid_points_num_image 
) const

Get the integral image of the range values (used for fast blur operations).

You are responsible for deleting it after usage!

◆ getInterpolatedSurfaceProjection() [1/2]

PCL_EXPORTS float* pcl::RangeImage::getInterpolatedSurfaceProjection ( const Eigen::Affine3f &  pose,
int  pixel_size,
float  world_size 
) const

Calculate a range patch as the z values of the coordinate frame given by pose.

The patch will have size pixel_size x pixel_size and each pixel covers world_size/pixel_size meters in the world You are responsible for deleting the structure afterwards!

◆ getInterpolatedSurfaceProjection() [2/2]

PCL_EXPORTS float* pcl::RangeImage::getInterpolatedSurfaceProjection ( const Eigen::Vector3f &  point,
int  pixel_size,
float  world_size 
) const

Same as above, but using the local coordinate frame defined by point and the viewing direction.

◆ getMaxAngleSize()

float pcl::RangeImage::getMaxAngleSize ( const Eigen::Affine3f &  viewer_pose,
const Eigen::Vector3f &  center,
float  radius 
)
inlinestatic

Get the size of a certain area when seen from the given pose.

Parameters
viewer_posean affine matrix defining the pose of the viewer
centerthe center of the area
radiusthe radius of the area
Returns
the size of the area as viewed according to viewer_pose

Definition at line 795 of file range_image.hpp.

Referenced by createFromPointCloudWithKnownSize().

◆ getMinMaxRanges()

PCL_EXPORTS void pcl::RangeImage::getMinMaxRanges ( float &  min_range,
float &  max_range 
) const

Find the minimum and maximum range in the image.

◆ getNew()

virtual PCL_EXPORTS RangeImage* pcl::RangeImage::getNew ( ) const
inlinevirtual

Return a newly created Range image.

Can be reimplemented in derived classes like RangeImagePlanar to return an image of the same type.

Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.

Definition at line 749 of file range_image.h.

References RangeImage().

◆ getNormal()

bool pcl::RangeImage::getNormal ( int  x,
int  y,
int  radius,
Eigen::Vector3f &  normal,
int  step_size = 1 
) const
inline

Calculate the normal of an image point using the neighbors with a maximum pixel distance of radius.

step_size determines how many pixels are used. 1 means all, 2 only every second, etc.. Returns false if it was unable to calculate a normal.

Definition at line 906 of file range_image.hpp.

References pcl::VectorAverage< real, dimension >::add(), pcl::VectorAverage< real, dimension >::doPCA(), pcl::VectorAverage< real, dimension >::getMean(), pcl::VectorAverage< real, dimension >::getNoOfSamples(), getPoint(), getSensorPos(), isInImage(), and pcl::_PointWithRange::range.

◆ getNormalBasedAcutenessValue()

float pcl::RangeImage::getNormalBasedAcutenessValue ( int  x,
int  y,
int  radius 
) const
inline

Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) This uses getImpactAngleBasedOnLocalNormal Will return -INFINITY if no normal could be calculated.

Definition at line 932 of file range_image.hpp.

References getImpactAngleBasedOnLocalNormal(), and M_PI.

◆ getNormalBasedUprightTransformation()

PCL_EXPORTS bool pcl::RangeImage::getNormalBasedUprightTransformation ( const Eigen::Vector3f &  point,
float  max_dist,
Eigen::Affine3f &  transformation 
) const

Get a local coordinate frame at the given point based on the normal.

◆ getNormalForClosestNeighbors() [1/3]

bool pcl::RangeImage::getNormalForClosestNeighbors ( int  x,
int  y,
Eigen::Vector3f &  normal,
int  radius = 2 
) const
inline

Same as above, using default values.

Definition at line 952 of file range_image.hpp.

References getNormalForClosestNeighbors(), getPoint(), and isValid().

◆ getNormalForClosestNeighbors() [2/3]

bool pcl::RangeImage::getNormalForClosestNeighbors ( int  x,
int  y,
int  radius,
const Eigen::Vector3f &  point,
int  no_of_nearest_neighbors,
Eigen::Vector3f &  normal,
Eigen::Vector3f *  point_on_plane = nullptr,
int  step_size = 1 
) const
inline

Same as above.

Definition at line 1089 of file range_image.hpp.

References getSurfaceInformation().

◆ getNormalForClosestNeighbors() [3/3]

bool 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
inline

Same as above, but only the no_of_nearest_neighbors points closest to the given point are considered.

Definition at line 944 of file range_image.hpp.

Referenced by getImpactAngleBasedOnLocalNormal(), and getNormalForClosestNeighbors().

◆ getOverlap()

PCL_EXPORTS float pcl::RangeImage::getOverlap ( const RangeImage other_range_image,
const Eigen::Affine3f &  relative_transformation,
int  search_radius,
float  max_distance,
int  pixel_step = 1 
) const

Calculates the overlap of two range images given the relative transformation (from the given image to *this)

◆ getPoint() [1/7]

PointWithRange & pcl::RangeImage::getPoint ( float  image_x,
float  image_y 
)
inline

Non-const-version of the above.

Definition at line 533 of file range_image.hpp.

References getPoint(), and real2DToInt2D().

◆ getPoint() [2/7]

const PointWithRange & pcl::RangeImage::getPoint ( float  image_x,
float  image_y 
) const
inline

Return the 3d point with range at the given image position.

Definition at line 524 of file range_image.hpp.

References getPoint(), and real2DToInt2D().

◆ getPoint() [3/7]

PointWithRange & pcl::RangeImage::getPoint ( int  image_x,
int  image_y 
)
inline

Non-const-version of getPoint.

Definition at line 509 of file range_image.hpp.

References pcl::PointCloud< PointWithRange >::points, and pcl::PointCloud< PointWithRange >::width.

◆ getPoint() [4/7]

const PointWithRange & pcl::RangeImage::getPoint ( int  image_x,
int  image_y 
) const
inline

◆ getPoint() [5/7]

void pcl::RangeImage::getPoint ( int  image_x,
int  image_y,
Eigen::Vector3f &  point 
) const
inline

Same as above.

Definition at line 542 of file range_image.hpp.

References getPoint().

◆ getPoint() [6/7]

const PointWithRange & pcl::RangeImage::getPoint ( int  index) const
inline

Return the 3d point with range at the given index (whereas index=y*width+x)

Definition at line 517 of file range_image.hpp.

References pcl::PointCloud< PointWithRange >::points.

◆ getPoint() [7/7]

void pcl::RangeImage::getPoint ( int  index,
Eigen::Vector3f &  point 
) const
inline

Same as above.

Definition at line 550 of file range_image.hpp.

References getPoint().

◆ getPointNoCheck() [1/2]

PointWithRange & pcl::RangeImage::getPointNoCheck ( int  image_x,
int  image_y 
)
inline

Non-const-version of getPointNoCheck.

Definition at line 502 of file range_image.hpp.

References pcl::PointCloud< PointWithRange >::points, and pcl::PointCloud< PointWithRange >::width.

◆ getPointNoCheck() [2/2]

const PointWithRange & pcl::RangeImage::getPointNoCheck ( int  image_x,
int  image_y 
) const
inline

Return the 3D point with range at the given image position.

This method performs no error checking to make sure the specified image position is inside of the image!

Parameters
image_xthe x coordinate
image_ythe y coordinate
Returns
the point at the specified location (program may fail if the location is outside of the image bounds)

Definition at line 495 of file range_image.hpp.

References pcl::PointCloud< PointWithRange >::points, and pcl::PointCloud< PointWithRange >::width.

Referenced by get1dPointAverage(), and getSquaredDistanceOfNthNeighbor().

◆ getRangeDifference()

float pcl::RangeImage::getRangeDifference ( const Eigen::Vector3f &  point) const
inline

Returns the difference in range between the given point and the range of the point in the image at the position the given point would be.

(Return value is point_in_image.range-given_point.range)

Definition at line 415 of file range_image.hpp.

References getImagePoint(), getPoint(), isInImage(), and pcl::_PointWithRange::range.

◆ getRangeImageWithSmoothedSurface()

PCL_EXPORTS void pcl::RangeImage::getRangeImageWithSmoothedSurface ( int  radius,
RangeImage smoothed_range_image 
) const

Project all points on the local plane approximation, thereby smoothing the surface of the scan.

◆ getRangesArray()

PCL_EXPORTS float* pcl::RangeImage::getRangesArray ( ) const

Get all the range values in one float array of size width*height.

Returns
a pointer to a new float array containing the range values
Note
This method allocates a new float array; the caller is responsible for freeing this memory.

◆ getRotationToViewerCoordinateFrame()

void pcl::RangeImage::getRotationToViewerCoordinateFrame ( const Eigen::Vector3f &  point,
Eigen::Affine3f &  transformation 
) const
inline

Same as above, but only returning the rotation.

Definition at line 1187 of file range_image.hpp.

References getSensorPos(), and pcl::getTransformationFromTwoUnitVectors().

◆ getSensorPos()

const Eigen::Vector3f pcl::RangeImage::getSensorPos ( ) const
inline

◆ getSquaredDistanceOfNthNeighbor()

float pcl::RangeImage::getSquaredDistanceOfNthNeighbor ( int  x,
int  y,
int  radius,
int  n,
int  step_size 
) const
inline

◆ getSubImage()

virtual void pcl::RangeImage::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
virtual

Get a sub part of the complete image as a new range image.

Parameters
sub_image_image_offset_x- The x coordinate of the top left pixel of the sub image. This is always according to absolute 0,0 meaning -180°,-90° and it is already in the system of the new image, so the actual pixel used in the original image is combine_pixels* (image_offset_x-image_offset_x_)
sub_image_image_offset_y- Same as image_offset_x for the y coordinate
sub_image_width- width of the new image
sub_image_height- height of the new image
combine_pixels- shrinking factor, meaning the new angular resolution is combine_pixels times the old one
sub_image- the output image

Reimplemented in pcl::RangeImagePlanar.

◆ getSurfaceAngleChange()

void pcl::RangeImage::getSurfaceAngleChange ( int  x,
int  y,
int  radius,
float &  angle_change_x,
float &  angle_change_y 
) const
inline

Calculates, how much the surface changes at a point.

Returns an angle [0.0f, PI] for x and y direction. A return value of -INFINITY means that a point was unobserved.

Definition at line 690 of file range_image.hpp.

References getPoint(), getTransformationToViewerCoordinateFrame(), isMaxRange(), isObserved(), and isValid().

◆ getSurfaceAngleChangeImages()

PCL_EXPORTS void pcl::RangeImage::getSurfaceAngleChangeImages ( int  radius,
float *&  angle_change_image_x,
float *&  angle_change_image_y 
) const

Uses the above function for every point in the image.

◆ getSurfaceChange()

PCL_EXPORTS float pcl::RangeImage::getSurfaceChange ( int  x,
int  y,
int  radius 
) const

Calculates, how much the surface changes at a point.

Pi meaning a flat surface and 0.0f would be a needle point Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat surface

◆ getSurfaceChangeImage()

PCL_EXPORTS float* pcl::RangeImage::getSurfaceChangeImage ( int  radius) const

Uses the above function for every point in the image.

◆ getSurfaceInformation()

bool 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 = nullptr,
Eigen::Vector3f *  mean_all_neighbors = nullptr,
Eigen::Vector3f *  eigen_values_all_neighbors = nullptr 
) const
inline

Same as above but extracts some more data and can also return the extracted information for all neighbors in radius if normal_all_neighbors is not NULL.

Definition at line 972 of file range_image.hpp.

References pcl::VectorAverage< real, dimension >::add(), pcl::geometry::distance(), pcl::VectorAverage< real, dimension >::doPCA(), pcl::VectorAverage< real, dimension >::getMean(), pcl::VectorAverage< real, dimension >::getNoOfSamples(), getPoint(), getSensorPos(), isValid(), and pcl::squaredEuclideanDistance().

Referenced by getNormalForClosestNeighbors().

◆ getTransformationToRangeImageSystem()

const Eigen::Affine3f& pcl::RangeImage::getTransformationToRangeImageSystem ( ) const
inline

Getter for the transformation from the world system into the range image system (the sensor coordinate frame)

Definition at line 337 of file range_image.h.

References to_range_image_system_.

◆ getTransformationToViewerCoordinateFrame() [1/2]

Eigen::Affine3f pcl::RangeImage::getTransformationToViewerCoordinateFrame ( const Eigen::Vector3f &  point) const
inline

Get the local coordinate frame with 0,0,0 in point, upright and Z as the viewing direction.

Definition at line 1170 of file range_image.hpp.

Referenced by getSurfaceAngleChange().

◆ getTransformationToViewerCoordinateFrame() [2/2]

void pcl::RangeImage::getTransformationToViewerCoordinateFrame ( const Eigen::Vector3f &  point,
Eigen::Affine3f &  transformation 
) const
inline

Same as above, using a reference for the retrurn value.

Definition at line 1179 of file range_image.hpp.

References getSensorPos(), and pcl::getTransformationFromTwoUnitVectorsAndOrigin().

◆ getTransformationToWorldSystem()

const Eigen::Affine3f& pcl::RangeImage::getTransformationToWorldSystem ( ) const
inline

Getter for the transformation from the range image system (the sensor coordinate frame) into the world system.

Definition at line 347 of file range_image.h.

References to_world_system_.

◆ getViewingDirection() [1/2]

void pcl::RangeImage::getViewingDirection ( const Eigen::Vector3f &  point,
Eigen::Vector3f &  viewing_direction 
) const
inline

Get the viewing direction for the given point.

Definition at line 1163 of file range_image.hpp.

References getSensorPos().

◆ getViewingDirection() [2/2]

bool pcl::RangeImage::getViewingDirection ( int  x,
int  y,
Eigen::Vector3f &  viewing_direction 
) const
inline

Get the viewing direction for the given point.

Definition at line 1153 of file range_image.hpp.

References getPoint(), getSensorPos(), and isValid().

◆ integrateFarRanges()

template<typename PointCloudType >
void pcl::RangeImage::integrateFarRanges ( const PointCloudType &  far_ranges)

Integrates the given far range measurements into the range image.

Definition at line 1229 of file range_image.hpp.

References getImagePoint(), getPoint(), isInImage(), pcl_lrint, and pcl::_PointWithRange::range.

◆ isInImage()

bool pcl::RangeImage::isInImage ( int  x,
int  y 
) const
inline

◆ isMaxRange()

bool pcl::RangeImage::isMaxRange ( int  x,
int  y 
) const
inline

Check if a point is a max range (range=INFINITY) - please check isInImage or isObserved first!

Definition at line 478 of file range_image.hpp.

References getPoint(), and pcl::_PointWithRange::range.

Referenced by pcl::RangeImageBorderExtractor::changeScoreAccordingToShadowBorderValue(), and getSurfaceAngleChange().

◆ isObserved()

bool pcl::RangeImage::isObserved ( int  x,
int  y 
) const
inline

Check if a point is inside of the image and has either a finite range or a max reading (range=INFINITY)

Definition at line 471 of file range_image.hpp.

Referenced by getEuclideanDistanceSquared(), and getSurfaceAngleChange().

◆ isValid() [1/2]

bool pcl::RangeImage::isValid ( int  index) const
inline

Check if a point has a finite range.

Definition at line 464 of file range_image.hpp.

◆ isValid() [2/2]

bool pcl::RangeImage::isValid ( int  x,
int  y 
) const
inline

◆ makeShared()

Ptr pcl::RangeImage::makeShared ( )
inline

Get a boost shared pointer of a copy of this.

Definition at line 124 of file range_image.h.

◆ real2DToInt2D()

void pcl::RangeImage::real2DToInt2D ( float  x,
float  y,
int &  xInt,
int &  yInt 
) const
inline

Transforms an image point in float values to an image point in int values.

Definition at line 442 of file range_image.hpp.

Referenced by doZBuffer(), getImagePoint(), and getPoint().

◆ recalculate3DPointPositions()

PCL_EXPORTS void pcl::RangeImage::recalculate3DPointPositions ( )

Recalculate all 3D point positions according to their pixel position and range.

Referenced by createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), and createFromPointCloudWithKnownSize().

◆ reset()

PCL_EXPORTS void pcl::RangeImage::reset ( )

Reset all values to an empty range image.

◆ setAngularResolution() [1/2]

void pcl::RangeImage::setAngularResolution ( float  angular_resolution)
inline

Set the angular resolution of the range image.

Parameters
angular_resolutionthe new angular resolution in x and y direction (in radians per pixel)

Definition at line 1195 of file range_image.hpp.

References angular_resolution_x_, angular_resolution_x_reciprocal_, angular_resolution_y_, and angular_resolution_y_reciprocal_.

Referenced by createFromPointCloud(), and createFromPointCloudWithKnownSize().

◆ setAngularResolution() [2/2]

void pcl::RangeImage::setAngularResolution ( float  angular_resolution_x,
float  angular_resolution_y 
)
inline

Set the angular resolution of the range image.

Parameters
angular_resolution_xthe new angular resolution in x direction (in radians per pixel)
angular_resolution_ythe new angular resolution in y direction (in radians per pixel)

Definition at line 1203 of file range_image.hpp.

References angular_resolution_x_, angular_resolution_x_reciprocal_, angular_resolution_y_, and angular_resolution_y_reciprocal_.

◆ setImageOffsets()

void pcl::RangeImage::setImageOffsets ( int  offset_x,
int  offset_y 
)
inline

Setter for image offsets.

Definition at line 637 of file range_image.h.

References image_offset_x_, and image_offset_y_.

◆ setTransformationToRangeImageSystem()

void pcl::RangeImage::setTransformationToRangeImageSystem ( const Eigen::Affine3f &  to_range_image_system)
inline

Setter for the transformation from the range image system (the sensor coordinate frame) into the world system.

Definition at line 1213 of file range_image.hpp.

References to_range_image_system_, and to_world_system_.

◆ setUnseenToMaxRange()

PCL_EXPORTS void pcl::RangeImage::setUnseenToMaxRange ( )

Sets all -INFINITY values to INFINITY.

Member Data Documentation

◆ angular_resolution_x_

float pcl::RangeImage::angular_resolution_x_ {0.0f}
protected

Angular resolution of the range image in x direction in radians per pixel.

Definition at line 770 of file range_image.h.

Referenced by getAnglesFromImagePoint(), pcl::RangeImageSpherical::getAnglesFromImagePoint(), getAngularResolution(), getAngularResolutionX(), and setAngularResolution().

◆ angular_resolution_x_reciprocal_

float pcl::RangeImage::angular_resolution_x_reciprocal_ {0.0f}
protected

1.0/angular_resolution_x_ - provided for better performance of multiplication compared to division

Definition at line 772 of file range_image.h.

Referenced by pcl::RangeImagePlanar::calculate3DPoint(), createFromPointCloud(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getImagePointFromAngles(), and setAngularResolution().

◆ angular_resolution_y_

float pcl::RangeImage::angular_resolution_y_ {0.0f}
protected

Angular resolution of the range image in y direction in radians per pixel.

Definition at line 771 of file range_image.h.

Referenced by getAnglesFromImagePoint(), pcl::RangeImageSpherical::getAnglesFromImagePoint(), getAngularResolution(), getAngularResolutionY(), and setAngularResolution().

◆ angular_resolution_y_reciprocal_

float pcl::RangeImage::angular_resolution_y_reciprocal_ {0.0f}
protected

1.0/angular_resolution_y_ - provided for better performance of multiplication compared to division

Definition at line 774 of file range_image.h.

Referenced by pcl::RangeImagePlanar::calculate3DPoint(), createFromPointCloud(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getImagePointFromAngles(), and setAngularResolution().

◆ asin_lookup_table

std::vector<float> pcl::RangeImage::asin_lookup_table
staticprotected

Definition at line 786 of file range_image.h.

Referenced by asinLookUp().

◆ atan_lookup_table

std::vector<float> pcl::RangeImage::atan_lookup_table
staticprotected

Definition at line 787 of file range_image.h.

Referenced by atan2LookUp().

◆ cos_lookup_table

std::vector<float> pcl::RangeImage::cos_lookup_table
staticprotected

Definition at line 788 of file range_image.h.

Referenced by cosLookUp().

◆ debug

bool pcl::RangeImage::debug
static

Just for...

well... debugging purposes. :-)

Definition at line 764 of file range_image.h.

◆ image_offset_x_

int pcl::RangeImage::image_offset_x_ {0}
protected

◆ image_offset_y_

int pcl::RangeImage::image_offset_y_ {0}
protected

◆ lookup_table_size

const int pcl::RangeImage::lookup_table_size
staticprotected

Definition at line 785 of file range_image.h.

Referenced by asinLookUp(), atan2LookUp(), and cosLookUp().

◆ max_no_of_threads

int pcl::RangeImage::max_no_of_threads
static

The maximum number of openmp threads that can be used in this class.

Definition at line 78 of file range_image.h.

◆ to_range_image_system_

Eigen::Affine3f pcl::RangeImage::to_range_image_system_
protected

◆ to_world_system_

Eigen::Affine3f pcl::RangeImage::to_world_system_
protected

◆ unobserved_point

PointWithRange pcl::RangeImage::unobserved_point
protected

This point is used to be able to return a reference to a non-existing point.

Definition at line 778 of file range_image.h.

Referenced by checkPoint(), createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), createFromPointCloudWithKnownSize(), get1dPointAverage(), and getPoint().


The documentation for this class was generated from the following files: