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 <range_image.h>
Public Types | |
typedef pcl::PointCloud < PointWithRange > | BaseClass |
typedef boost::shared_ptr < const RangeImage > | ConstPtr |
enum | CoordinateFrame { CAMERA_FRAME = 0, LASER_FRAME = 1 } |
typedef boost::shared_ptr < RangeImage > | Ptr |
typedef std::vector < Eigen::Vector3f, Eigen::aligned_allocator < Eigen::Vector3f > > | VectorOfEigenVector3f |
Public Member Functions | |
void | calculate3DPoint (float image_x, float image_y, float range, PointWithRange &point) const |
void | calculate3DPoint (float image_x, float image_y, PointWithRange &point) const |
virtual void | calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f &point) const |
void | calculate3DPoint (float image_x, float image_y, Eigen::Vector3f &point) const |
PCL_EXPORTS void | change3dPointsToLocalCoordinateFrame () |
This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame. | |
float | checkPoint (const Eigen::Vector3f &point, PointWithRange &point_in_image) const |
virtual PCL_EXPORTS void | copyTo (RangeImage &other) const |
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) | |
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) | |
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. | |
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. | |
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. | |
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. | |
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)). | |
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)). | |
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. | |
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. | |
void | get1dPointAverage (int x, int y, int delta_x, int delta_y, int no_of_points, PointWithRange &average_point) const |
float | getAcutenessValue (const PointWithRange &point1, const PointWithRange &point2) const |
float | getAcutenessValue (int x1, int y1, int x2, int y2) const |
Same as above. | |
PCL_EXPORTS void | getAcutenessValueImages (int pixel_distance, float *´ness_value_image_x, float *´ness_value_image_y) const |
void | getAnglesFromImagePoint (float image_x, float image_y, float &angle_x, float &angle_y) const |
float | getAngularResolution () const |
void | getAngularResolution (float &angular_resolution_x, float &angular_resolution_y) const |
float | getAngularResolutionX () const |
float | getAngularResolutionY () const |
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. | |
virtual PCL_EXPORTS void | getBlurredImage (int blur_radius, RangeImage &range_image) const |
PCL_EXPORTS void | getBlurredImageUsingIntegralImage (int blur_radius, float *integral_image, int *valid_points_num_image, RangeImage &range_image) const |
float | getCurvature (int x, int y, int radius, int step_size) const |
const Eigen::Map< const Eigen::Vector3f > | getEigenVector3f (int x, int y) const |
const Eigen::Map< const Eigen::Vector3f > | getEigenVector3f (int index) const |
float | getEuclideanDistanceSquared (int x1, int y1, int x2, int y2) const |
virtual void | getHalfImage (RangeImage &half_image) const |
Get a range image with half the resolution. | |
int | getImageOffsetX () const |
Getter for image_offset_x_. | |
int | getImageOffsetY () const |
Getter for image_offset_y_. | |
virtual void | getImagePoint (const Eigen::Vector3f &point, float &image_x, float &image_y, float &range) const |
void | getImagePoint (const Eigen::Vector3f &point, int &image_x, int &image_y, float &range) const |
void | getImagePoint (const Eigen::Vector3f &point, float &image_x, float &image_y) const |
void | getImagePoint (const Eigen::Vector3f &point, int &image_x, int &image_y) const |
void | getImagePoint (float x, float y, float z, float &image_x, float &image_y, float &range) const |
void | getImagePoint (float x, float y, float z, float &image_x, float &image_y) const |
void | getImagePoint (float x, float y, float z, int &image_x, int &image_y) const |
void | getImagePointFromAngles (float angle_x, float angle_y, float &image_x, float &image_y) const |
float | getImpactAngle (const PointWithRange &point1, const PointWithRange &point2) const |
float | getImpactAngle (int x1, int y1, int x2, int y2) const |
Same as above. | |
float | getImpactAngleBasedOnLocalNormal (int x, int y, int radius) const |
PCL_EXPORTS float * | getImpactAngleImageBasedOnLocalNormals (int radius) const |
PCL_EXPORTS void | getIntegralImage (float *&integral_image, int *&valid_points_num_image) const |
PCL_EXPORTS float * | getInterpolatedSurfaceProjection (const Eigen::Affine3f &pose, int pixel_size, float world_size) const |
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. | |
PCL_EXPORTS void | getMinMaxRanges (float &min_range, float &max_range) const |
Find the minimum and maximum range in the image. | |
virtual PCL_EXPORTS RangeImage * | getNew () const |
bool | getNormal (int x, int y, int radius, Eigen::Vector3f &normal, int step_size=1) const |
float | getNormalBasedAcutenessValue (int x, int y, int radius) const |
PCL_EXPORTS bool | getNormalBasedUprightTransformation (const Eigen::Vector3f &point, float max_dist, Eigen::Affine3f &transformation) const |
bool | getNormalForClosestNeighbors (int x, int y, int radius, const PointWithRange &point, int no_of_nearest_neighbors, Eigen::Vector3f &normal, int step_size=1) const |
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=NULL, int step_size=1) const |
bool | getNormalForClosestNeighbors (int x, int y, Eigen::Vector3f &normal, int radius=2) const |
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 |
const PointWithRange & | getPoint (int image_x, int image_y) const |
Return the 3D point with range at the given image position. | |
PointWithRange & | getPoint (int image_x, int image_y) |
Non-const-version of getPoint. | |
const PointWithRange & | getPoint (float image_x, float image_y) const |
PointWithRange & | getPoint (float image_x, float image_y) |
void | getPoint (int image_x, int image_y, Eigen::Vector3f &point) const |
void | getPoint (int index, Eigen::Vector3f &point) const |
const PointWithRange & | getPoint (int index) const |
const PointWithRange & | getPointNoCheck (int image_x, int image_y) const |
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! | |
PointWithRange & | getPointNoCheck (int image_x, int image_y) |
float | getRangeDifference (const Eigen::Vector3f &point) const |
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. | |
PCL_EXPORTS float * | getRangesArray () const |
Get all the range values in one float array of size width*height. | |
void | getRotationToViewerCoordinateFrame (const Eigen::Vector3f &point, Eigen::Affine3f &transformation) const |
Same as above, but only returning the rotation. | |
const Eigen::Vector3f | getSensorPos () const |
Get the sensor position. | |
float | getSquaredDistanceOfNthNeighbor (int x, int y, int radius, int n, int step_size) const |
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 |
void | getSurfaceAngleChange (int x, int y, int radius, float &angle_change_x, float &angle_change_y) const |
PCL_EXPORTS void | getSurfaceAngleChangeImages (int radius, float *&angle_change_image_x, float *&angle_change_image_y) const |
PCL_EXPORTS float | getSurfaceChange (int x, int y, int radius) const |
PCL_EXPORTS float * | getSurfaceChangeImage (int radius) const |
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=NULL, Eigen::Vector3f *mean_all_neighbors=NULL, Eigen::Vector3f *eigen_values_all_neighbors=NULL) const |
const Eigen::Affine3f & | getTransformationToRangeImageSystem () const |
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. | |
void | getTransformationToViewerCoordinateFrame (const Eigen::Vector3f &point, Eigen::Affine3f &transformation) const |
Same as above, using a reference for the retrurn value. | |
const Eigen::Affine3f & | getTransformationToWorldSystem () const |
bool | getViewingDirection (int x, int y, Eigen::Vector3f &viewing_direction) const |
void | getViewingDirection (const Eigen::Vector3f &point, Eigen::Vector3f &viewing_direction) const |
template<typename PointCloudType > | |
void | integrateFarRanges (const PointCloudType &far_ranges) |
Integrates the given far range measurements into the range image. | |
bool | isInImage (int x, int y) const |
bool | isMaxRange (int x, int y) const |
bool | isObserved (int x, int y) const |
bool | isValid (int x, int y) const |
bool | isValid (int index) const |
Ptr | makeShared () |
Get a boost shared pointer of a copy of this. | |
PCL_EXPORTS | RangeImage () |
void | real2DToInt2D (float x, float y, int &xInt, int &yInt) const |
PCL_EXPORTS void | recalculate3DPointPositions () |
PCL_EXPORTS void | reset () |
Reset all values to an empty range image. | |
void | setAngularResolution (float angular_resolution) |
Set the angular resolution of the range image. | |
void | setAngularResolution (float angular_resolution_x, float angular_resolution_y) |
Set the angular resolution of the range image. | |
void | setImageOffsets (int offset_x, int offset_y) |
Setter for image offsets. | |
void | setTransformationToRangeImageSystem (const Eigen::Affine3f &to_range_image_system) |
PCL_EXPORTS void | setUnseenToMaxRange () |
virtual PCL_EXPORTS | ~RangeImage () |
Static Public Member Functions | |
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. | |
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. | |
static PCL_EXPORTS void | getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordinate_frame, Eigen::Affine3f &transformation) |
Get the transformation that transforms the given coordinate frame into CAMERA_FRAME. | |
static Eigen::Vector3f | getEigenVector3f (const PointWithRange &point) |
Get Eigen::Vector3f from PointWithRange. | |
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. | |
Static Public Attributes | |
static bool | debug = false |
static int | max_no_of_threads = 1 |
Static Protected Member Functions | |
static float | asinLookUp (float value) |
static float | atan2LookUp (float y, float x) |
static float | cosLookUp (float value) |
static void | createLookupTables () |
Protected Attributes | |
float | angular_resolution_x_ |
float | angular_resolution_x_reciprocal_ |
float | angular_resolution_y_ |
float | angular_resolution_y_reciprocal_ |
int | image_offset_x_ |
int | image_offset_y_ |
Eigen::Affine3f | to_range_image_system_ |
Eigen::Affine3f | to_world_system_ |
PointWithRange | unobserved_point |
Static Protected Attributes | |
static std::vector< float > | asin_lookup_table |
static std::vector< float > | atan_lookup_table |
static std::vector< float > | cos_lookup_table |
static const int | lookup_table_size = 20001 |
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 55 of file range_image.h.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 59 of file range_image.h.
typedef boost::shared_ptr<const RangeImage> pcl::RangeImage::ConstPtr |
Reimplemented from pcl::PointCloud< PointWithRange >.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 62 of file range_image.h.
typedef boost::shared_ptr<RangeImage> pcl::RangeImage::Ptr |
Reimplemented from pcl::PointCloud< PointWithRange >.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 61 of file range_image.h.
typedef std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > pcl::RangeImage::VectorOfEigenVector3f |
Definition at line 60 of file range_image.h.
Definition at line 64 of file range_image.h.
Constructor
Definition at line 107 of file range_image.cpp.
pcl::RangeImage::~RangeImage | ( | ) | [virtual] |
Destructor
Definition at line 123 of file range_image.cpp.
float pcl::RangeImage::asinLookUp | ( | float | value | ) | [inline, static, protected] |
Query the asin lookup table
Definition at line 50 of file range_image.hpp.
float pcl::RangeImage::atan2LookUp | ( | float | y, |
float | x | ||
) | [inline, static, protected] |
Query the atan2 lookup table
Definition at line 60 of file range_image.hpp.
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 585 of file range_image.hpp.
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 594 of file range_image.hpp.
void pcl::RangeImage::calculate3DPoint | ( | float | image_x, |
float | image_y, | ||
float | range, | ||
Eigen::Vector3f & | point | ||
) | const [inline, virtual] |
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.
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 577 of file range_image.hpp.
This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame.
Definition at line 458 of file range_image.cpp.
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 391 of file range_image.hpp.
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.
Definition at line 1017 of file range_image.cpp.
float pcl::RangeImage::cosLookUp | ( | float | value | ) | [inline, static, protected] |
Query the cos lookup table
Definition at line 86 of file range_image.hpp.
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)) |
Definition at line 142 of file range_image.cpp.
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)) |
Definition at line 150 of file range_image.cpp.
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 94 of file range_image.hpp.
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 105 of file range_image.hpp.
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 142 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 |
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 153 of file range_image.hpp.
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 203 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 216 of file range_image.hpp.
void pcl::RangeImage::createLookupTables | ( | ) | [static, protected] |
Create lookup tables for trigonometric functions
Definition at line 57 of file range_image.cpp.
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) |
Definition at line 172 of file range_image.cpp.
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 |
top | returns the minimum y 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 230 of file range_image.hpp.
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.
point_cloud_data | a PCLPointCloud2 message containing the input cloud |
far_ranges | the resulting cloud containing those points with far ranges |
Definition at line 815 of file range_image.cpp.
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 802 of file range_image.hpp.
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 652 of file range_image.hpp.
float pcl::RangeImage::getAcutenessValue | ( | int | x1, |
int | y1, | ||
int | x2, | ||
int | y2 | ||
) | const [inline] |
Same as above.
Definition at line 667 of file range_image.hpp.
void pcl::RangeImage::getAcutenessValueImages | ( | int | pixel_distance, |
float *& | acuteness_value_image_x, | ||
float *& | acuteness_value_image_y | ||
) | const |
Calculate getAcutenessValue for every point
Definition at line 743 of file range_image.cpp.
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
Reimplemented in pcl::RangeImageSpherical.
Definition at line 602 of file range_image.hpp.
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 compatability
Definition at line 355 of file range_image.h.
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 1214 of file range_image.hpp.
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 359 of file range_image.h.
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 363 of file range_image.h.
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 857 of file range_image.hpp.
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.
point_cloud | the input point cloud |
Definition at line 1125 of file range_image.hpp.
void pcl::RangeImage::getBlurredImage | ( | int | blur_radius, |
RangeImage & | range_image | ||
) | const [virtual] |
Get a blurred version of the range image using box filters
Definition at line 968 of file range_image.cpp.
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
Definition at line 922 of file range_image.cpp.
void pcl::RangeImage::getCoordinateFrameTransformation | ( | RangeImage::CoordinateFrame | coordinate_frame, |
Eigen::Affine3f & | transformation | ||
) | [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 |
Definition at line 88 of file range_image.cpp.
float pcl::RangeImage::getCurvature | ( | int | x, |
int | y, | ||
int | radius, | ||
int | step_size | ||
) | const [inline] |
Calculates the curvature in a point using pca
Definition at line 1100 of file range_image.hpp.
Eigen::Vector3f pcl::RangeImage::getEigenVector3f | ( | const PointWithRange & | point | ) | [inline, static] |
Get Eigen::Vector3f from PointWithRange.
point | the input point |
Definition at line 795 of file range_image.hpp.
const Eigen::Map< const Eigen::Vector3f > pcl::RangeImage::getEigenVector3f | ( | int | x, |
int | y | ||
) | const [inline] |
Same as above
Definition at line 550 of file range_image.hpp.
const Eigen::Map< const Eigen::Vector3f > pcl::RangeImage::getEigenVector3f | ( | int | index | ) | const [inline] |
Same as above
Definition at line 557 of file range_image.hpp.
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 842 of file range_image.hpp.
void pcl::RangeImage::getHalfImage | ( | RangeImage & | half_image | ) | const [virtual] |
Get a range image with half the resolution.
Reimplemented in pcl::RangeImagePlanar.
Definition at line 355 of file range_image.cpp.
int pcl::RangeImage::getImageOffsetX | ( | ) | const [inline] |
Getter for image_offset_x_.
Definition at line 633 of file range_image.h.
int pcl::RangeImage::getImageOffsetY | ( | ) | const [inline] |
Getter for image_offset_y_.
Definition at line 636 of file range_image.h.
void pcl::RangeImage::getImagePoint | ( | const Eigen::Vector3f & | point, |
float & | image_x, | ||
float & | image_y, | ||
float & | range | ||
) | const [inline, virtual] |
Get imagePoint from 3D point in world coordinates
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 352 of file range_image.hpp.
void pcl::RangeImage::getImagePoint | ( | const Eigen::Vector3f & | point, |
int & | image_x, | ||
int & | image_y, | ||
float & | range | ||
) | const [inline] |
Same as above
Definition at line 366 of file range_image.hpp.
void pcl::RangeImage::getImagePoint | ( | const Eigen::Vector3f & | point, |
float & | image_x, | ||
float & | image_y | ||
) | const [inline] |
Same as above
Definition at line 374 of file range_image.hpp.
void pcl::RangeImage::getImagePoint | ( | const Eigen::Vector3f & | point, |
int & | image_x, | ||
int & | image_y | ||
) | const [inline] |
Same as above
Definition at line 382 of file range_image.hpp.
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 327 of file range_image.hpp.
void pcl::RangeImage::getImagePoint | ( | float | x, |
float | y, | ||
float | z, | ||
float & | image_x, | ||
float & | image_y | ||
) | const [inline] |
Same as above
Definition at line 335 of file range_image.hpp.
void pcl::RangeImage::getImagePoint | ( | float | x, |
float | y, | ||
float | z, | ||
int & | image_x, | ||
int & | image_y | ||
) | const [inline] |
Same as above
Definition at line 343 of file range_image.hpp.
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
Reimplemented in pcl::RangeImageSpherical.
Definition at line 425 of file range_image.hpp.
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 620 of file range_image.hpp.
float pcl::RangeImage::getImpactAngle | ( | int | x1, |
int | y1, | ||
int | x2, | ||
int | y2 | ||
) | const [inline] |
Same as above.
Definition at line 611 of file range_image.hpp.
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 885 of file range_image.hpp.
float * pcl::RangeImage::getImpactAngleImageBasedOnLocalNormals | ( | int | radius | ) | const |
Uses the above function for every point in the image
Definition at line 763 of file range_image.cpp.
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!
Definition at line 301 of file range_image.cpp.
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!
Definition at line 467 of file range_image.cpp.
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.
Definition at line 659 of file range_image.cpp.
float pcl::RangeImage::getMaxAngleSize | ( | const Eigen::Affine3f & | viewer_pose, |
const Eigen::Vector3f & | center, | ||
float | radius | ||
) | [inline, static] |
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.
void pcl::RangeImage::getMinMaxRanges | ( | float & | min_range, |
float & | max_range | ||
) | const |
Find the minimum and maximum range in the image.
Definition at line 442 of file range_image.cpp.
virtual PCL_EXPORTS RangeImage* pcl::RangeImage::getNew | ( | ) | const [inline, virtual] |
Return a newly created Range image. Can be reimplmented in derived classes like RangeImagePlanar to return an image of the same type.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 752 of file range_image.h.
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 900 of file range_image.hpp.
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 926 of file range_image.hpp.
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.
Definition at line 668 of file range_image.cpp.
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 938 of file range_image.hpp.
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 = NULL , |
||
int | step_size = 1 |
||
) | const [inline] |
Same as above
Definition at line 1081 of file range_image.hpp.
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 946 of file range_image.hpp.
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)
Definition at line 871 of file range_image.cpp.
const PointWithRange & pcl::RangeImage::getPoint | ( | int | image_x, |
int | image_y | ||
) | const [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.
PointWithRange & pcl::RangeImage::getPoint | ( | int | image_x, |
int | image_y | ||
) | [inline] |
Non-const-version of getPoint.
Definition at line 502 of file range_image.hpp.
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 517 of file range_image.hpp.
PointWithRange & pcl::RangeImage::getPoint | ( | float | image_x, |
float | image_y | ||
) | [inline] |
Non-const-version of the above
Definition at line 526 of file range_image.hpp.
void pcl::RangeImage::getPoint | ( | int | image_x, |
int | image_y, | ||
Eigen::Vector3f & | point | ||
) | const [inline] |
Same as above
Definition at line 535 of file range_image.hpp.
void pcl::RangeImage::getPoint | ( | int | index, |
Eigen::Vector3f & | point | ||
) | const [inline] |
Same as above
Definition at line 543 of file range_image.hpp.
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 510 of file range_image.hpp.
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 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.
PointWithRange & pcl::RangeImage::getPointNoCheck | ( | int | image_x, |
int | image_y | ||
) | [inline] |
Non-const-version of getPointNoCheck
Definition at line 495 of file range_image.hpp.
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 405 of file range_image.hpp.
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.
Definition at line 780 of file range_image.cpp.
float * pcl::RangeImage::getRangesArray | ( | ) | const |
Get all the range values in one float array of size width*height.
Definition at line 289 of file range_image.cpp.
void pcl::RangeImage::getRotationToViewerCoordinateFrame | ( | const Eigen::Vector3f & | point, |
Eigen::Affine3f & | transformation | ||
) | const [inline] |
Same as above, but only returning the rotation.
Definition at line 1180 of file range_image.hpp.
const Eigen::Vector3f pcl::RangeImage::getSensorPos | ( | ) | const [inline] |
Get the sensor position.
Definition at line 676 of file range_image.hpp.
float pcl::RangeImage::getSquaredDistanceOfNthNeighbor | ( | int | x, |
int | y, | ||
int | radius, | ||
int | n, | ||
int | step_size | ||
) | const [inline] |
Definition at line 1052 of file range_image.hpp.
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.
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.
Definition at line 397 of file range_image.cpp.
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 683 of file range_image.hpp.
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
Definition at line 725 of file range_image.cpp.
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
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 = NULL , |
||
Eigen::Vector3f * | mean_all_neighbors = NULL , |
||
Eigen::Vector3f * | eigen_values_all_neighbors = NULL |
||
) | 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 966 of file range_image.hpp.
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 340 of file range_image.h.
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 1163 of file range_image.hpp.
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 1172 of file range_image.hpp.
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 350 of file range_image.h.
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 1146 of file range_image.hpp.
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 1156 of file range_image.hpp.
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.
bool pcl::RangeImage::isInImage | ( | int | x, |
int | y | ||
) | const [inline] |
Check if a point is inside of the image
Definition at line 441 of file range_image.hpp.
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 471 of file range_image.hpp.
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 462 of file range_image.hpp.
bool pcl::RangeImage::isValid | ( | int | x, |
int | y | ||
) | const [inline] |
Check if a point is inside of the image and has a finite range
Definition at line 448 of file range_image.hpp.
bool pcl::RangeImage::isValid | ( | int | index | ) | const [inline] |
Check if a point has a finite range
Definition at line 455 of file range_image.hpp.
Ptr pcl::RangeImage::makeShared | ( | ) | [inline] |
Get a boost shared pointer of a copy of this.
Reimplemented in pcl::RangeImagePlanar, and pcl::RangeImageSpherical.
Definition at line 125 of file range_image.h.
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 433 of file range_image.hpp.
Recalculate all 3D point positions according to their pixel position and range
Definition at line 274 of file range_image.cpp.
void pcl::RangeImage::reset | ( | ) |
Reset all values to an empty range image.
Definition at line 129 of file range_image.cpp.
void pcl::RangeImage::setAngularResolution | ( | float | angular_resolution | ) | [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.
void pcl::RangeImage::setAngularResolution | ( | float | angular_resolution_x, |
float | angular_resolution_y | ||
) | [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.
void pcl::RangeImage::setImageOffsets | ( | int | offset_x, |
int | offset_y | ||
) | [inline] |
Setter for image offsets.
Definition at line 640 of file range_image.h.
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 1206 of file range_image.hpp.
void pcl::RangeImage::setUnseenToMaxRange | ( | ) |
Sets all -INFINITY values to INFINITY
Definition at line 346 of file range_image.cpp.
float pcl::RangeImage::angular_resolution_x_ [protected] |
Angular resolution of the range image in x direction in radians per pixel
Definition at line 773 of file range_image.h.
float pcl::RangeImage::angular_resolution_x_reciprocal_ [protected] |
1.0/angular_resolution_x_ - provided for better performace of multiplication compared to division
Definition at line 775 of file range_image.h.
float pcl::RangeImage::angular_resolution_y_ [protected] |
Angular resolution of the range image in y direction in radians per pixel
Definition at line 774 of file range_image.h.
float pcl::RangeImage::angular_resolution_y_reciprocal_ [protected] |
1.0/angular_resolution_y_ - provided for better performace of multiplication compared to division
Definition at line 777 of file range_image.h.
std::vector< float > pcl::RangeImage::asin_lookup_table [static, protected] |
Definition at line 789 of file range_image.h.
std::vector< float > pcl::RangeImage::atan_lookup_table [static, protected] |
Definition at line 790 of file range_image.h.
std::vector< float > pcl::RangeImage::cos_lookup_table [static, protected] |
Definition at line 791 of file range_image.h.
bool pcl::RangeImage::debug = false [static] |
Just for... well... debugging purposes. :-)
Definition at line 767 of file range_image.h.
int pcl::RangeImage::image_offset_x_ [protected] |
Definition at line 779 of file range_image.h.
int pcl::RangeImage::image_offset_y_ [protected] |
Position of the top left corner of the range image compared to an image of full size (360x180 degrees)
Definition at line 779 of file range_image.h.
const int pcl::RangeImage::lookup_table_size = 20001 [static, protected] |
Definition at line 788 of file range_image.h.
int pcl::RangeImage::max_no_of_threads = 1 [static] |
The maximum number of openmp threads that can be used in this class
Definition at line 79 of file range_image.h.
Eigen::Affine3f pcl::RangeImage::to_range_image_system_ [protected] |
Inverse of to_world_system_
Definition at line 771 of file range_image.h.
Eigen::Affine3f pcl::RangeImage::to_world_system_ [protected] |
Inverse of to_range_image_system_
Definition at line 772 of file range_image.h.
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 781 of file range_image.h.