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>
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 PointWithRange & | getPoint (int image_x, int image_y) const |
Return the 3D point with range at the given image position. More... |
|
PointWithRange & | getPoint (int image_x, int image_y) |
Non-const-version of getPoint. More... |
|
const PointWithRange & | getPoint (float image_x, float image_y) const |
Return the 3d point with range at the given image position. More... |
|
PointWithRange & | getPoint (float image_x, float image_y) |
Non-const-version of the above. More... |
|
const PointWithRange & | getPointNoCheck (int image_x, int image_y) const |
Return the 3D point with range at the given image position. More... |
|
PointWithRange & | getPointNoCheck (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 PointWithRange & | getPoint (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 *´ness_value_image_x, float *´ness_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 RangeImage * | getNew () 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... |
|
PointCloud & | operator+= (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 PointWithRange & | at (int column, int row) const |
Obtain the point given by the (column, row) coordinates. More... |
|
PointWithRange & | at (int column, int row) |
Obtain the point given by the (column, row) coordinates. More... |
|
const PointWithRange & | at (std::size_t n) const |
PointWithRange & | at (std::size_t n) |
const PointWithRange & | operator() (std::size_t column, std::size_t row) const |
Obtain the point given by the (column, row) coordinates. More... |
|
PointWithRange & | operator() (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 |
PointWithRange * | data () noexcept |
const PointWithRange * | data () 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 PointWithRange & | operator[] (std::size_t n) const |
PointWithRange & | operator[] (std::size_t n) |
const PointWithRange & | front () const |
PointWithRange & | front () |
const PointWithRange & | back () const |
PointWithRange & | back () |
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 ¢er, 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_ |
Angular resolution of the range image in x direction in radians per pixel. More... |
|
float | angular_resolution_y_ |
Angular resolution of the range image in y direction in radians per pixel. More... |
|
float | angular_resolution_x_reciprocal_ |
1.0/angular_resolution_x_ - provided for better performance of multiplication compared to division More... |
|
float | angular_resolution_y_reciprocal_ |
1.0/angular_resolution_y_ - provided for better performance of multiplication compared to division More... |
|
int | image_offset_x_ |
int | image_offset_y_ |
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... |
|
RangeImage is derived from pcl/PointCloud and provides functionalities with focus on situations where a 3D scene was captured from a specific view point.
Definition at line 54 of file range_image.h.
Definition at line 58 of file range_image.h.
using pcl::RangeImage::ConstPtr = shared_ptr<const RangeImage> |
Definition at line 61 of file range_image.h.
using pcl::RangeImage::Ptr = shared_ptr<RangeImage> |
Definition at line 60 of file range_image.h.
using pcl::RangeImage::VectorOfEigenVector3f = std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > |
Definition at line 59 of file range_image.h.
Enumerator | |
---|---|
CAMERA_FRAME | |
LASER_FRAME |
Definition at line 63 of file range_image.h.
PCL_EXPORTS pcl::RangeImage::RangeImage | ( | ) |
Constructor.
Referenced by getNew().
| virtualdefault |
Destructor.
| inlinestaticprotected |
Query the asin lookup table.
Definition at line 53 of file range_image.hpp.
References asin_lookup_table, lookup_table_size, and pcl_lrintf.
Referenced by pcl::RangeImageSpherical::getImagePoint(), and getImagePoint().
| inlinestaticprotected |
Query the std::atan2 lookup table.
Definition at line 63 of file range_image.hpp.
References atan_lookup_table, lookup_table_size, M_PI, and pcl_lrintf.
Referenced by pcl::RangeImageSpherical::getImagePoint(), and getImagePoint().
| inline |
Calculate the 3D point according to the given image point and the range value at the closest pixel.
Definition at line 577 of file range_image.hpp.
References calculate3DPoint(), getPoint(), and pcl::_PointWithRange::range.
| inlinevirtual |
Calculate the 3D point according to the given image point and range.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 564 of file range_image.hpp.
References getAnglesFromImagePoint(), and to_world_system_.
| inline |
Calculate the 3D point according to the given image point and range.
Definition at line 585 of file range_image.hpp.
References pcl::_PointWithRange::range.
Referenced by calculate3DPoint(), and pcl::RangeImageBorderExtractor::get3dDirection().
| inline |
Calculate the 3D point according to the given image point and the range value at the closest pixel.
Definition at line 594 of file range_image.hpp.
References calculate3DPoint(), getPoint(), and pcl::_PointWithRange::range.
PCL_EXPORTS void pcl::RangeImage::change3dPointsToLocalCoordinateFrame | ( | ) |
This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame.
| 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 394 of file range_image.hpp.
References getImagePoint(), getPoint(), isInImage(), and unobserved_point.
| virtual |
Copy other to *this.
Necessary for use in virtual functions that need to copy derived RangeImage classes (like RangeImagePlanar)
Reimplemented in pcl::RangeImagePlanar.
| inlinestaticprotected |
Query the cos lookup table.
Definition at line 89 of file range_image.hpp.
References cos_lookup_table, lookup_table_size, M_PI, and pcl_lrintf.
Referenced by getImagePointFromAngles().
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)
[in] | angular_resolution | the angle (in radians) between each sample in the depth image |
[in] | sensor_pose | an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) |
[in] | coordinate_frame | the coordinate frame (defaults to CAMERA_FRAME) |
[in] | angle_width | an angle (in radians) defining the horizontal bounds of the sensor (defaults to 2*pi (360deg)) |
[in] | angle_height | an angle (in radians) defining the vertical bounds of the sensor (defaults to pi (180deg)) |
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)
angular_resolution_x | the angular difference (in radians) between the individual pixels in the image in the x-direction | |
angular_resolution_y | the angular difference (in radians) between the individual pixels in the image in the y-direction | |
[in] | sensor_pose | an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) |
[in] | coordinate_frame | the coordinate frame (defaults to CAMERA_FRAME) |
[in] | angle_width | an angle (in radians) defining the horizontal bounds of the sensor (defaults to 2*pi (360deg)) |
[in] | angle_height | an angle (in radians) defining the vertical bounds of the sensor (defaults to pi (180deg)) |
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.
point_cloud | the input point cloud |
angular_resolution | the angular difference (in radians) between the individual pixels in the image |
max_angle_width | an angle (in radians) defining the horizontal bounds of the sensor |
max_angle_height | an angle (in radians) defining the vertical bounds of the sensor |
sensor_pose | an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) |
coordinate_frame | the 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_range | the minimum visible range (defaults to 0) |
border_size | the border size (defaults to 0) |
Definition at line 97 of file range_image.hpp.
Referenced by createFromPointCloudWithKnownSize(), and createFromPointCloudWithViewpoints().
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.
point_cloud | the input point cloud |
angular_resolution_x | the angular difference (in radians) between the individual pixels in the image in the x-direction |
angular_resolution_y | the angular difference (in radians) between the individual pixels in the image in the y-direction |
max_angle_width | an angle (in radians) defining the horizontal bounds of the sensor |
max_angle_height | an angle (in radians) defining the vertical bounds of the sensor |
sensor_pose | an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) |
coordinate_frame | the 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_range | the minimum visible range (defaults to 0) |
border_size | the border size (defaults to 0) |
Definition at line 108 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.
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.
point_cloud | the input point cloud |
angular_resolution | the angle (in radians) between each sample in the depth image |
point_cloud_center | the center of bounding sphere |
point_cloud_radius | the radius of the bounding sphere |
sensor_pose | an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) |
coordinate_frame | the 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_range | the minimum visible range (defaults to 0) |
border_size | the border size (defaults to 0) |
Definition at line 145 of file range_image.hpp.
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.
point_cloud | the input point cloud |
angular_resolution_x | the angular difference (in radians) between the individual pixels in the image in the x-direction |
angular_resolution_y | the angular difference (in radians) between the individual pixels in the image in the y-direction |
point_cloud_center | the center of bounding sphere |
point_cloud_radius | the radius of the bounding sphere |
sensor_pose | an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) |
coordinate_frame | the 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_range | the minimum visible range (defaults to 0) |
border_size | the border size (defaults to 0) |
Definition at line 156 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.
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)).
point_cloud | the input point cloud |
angular_resolution | the angle (in radians) between each sample in the depth image |
max_angle_width | an angle (in radians) defining the horizontal bounds of the sensor |
max_angle_height | an angle (in radians) defining the vertical bounds of the sensor |
coordinate_frame | the 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_range | the minimum visible range (defaults to 0) |
border_size | the border size (defaults to 0) |
Definition at line 206 of file range_image.hpp.
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)).
point_cloud | the input point cloud |
angular_resolution_x | the angular difference (in radians) between the individual pixels in the image in the x-direction |
angular_resolution_y | the angular difference (in radians) between the individual pixels in the image in the y-direction |
max_angle_width | an angle (in radians) defining the horizontal bounds of the sensor |
max_angle_height | an angle (in radians) defining the vertical bounds of the sensor |
coordinate_frame | the 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_range | the minimum visible range (defaults to 0) |
border_size | the border size (defaults to 0) |
Definition at line 219 of file range_image.hpp.
References createFromPointCloud(), and getAverageViewPoint().
| staticprotected |
Create lookup tables for trigonometric functions.
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.
border_size | allows increase from the minimal size by the specified number of pixels (defaults to 0) |
top | if positive, this value overrides the position of the top edge (defaults to -1) |
right | if positive, this value overrides the position of the right edge (defaults to -1) |
bottom | if positive, this value overrides the position of the bottom edge (defaults to -1) |
left | if positive, this value overrides the position of the left edge (defaults to -1) |
Referenced by createFromPointCloud(), and createFromPointCloudWithKnownSize().
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.
point_cloud | the 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_range | the minimum visible range |
top | returns the minimum y pixel position in the image where a point was added |
right | returns the maximum x pixel position in the image where a point was added |
bottom | returns the maximum y pixel position in the image where a point was added |
left | returns the minimum x pixel position in the image where a point was added |
Definition at line 233 of file range_image.hpp.
References ERASE_ARRAY, 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().
| static |
Check if the provided data includes far ranges and add them to far_ranges.
point_cloud_data | a PCLPointCloud2 message containing the input cloud |
far_ranges | the resulting cloud containing those points with far ranges |
| 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 802 of file range_image.hpp.
References getPoint(), getPointNoCheck(), isValid(), pcl::_PointWithRange::range, and unobserved_point.
Referenced by pcl::RangeImageBorderExtractor::getNeighborDistanceChangeScore().
| 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 652 of file range_image.hpp.
References getImpactAngle(), and M_PI.
Referenced by getAcutenessValue().
| inline |
Same as above.
Definition at line 667 of file range_image.hpp.
References getAcutenessValue(), getPoint(), and isInImage().
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.
| inline |
Get the angles corresponding to the given image point.
Definition at line 602 of file range_image.hpp.
References angular_resolution_x_, angular_resolution_y_, image_offset_x_, image_offset_y_, and M_PI.
Referenced by calculate3DPoint().
| 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_.
| inline |
Getter for the angular resolution of the range image in x and y direction (in radians).
Definition at line 1214 of file range_image.hpp.
References angular_resolution_x_, and angular_resolution_y_.
| 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<<().
| 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<<().
| inline |
Doing the above for some steps in the given direction and averaging.
Definition at line 857 of file range_image.hpp.
References getEuclideanDistanceSquared().
| static |
Get the average viewpoint of a point cloud where each point carries viewpoint information as vp_x, vp_y, vp_z.
point_cloud | the input point cloud |
Definition at line 1126 of file range_image.hpp.
Referenced by createFromPointCloudWithViewpoints().
| virtual |
Get a blurred version of the range image using box filters.
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.
| static |
Get the transformation that transforms the given coordinate frame into CAMERA_FRAME.
coordinate_frame | the input coordinate frame |
transformation | the resulting transformation that warps coordinate_frame into CAMERA_FRAME |
Referenced by createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), and createFromPointCloudWithKnownSize().
| inline |
Calculates the curvature in a point using pca.
Definition at line 1101 of file range_image.hpp.
References pcl::VectorAverage< real, dimension >::add(), pcl::VectorAverage< real, dimension >::doPCA(), pcl::VectorAverage< real, dimension >::getNoOfSamples(), getPoint(), isInImage(), and pcl::_PointWithRange::range.
| inlinestatic |
Get Eigen::Vector3f from PointWithRange.
point | the input point |
Definition at line 795 of file range_image.hpp.
Referenced by getImpactAngleBasedOnLocalNormal().
| inline |
| inline |
| inline |
Get the squared euclidean distance between the two image points.
Returns -INFINITY if one of the points was not observed
Definition at line 842 of file range_image.hpp.
References getPoint(), isObserved(), pcl::_PointWithRange::range, and pcl::squaredEuclideanDistance().
Referenced by getAverageEuclideanDistance().
| virtual |
Get a range image with half the resolution.
Reimplemented in pcl::RangeImagePlanar.
| inline |
Getter for image_offset_x_.
Definition at line 630 of file range_image.h.
References image_offset_x_.
| inline |
Getter for image_offset_y_.
Definition at line 633 of file range_image.h.
References image_offset_y_.
| inline |
| inlinevirtual |
Get imagePoint from 3D point in world coordinates.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 355 of file range_image.hpp.
References asinLookUp(), atan2LookUp(), getImagePointFromAngles(), and to_range_image_system_.
Referenced by checkPoint(), createFromPointCloudWithKnownSize(), doZBuffer(), getImagePoint(), getRangeDifference(), and integrateFarRanges().
| inline |
Same as above.
Definition at line 385 of file range_image.hpp.
References getImagePoint(), and real2DToInt2D().
| inline |
Same as above.
Definition at line 369 of file range_image.hpp.
References getImagePoint(), and real2DToInt2D().
| inline |
| inline |
| inline |
Same as above.
Definition at line 346 of file range_image.hpp.
References getImagePoint(), and real2DToInt2D().
| inline |
Get the image point corresponding to the given angles.
Definition at line 427 of file range_image.hpp.
References angular_resolution_x_reciprocal_, angular_resolution_y_reciprocal_, cosLookUp(), image_offset_x_, image_offset_y_, and M_PI.
Referenced by getImagePoint().
| 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 620 of file range_image.hpp.
References M_PI, pcl::_PointWithRange::range, and pcl::squaredEuclideanDistance().
Referenced by getAcutenessValue(), and getImpactAngle().
| inline |
Same as above.
Definition at line 611 of file range_image.hpp.
References getImpactAngle(), getPoint(), and isInImage().
| inline |
Extract a local normal (with a heuristic not to include background points) and calculate the impact angle based on this.
Definition at line 884 of file range_image.hpp.
References pcl::deg2rad(), getEigenVector3f(), getNormalForClosestNeighbors(), getPoint(), getSensorPos(), and isValid().
Referenced by getNormalBasedAcutenessValue().
PCL_EXPORTS float* pcl::RangeImage::getImpactAngleImageBasedOnLocalNormals | ( | int | radius | ) | const |
Uses the above function for every point in the image.
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!
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!
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.
| inlinestatic |
Get the size of a certain area when seen from the given pose.
viewer_pose | an affine matrix defining the pose of the viewer |
center | the center of the area |
radius | the radius of the area |
Definition at line 788 of file range_image.hpp.
Referenced by createFromPointCloudWithKnownSize().
PCL_EXPORTS void pcl::RangeImage::getMinMaxRanges | ( | float & | min_range, |
float & | max_range | ||
) | const |
Find the minimum and maximum range in the image.
| 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().
| 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 899 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.
| 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 925 of file range_image.hpp.
References getImpactAngleBasedOnLocalNormal(), and M_PI.
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.
| inline |
Same as above, using default values.
Definition at line 945 of file range_image.hpp.
References getNormalForClosestNeighbors(), getPoint(), and isValid().
| inline |
| inline |
Same as above, but only the no_of_nearest_neighbors points closest to the given point are considered.
Definition at line 937 of file range_image.hpp.
Referenced by getImpactAngleBasedOnLocalNormal(), and getNormalForClosestNeighbors().
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)
| inline |
Non-const-version of the above.
Definition at line 526 of file range_image.hpp.
References getPoint(), and real2DToInt2D().
| inline |
Return the 3d point with range at the given image position.
Definition at line 517 of file range_image.hpp.
References getPoint(), and real2DToInt2D().
| inline |
Non-const-version of getPoint.
Definition at line 502 of file range_image.hpp.
References pcl::PointCloud< PointWithRange >::points, and pcl::PointCloud< PointWithRange >::width.
| inline |
Return the 3D point with range at the given image position.
image_x | the x coordinate |
image_y | the y coordinate |
Definition at line 479 of file range_image.hpp.
References isInImage(), pcl::PointCloud< PointWithRange >::points, unobserved_point, and pcl::PointCloud< PointWithRange >::width.
Referenced by calculate3DPoint(), checkPoint(), get1dPointAverage(), pcl::RangeImageBorderExtractor::get3dDirection(), getAcutenessValue(), getCurvature(), getEigenVector3f(), getEuclideanDistanceSquared(), getImpactAngle(), getImpactAngleBasedOnLocalNormal(), pcl::RangeImageBorderExtractor::getNeighborDistanceChangeScore(), getNormal(), getNormalForClosestNeighbors(), getPoint(), getRangeDifference(), getSquaredDistanceOfNthNeighbor(), getSurfaceAngleChange(), getSurfaceInformation(), getViewingDirection(), integrateFarRanges(), isMaxRange(), isObserved(), and isValid().
| inline |
| inline |
Return the 3d point with range at the given index (whereas index=y*width+x)
Definition at line 510 of file range_image.hpp.
References pcl::PointCloud< PointWithRange >::points.
| inline |
| inline |
Non-const-version of getPointNoCheck.
Definition at line 495 of file range_image.hpp.
References pcl::PointCloud< PointWithRange >::points, and pcl::PointCloud< PointWithRange >::width.
| inline |
Return the 3D point with range at the given image position.
This methd performs no error checking to make sure the specified image position is inside of the image!
image_x | the x coordinate |
image_y | the y coordinate |
Definition at line 488 of file range_image.hpp.
References pcl::PointCloud< PointWithRange >::points, and pcl::PointCloud< PointWithRange >::width.
Referenced by get1dPointAverage(), and getSquaredDistanceOfNthNeighbor().
| 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 408 of file range_image.hpp.
References getImagePoint(), getPoint(), isInImage(), and pcl::_PointWithRange::range.
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.
PCL_EXPORTS float* pcl::RangeImage::getRangesArray | ( | ) | const |
Get all the range values in one float array of size width*height.
| inline |
Same as above, but only returning the rotation.
Definition at line 1180 of file range_image.hpp.
References getSensorPos(), and pcl::getTransformationFromTwoUnitVectors().
| inline |
Get the sensor position.
Definition at line 676 of file range_image.hpp.
References to_world_system_.
Referenced by pcl::RangeImageBorderExtractor::get3dDirection(), getImpactAngleBasedOnLocalNormal(), getNormal(), getRotationToViewerCoordinateFrame(), getSurfaceInformation(), getTransformationToViewerCoordinateFrame(), and getViewingDirection().
| inline |
Definition at line 1052 of file range_image.hpp.
References getPoint(), getPointNoCheck(), isValid(), pcl::_PointWithRange::range, and pcl::squaredEuclideanDistance().
| virtual |
Get a sub part of the complete image as a new range image.
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.
| 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 683 of file range_image.hpp.
References getPoint(), getTransformationToViewerCoordinateFrame(), isMaxRange(), isObserved(), and isValid().
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.
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 suface 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 suface
PCL_EXPORTS float* pcl::RangeImage::getSurfaceChangeImage | ( | int | radius | ) | const |
Uses the above function for every point in the image.
| 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 965 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().
| 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_.
| inline |
Get the local coordinate frame with 0,0,0 in point, upright and Z as the viewing direction.
Definition at line 1163 of file range_image.hpp.
Referenced by getSurfaceAngleChange().
| inline |
Same as above, using a reference for the retrurn value.
Definition at line 1172 of file range_image.hpp.
References getSensorPos(), and pcl::getTransformationFromTwoUnitVectorsAndOrigin().
| 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_.
| inline |
Get the viewing direction for the given point.
Definition at line 1156 of file range_image.hpp.
References getSensorPos().
| inline |
Get the viewing direction for the given point.
Definition at line 1146 of file range_image.hpp.
References getPoint(), getSensorPos(), and isValid().
void pcl::RangeImage::integrateFarRanges | ( | const PointCloudType & | far_ranges | ) |
Integrates the given far range measurements into the range image.
Definition at line 1222 of file range_image.hpp.
References getImagePoint(), getPoint(), isInImage(), pcl_lrint, and pcl::_PointWithRange::range.
| inline |
Check if a point is inside of the image.
Definition at line 443 of file range_image.hpp.
References pcl::PointCloud< PointWithRange >::height, and pcl::PointCloud< PointWithRange >::width.
Referenced by pcl::RangeImageBorderExtractor::changeScoreAccordingToShadowBorderValue(), pcl::RangeImageBorderExtractor::checkIfMaximum(), checkPoint(), pcl::RangeImageBorderExtractor::checkPotentialBorder(), doZBuffer(), getAcutenessValue(), getCurvature(), getImpactAngle(), getNormal(), getPoint(), getRangeDifference(), integrateFarRanges(), isObserved(), isValid(), and pcl::RangeImageBorderExtractor::updatedScoreAccordingToNeighborValues().
| inline |
Check if a point is a max range (range=INFINITY) - please check isInImage or isObserved first!
Definition at line 471 of file range_image.hpp.
References getPoint(), and pcl::_PointWithRange::range.
Referenced by pcl::RangeImageBorderExtractor::changeScoreAccordingToShadowBorderValue(), and getSurfaceAngleChange().
| 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 464 of file range_image.hpp.
References getPoint(), isInImage(), and pcl::_PointWithRange::range.
Referenced by getEuclideanDistanceSquared(), and getSurfaceAngleChange().
| inline |
Check if a point has a finite range.
Definition at line 457 of file range_image.hpp.
References getPoint().
| inline |
Check if a point is inside of the image and has a finite range.
Definition at line 450 of file range_image.hpp.
References getPoint(), and isInImage().
Referenced by pcl::RangeImageBorderExtractor::calculateMainPrincipalCurvature(), get1dPointAverage(), getImpactAngleBasedOnLocalNormal(), getNormalForClosestNeighbors(), getSquaredDistanceOfNthNeighbor(), getSurfaceAngleChange(), getSurfaceInformation(), and getViewingDirection().
| inline |
Get a boost shared pointer of a copy of this.
Definition at line 124 of file range_image.h.
| inline |
Transforms an image point in float values to an image point in int values.
Definition at line 435 of file range_image.hpp.
References pcl_lrintf.
Referenced by doZBuffer(), getImagePoint(), and getPoint().
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().
PCL_EXPORTS void pcl::RangeImage::reset | ( | ) |
Reset all values to an empty range image.
| inline |
Set the angular resolution of the range image.
angular_resolution | the new angular resolution in x and y direction (in radians per pixel) |
Definition at line 1188 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().
| inline |
Set the angular resolution of the range image.
angular_resolution_x | the new angular resolution in x direction (in radians per pixel) |
angular_resolution_y | the new angular resolution in y direction (in radians per pixel) |
Definition at line 1196 of file range_image.hpp.
References angular_resolution_x_, angular_resolution_x_reciprocal_, angular_resolution_y_, and angular_resolution_y_reciprocal_.
| inline |
Setter for image offsets.
Definition at line 637 of file range_image.h.
References image_offset_x_, and image_offset_y_.
| inline |
Setter for the transformation from the range image system (the sensor coordinate frame) into the world system.
Definition at line 1206 of file range_image.hpp.
References to_range_image_system_, and to_world_system_.
PCL_EXPORTS void pcl::RangeImage::setUnseenToMaxRange | ( | ) |
Sets all -INFINITY values to INFINITY.
| 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 pcl::RangeImageSpherical::getAnglesFromImagePoint(), getAnglesFromImagePoint(), getAngularResolution(), getAngularResolutionX(), and setAngularResolution().
| 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 createFromPointCloud(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getImagePointFromAngles(), getImagePointFromAngles(), and setAngularResolution().
| 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 pcl::RangeImageSpherical::getAnglesFromImagePoint(), getAnglesFromImagePoint(), getAngularResolution(), getAngularResolutionY(), and setAngularResolution().
| 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 createFromPointCloud(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getImagePointFromAngles(), getImagePointFromAngles(), and setAngularResolution().
| staticprotected |
Definition at line 786 of file range_image.h.
Referenced by asinLookUp().
| staticprotected |
Definition at line 787 of file range_image.h.
Referenced by atan2LookUp().
| staticprotected |
Definition at line 788 of file range_image.h.
Referenced by cosLookUp().
| static |
| protected |
Definition at line 776 of file range_image.h.
Referenced by pcl::RangeImagePlanar::calculate3DPoint(), createFromPointCloud(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getAnglesFromImagePoint(), getAnglesFromImagePoint(), getImageOffsetX(), pcl::RangeImagePlanar::getImagePoint(), pcl::RangeImageSpherical::getImagePointFromAngles(), getImagePointFromAngles(), and setImageOffsets().
| protected |
Position of the top left corner of the range image compared to an image of full size (360x180 degrees)
Definition at line 776 of file range_image.h.
Referenced by pcl::RangeImagePlanar::calculate3DPoint(), createFromPointCloud(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getAnglesFromImagePoint(), getAnglesFromImagePoint(), getImageOffsetY(), pcl::RangeImagePlanar::getImagePoint(), pcl::RangeImageSpherical::getImagePointFromAngles(), getImagePointFromAngles(), and setImageOffsets().
| staticprotected |
Definition at line 785 of file range_image.h.
Referenced by asinLookUp(), atan2LookUp(), and cosLookUp().
| static |
The maximum number of openmp threads that can be used in this class.
Definition at line 78 of file range_image.h.
| protected |
Inverse of to_world_system_.
Definition at line 768 of file range_image.h.
Referenced by createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), createFromPointCloudWithKnownSize(), pcl::RangeImageSpherical::getImagePoint(), pcl::RangeImagePlanar::getImagePoint(), getImagePoint(), getTransformationToRangeImageSystem(), and setTransformationToRangeImageSystem().
| protected |
Inverse of to_range_image_system_.
Definition at line 769 of file range_image.h.
Referenced by pcl::RangeImageSpherical::calculate3DPoint(), pcl::RangeImagePlanar::calculate3DPoint(), calculate3DPoint(), createFromPointCloud(), pcl::RangeImagePlanar::createFromPointCloudWithFixedSize(), createFromPointCloudWithKnownSize(), getSensorPos(), getTransformationToWorldSystem(), and setTransformationToRangeImageSystem().
| 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().
© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_range_image.html