RangeImageSpherical is derived from the original range image and uses a slightly different spherical projection. In the original range image, the image will appear more and more "scaled down" along the y axis, the further away from the mean line of the image a point is. This class removes this scaling, which makes it especially suitable for spinning LIDAR sensors that capure a 360° view, since a rotation of the sensor will now simply correspond to a shift of the range image. (This class is similar to RangeImagePlanar, but changes less of the behaviour of the base class.) More...
#include <range_image_spherical.h>
Public Types | |
typedef RangeImage | BaseClass |
typedef boost::shared_ptr < const RangeImageSpherical > | ConstPtr |
typedef boost::shared_ptr < RangeImageSpherical > | 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. | |
void | getAnglesFromImagePoint (float image_x, float image_y, float &angle_x, float &angle_y) const |
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. | |
void | getImagePointFromAngles (float angle_x, float angle_y, float &image_x, float &image_y) const |
virtual RangeImage * | getNew () const |
Ptr | makeShared () |
Get a boost shared pointer of a copy of this. | |
PCL_EXPORTS | RangeImageSpherical () |
virtual PCL_EXPORTS | ~RangeImageSpherical () |
RangeImageSpherical is derived from the original range image and uses a slightly different spherical projection. In the original range image, the image will appear more and more "scaled down" along the y axis, the further away from the mean line of the image a point is. This class removes this scaling, which makes it especially suitable for spinning LIDAR sensors that capure a 360° view, since a rotation of the sensor will now simply correspond to a shift of the range image. (This class is similar to RangeImagePlanar, but changes less of the behaviour of the base class.)
Definition at line 51 of file range_image_spherical.h.
Reimplemented from pcl::RangeImage.
Definition at line 55 of file range_image_spherical.h.
typedef boost::shared_ptr<const RangeImageSpherical> pcl::RangeImageSpherical::ConstPtr |
Reimplemented from pcl::RangeImage.
Definition at line 57 of file range_image_spherical.h.
typedef boost::shared_ptr<RangeImageSpherical> pcl::RangeImageSpherical::Ptr |
Reimplemented from pcl::RangeImage.
Definition at line 56 of file range_image_spherical.h.
PCL_EXPORTS pcl::RangeImageSpherical::RangeImageSpherical | ( | ) | [inline] |
Constructor
Definition at line 61 of file range_image_spherical.h.
virtual PCL_EXPORTS pcl::RangeImageSpherical::~RangeImageSpherical | ( | ) | [inline, virtual] |
Destructor
Definition at line 63 of file range_image_spherical.h.
void pcl::RangeImageSpherical::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 44 of file range_image_spherical.hpp.
void pcl::RangeImageSpherical::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 from pcl::RangeImage.
Definition at line 66 of file range_image_spherical.hpp.
void pcl::RangeImageSpherical::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 56 of file range_image_spherical.hpp.
void pcl::RangeImageSpherical::getImagePointFromAngles | ( | float | angle_x, |
float | angle_y, | ||
float & | image_x, | ||
float & | image_y | ||
) | const [inline] |
Get the image point corresponding to the given ranges
Reimplemented from pcl::RangeImage.
Definition at line 73 of file range_image_spherical.hpp.
virtual RangeImage* pcl::RangeImageSpherical::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 68 of file range_image_spherical.h.
Ptr pcl::RangeImageSpherical::makeShared | ( | ) | [inline] |
Get a boost shared pointer of a copy of this.
Reimplemented from pcl::RangeImage.
Definition at line 73 of file range_image_spherical.h.