Public Types | Public Member Functions
pcl::RangeImageSpherical Class Reference

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>

Inheritance diagram for pcl::RangeImageSpherical:
Inheritance graph
[legend]

List of all members.

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 RangeImagegetNew () const
Ptr makeShared ()
 Get a boost shared pointer of a copy of this.
PCL_EXPORTS RangeImageSpherical ()
virtual PCL_EXPORTS ~RangeImageSpherical ()

Detailed Description

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

Author:
Andreas Muetzel

Definition at line 51 of file range_image_spherical.h.


Member Typedef Documentation

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.

Reimplemented from pcl::RangeImage.

Definition at line 56 of file range_image_spherical.h.


Constructor & Destructor Documentation

Constructor

Definition at line 61 of file range_image_spherical.h.

Destructor

Definition at line 63 of file range_image_spherical.h.


Member Function Documentation

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.

Parameters:
image_xthe x image position
image_ythe y image position
rangethe range
pointthe resulting 3D point
Note:
Implementation according to planar range images (compared to spherical as in the original)

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.

Parameters:
pointthe resulting 3D point
image_xthe resulting x image position
image_ythe resulting y image position
rangethe resulting range
Note:
Implementation according to planar range images (compared to spherical as in the original)

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.

Get a boost shared pointer of a copy of this.

Reimplemented from pcl::RangeImage.

Definition at line 73 of file range_image_spherical.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:08