RangeImagePlanar is derived from the original range image and differs from it because it's not a spherical projection, but using a projection plane (as normal cameras do), therefore being better applicable for range sensors that already provide a range image by themselves (stereo cameras, ToF-cameras), so that a conversion to point cloud and then to a spherical range image becomes unnecessary. More...
#include <range_image_planar.h>
Public Types | |
typedef RangeImage | BaseClass |
typedef boost::shared_ptr < const RangeImagePlanar > | ConstPtr |
typedef boost::shared_ptr < RangeImagePlanar > | Ptr |
Public Member Functions | |
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. | |
virtual PCL_EXPORTS void | copyTo (RangeImage &other) const |
template<typename PointCloudType > | |
void | createFromPointCloudWithFixedSize (const PointCloudType &point_cloud, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, const Eigen::Affine3f &sensor_pose, CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f) |
float | getCenterX () const |
Getter for the principal point in X. | |
float | getCenterY () const |
Getter for the principal point in Y. | |
float | getFocalLengthX () const |
Getter for the focal length in X. | |
float | getFocalLengthY () const |
Getter for the focal length in Y. | |
virtual PCL_EXPORTS void | getHalfImage (RangeImage &half_image) const |
Get a range image with half the resolution. | |
virtual void | getImagePoint (const Eigen::Vector3f &point, float &image_x, float &image_y, float &range) const |
Calculate the image point and range from the given 3D point. | |
virtual RangeImage * | getNew () const |
virtual PCL_EXPORTS 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 |
Ptr | makeShared () |
Get a boost shared pointer of a copy of this. | |
PCL_EXPORTS | RangeImagePlanar () |
PCL_EXPORTS void | setDepthImage (const float *depth_image, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1) |
PCL_EXPORTS void | setDepthImage (const unsigned short *depth_image, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1) |
PCL_EXPORTS void | setDisparityImage (const float *disparity_image, int di_width, int di_height, float focal_length, float base_line, float desired_angular_resolution=-1) |
Create the image from an existing disparity image. | |
virtual PCL_EXPORTS | ~RangeImagePlanar () |
Protected Attributes | |
float | center_x_ |
float | center_y_ |
The principle point of the image. | |
float | focal_length_x_ |
float | focal_length_x_reciprocal_ |
float | focal_length_y_ |
The focal length of the image in pixels. | |
float | focal_length_y_reciprocal_ |
1/focal_length -> for internal use |
RangeImagePlanar is derived from the original range image and differs from it because it's not a spherical projection, but using a projection plane (as normal cameras do), therefore being better applicable for range sensors that already provide a range image by themselves (stereo cameras, ToF-cameras), so that a conversion to point cloud and then to a spherical range image becomes unnecessary.
Definition at line 52 of file range_image_planar.h.
Reimplemented from pcl::RangeImage.
Definition at line 56 of file range_image_planar.h.
typedef boost::shared_ptr<const RangeImagePlanar> pcl::RangeImagePlanar::ConstPtr |
Reimplemented from pcl::RangeImage.
Definition at line 58 of file range_image_planar.h.
typedef boost::shared_ptr<RangeImagePlanar> pcl::RangeImagePlanar::Ptr |
Reimplemented from pcl::RangeImage.
Definition at line 57 of file range_image_planar.h.
Constructor
Definition at line 46 of file range_image_planar.cpp.
pcl::RangeImagePlanar::~RangeImagePlanar | ( | ) | [virtual] |
Destructor
Definition at line 53 of file range_image_planar.cpp.
void pcl::RangeImagePlanar::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.
image_x | the x image position |
image_y | the y image position |
range | the range |
point | the resulting 3D point |
Reimplemented from pcl::RangeImage.
Definition at line 92 of file range_image_planar.hpp.
void pcl::RangeImagePlanar::copyTo | ( | RangeImage & | other | ) | const [virtual] |
Copy *this to other. Derived version - also copying additonal RangeImagePlanar members
Reimplemented from pcl::RangeImage.
Definition at line 253 of file range_image_planar.cpp.
void pcl::RangeImagePlanar::createFromPointCloudWithFixedSize | ( | const PointCloudType & | point_cloud, |
int | di_width, | ||
int | di_height, | ||
float | di_center_x, | ||
float | di_center_y, | ||
float | di_focal_length_x, | ||
float | di_focal_length_y, | ||
const Eigen::Affine3f & | sensor_pose, | ||
CoordinateFrame | coordinate_frame = CAMERA_FRAME , |
||
float | noise_level = 0.0f , |
||
float | min_range = 0.0f |
||
) |
Create the image from an existing point cloud.
point_cloud | the source point cloud |
di_width | the disparity image width |
di_height | the disparity image height |
di_center_x | the x-coordinate of the camera's center of projection |
di_center_y | the y-coordinate of the camera's center of projection |
di_focal_length_x | the camera's focal length in the horizontal direction |
di_focal_length_y | the camera's focal length in the vertical direction |
sensor_pose | the pose of the virtual depth camera |
coordinate_frame | the used coordinate frame of the point cloud |
noise_level | what is the typical noise of the sensor - is used for averaging in the z-buffer |
min_range | minimum range to consifder points |
Definition at line 50 of file range_image_planar.hpp.
float pcl::RangeImagePlanar::getCenterX | ( | ) | const [inline] |
Getter for the principal point in X.
Definition at line 202 of file range_image_planar.h.
float pcl::RangeImagePlanar::getCenterY | ( | ) | const [inline] |
Getter for the principal point in Y.
Definition at line 206 of file range_image_planar.h.
float pcl::RangeImagePlanar::getFocalLengthX | ( | ) | const [inline] |
Getter for the focal length in X.
Definition at line 194 of file range_image_planar.h.
float pcl::RangeImagePlanar::getFocalLengthY | ( | ) | const [inline] |
Getter for the focal length in Y.
Definition at line 198 of file range_image_planar.h.
void pcl::RangeImagePlanar::getHalfImage | ( | RangeImage & | half_image | ) | const [virtual] |
Get a range image with half the resolution.
Reimplemented from pcl::RangeImage.
Definition at line 207 of file range_image_planar.cpp.
void pcl::RangeImagePlanar::getImagePoint | ( | const Eigen::Vector3f & | point, |
float & | image_x, | ||
float & | image_y, | ||
float & | range | ||
) | const [inline, virtual] |
Calculate the image point and range from the given 3D point.
point | the resulting 3D point |
image_x | the resulting x image position |
image_y | the resulting y image position |
range | the resulting range |
Reimplemented from pcl::RangeImage.
Definition at line 105 of file range_image_planar.hpp.
virtual RangeImage* pcl::RangeImagePlanar::getNew | ( | ) | const [inline, virtual] |
Return a newly created RangeImagePlanar. Reimplmentation to return an image of the same type.
Reimplemented from pcl::RangeImage.
Definition at line 69 of file range_image_planar.h.
void pcl::RangeImagePlanar::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 from pcl::RangeImage.
Definition at line 228 of file range_image_planar.cpp.
Ptr pcl::RangeImagePlanar::makeShared | ( | ) | [inline] |
Get a boost shared pointer of a copy of this.
Reimplemented from pcl::RangeImage.
Definition at line 78 of file range_image_planar.h.
void pcl::RangeImagePlanar::setDepthImage | ( | const float * | depth_image, |
int | di_width, | ||
int | di_height, | ||
float | di_center_x, | ||
float | di_center_y, | ||
float | di_focal_length_x, | ||
float | di_focal_length_y, | ||
float | desired_angular_resolution = -1 |
||
) |
Create the image from an existing depth image.
depth_image | the input depth image data as float values |
di_width | the disparity image width |
di_height | the disparity image height |
di_center_x | the x-coordinate of the camera's center of projection |
di_center_y | the y-coordinate of the camera's center of projection |
di_focal_length_x | the camera's focal length in the horizontal direction |
di_focal_length_y | the camera's focal length in the vertical direction |
desired_angular_resolution | If this is set, the system will skip as many pixels as necessary to get as close to this angular resolution as possible while not going over this value (the density will not be lower than this value). The value is in radians per pixel. |
Definition at line 116 of file range_image_planar.cpp.
void pcl::RangeImagePlanar::setDepthImage | ( | const unsigned short * | depth_image, |
int | di_width, | ||
int | di_height, | ||
float | di_center_x, | ||
float | di_center_y, | ||
float | di_focal_length_x, | ||
float | di_focal_length_y, | ||
float | desired_angular_resolution = -1 |
||
) |
Create the image from an existing depth image.
depth_image | the input disparity image data as short values describing millimeters |
di_width | the disparity image width |
di_height | the disparity image height |
di_center_x | the x-coordinate of the camera's center of projection |
di_center_y | the y-coordinate of the camera's center of projection |
di_focal_length_x | the camera's focal length in the horizontal direction |
di_focal_length_y | the camera's focal length in the vertical direction |
desired_angular_resolution | If this is set, the system will skip as many pixels as necessary to get as close to this angular resolution as possible while not going over this value (the density will not be lower than this value). The value is in radians per pixel. |
Definition at line 162 of file range_image_planar.cpp.
void pcl::RangeImagePlanar::setDisparityImage | ( | const float * | disparity_image, |
int | di_width, | ||
int | di_height, | ||
float | focal_length, | ||
float | base_line, | ||
float | desired_angular_resolution = -1 |
||
) |
Create the image from an existing disparity image.
disparity_image | the input disparity image data |
di_width | the disparity image width |
di_height | the disparity image height |
focal_length | the focal length of the primary camera that generated the disparity image |
base_line | the baseline of the stereo pair that generated the disparity image |
desired_angular_resolution | If this is set, the system will skip as many pixels as necessary to get as close to this angular resolution as possible while not going over this value (the density will not be lower than this value). The value is in radians per pixel. |
Definition at line 59 of file range_image_planar.cpp.
float pcl::RangeImagePlanar::center_x_ [protected] |
Definition at line 212 of file range_image_planar.h.
float pcl::RangeImagePlanar::center_y_ [protected] |
The principle point of the image.
Definition at line 212 of file range_image_planar.h.
float pcl::RangeImagePlanar::focal_length_x_ [protected] |
Definition at line 210 of file range_image_planar.h.
float pcl::RangeImagePlanar::focal_length_x_reciprocal_ [protected] |
Definition at line 211 of file range_image_planar.h.
float pcl::RangeImagePlanar::focal_length_y_ [protected] |
The focal length of the image in pixels.
Definition at line 210 of file range_image_planar.h.
float pcl::RangeImagePlanar::focal_length_y_reciprocal_ [protected] |
1/focal_length -> for internal use
Definition at line 211 of file range_image_planar.h.