Class for converting 2D points between various coordinate systems. More...
#include <CoordinateConverter.h>
Public Member Functions | |
Point2D | mapToWorld (Pixel mapPoint) |
std::vector< Point2D > | mapToWorld (const std::vector< Pixel > &mapPoints) |
void | robotToMap (float robotX, float robotY, float robotTheta, float pointX, float pointY, int &mapX, int &mapY) |
Pixel | robotToMap (Pose robotPose, Point2D robotPoint) |
std::vector< Pixel > | robotToMap (Pose robotPose, const std::vector< Point2D > &robotPoints) |
Pixel | worldToMap (Point2D worldPoint) |
Pixel | worldToMap (Pose worldPose) |
void | worldToMap (float worldX, float worldY, int &mapX, int &mapY) |
std::vector< Pixel > | worldToMap (const std::vector< Point2D > &worldPoints) |
Point2D | worldToMapPoint (Point2D worldPoint) |
virtual | ~CoordinateConverter () |
Static Public Member Functions | |
static CoordinateConverter * | getInstance () |
************ Deprecated. DO NOT USE! ***************** | |
static Point2D | polarToCartesian (float theta, float distance) |
static Point2D | robotToWorld (Pose robotPose, Point2D robotPoint) |
static Pose | robotToWorld (Pose robotPose, Pose pose) |
static Transformation2D | robotToWorld (Pose robotPose, Transformation2D transformation) |
static std::vector< Point2D > | robotToWorld (Pose robotPose, const std::vector< Point2D > &robotPoints) |
static Vector3D | simLaser3DToLaser3D (float alpha, float beta, float range) |
static std::vector< Vector3D > | simLaser3DToLaser3D (float fovH, float fovV, float resH, float resH2, std::vector< float > *range) |
static Vector3D | sphericalPlaneToWorldCoordDeg (float range, float h, float theta_deg, float phi_deg) |
static Vector3D | sphericalPlaneToWorldCoordRad (float range, float h, float theta_rad, float phi_rad) |
static Vector3D | sphericalToCartesian (float range, float phi, float theta) |
static Point2D | worldToRobot (Pose robotPose, Point2D worldPoint) |
static Transformation2D | worldToRobot (Pose robotPose, Transformation2D transformation) |
Private Member Functions | |
CoordinateConverter () | |
Private Attributes | |
float | m_CellSize |
float | m_MapHalfHeight |
float | m_MapHalfWidth |
float | m_MapHeight |
float | m_MapWidth |
Static Private Attributes | |
static CoordinateConverter * | m_Instance |
Class for converting 2D points between various coordinate systems.
Definition at line 26 of file CoordinateConverter.h.
virtual CoordinateConverter::~CoordinateConverter | ( | ) | [virtual] |
Destructor
CoordinateConverter::CoordinateConverter | ( | ) | [private] |
Private default Constructor (-->Singleton)
static CoordinateConverter* CoordinateConverter::getInstance | ( | ) | [static] |
************ Deprecated. DO NOT USE! *****************
Point2D CoordinateConverter::mapToWorld | ( | Pixel | mapPoint | ) |
std::vector<Point2D> CoordinateConverter::mapToWorld | ( | const std::vector< Pixel > & | mapPoints | ) |
static Point2D CoordinateConverter::polarToCartesian | ( | float | theta, |
float | distance | ||
) | [static] |
void CoordinateConverter::robotToMap | ( | float | robotX, |
float | robotY, | ||
float | robotTheta, | ||
float | pointX, | ||
float | pointY, | ||
int & | mapX, | ||
int & | mapY | ||
) |
Pixel CoordinateConverter::robotToMap | ( | Pose | robotPose, |
Point2D | robotPoint | ||
) |
std::vector<Pixel> CoordinateConverter::robotToMap | ( | Pose | robotPose, |
const std::vector< Point2D > & | robotPoints | ||
) |
static Point2D CoordinateConverter::robotToWorld | ( | Pose | robotPose, |
Point2D | robotPoint | ||
) | [static] |
From robot to all others
static Pose CoordinateConverter::robotToWorld | ( | Pose | robotPose, |
Pose | pose | ||
) | [static] |
static Transformation2D CoordinateConverter::robotToWorld | ( | Pose | robotPose, |
Transformation2D | transformation | ||
) | [static] |
static std::vector<Point2D> CoordinateConverter::robotToWorld | ( | Pose | robotPose, |
const std::vector< Point2D > & | robotPoints | ||
) | [static] |
static Vector3D CoordinateConverter::simLaser3DToLaser3D | ( | float | alpha, |
float | beta, | ||
float | range | ||
) | [static] |
From simLaser3D (spheric) to laser3D (cartesian)
static std::vector<Vector3D> CoordinateConverter::simLaser3DToLaser3D | ( | float | fovH, |
float | fovV, | ||
float | resH, | ||
float | resH2, | ||
std::vector< float > * | range | ||
) | [static] |
Convert simLaser3D points given by a vector of ranges, horizontal and vertical FOV and resolution
static Vector3D CoordinateConverter::sphericalPlaneToWorldCoordDeg | ( | float | range, |
float | h, | ||
float | theta_deg, | ||
float | phi_deg | ||
) | [inline, static] |
Definition at line 71 of file CoordinateConverter.h.
static Vector3D CoordinateConverter::sphericalPlaneToWorldCoordRad | ( | float | range, |
float | h, | ||
float | theta_rad, | ||
float | phi_rad | ||
) | [static] |
From spherical plane slice to world coordinate
range | the distance from the LRF-origin to a measured point P |
h | the distance from the LRF-origin to the rotation axis of the servo-motor |
theta | the angle between the positive z-axis and the line g between the rotation axis and the measured point P |
phi | the angle between the positive x-axis and the projected line g onto the xy-plane |
static Vector3D CoordinateConverter::sphericalToCartesian | ( | float | range, |
float | phi, | ||
float | theta | ||
) | [static] |
From spherical to cartesian
range | the distance from the origin to a given point P |
phi | the angle between the positive z-axis and the line formed between the origin and the point P |
theta | the angle between the positive x-axis and the line from the origin to the point P projected onto the xy-plane |
Pixel CoordinateConverter::worldToMap | ( | Point2D | worldPoint | ) |
Pixel CoordinateConverter::worldToMap | ( | Pose | worldPose | ) |
void CoordinateConverter::worldToMap | ( | float | worldX, |
float | worldY, | ||
int & | mapX, | ||
int & | mapY | ||
) |
std::vector<Pixel> CoordinateConverter::worldToMap | ( | const std::vector< Point2D > & | worldPoints | ) |
Point2D CoordinateConverter::worldToMapPoint | ( | Point2D | worldPoint | ) |
static Point2D CoordinateConverter::worldToRobot | ( | Pose | robotPose, |
Point2D | worldPoint | ||
) | [static] |
From world to all others
static Transformation2D CoordinateConverter::worldToRobot | ( | Pose | robotPose, |
Transformation2D | transformation | ||
) | [static] |
float CoordinateConverter::m_CellSize [private] |
Definition at line 115 of file CoordinateConverter.h.
CoordinateConverter* CoordinateConverter::m_Instance [static, private] |
Single instance of the singleton ;-)
Definition at line 112 of file CoordinateConverter.h.
float CoordinateConverter::m_MapHalfHeight [private] |
Definition at line 119 of file CoordinateConverter.h.
float CoordinateConverter::m_MapHalfWidth [private] |
Definition at line 118 of file CoordinateConverter.h.
float CoordinateConverter::m_MapHeight [private] |
Definition at line 117 of file CoordinateConverter.h.
float CoordinateConverter::m_MapWidth [private] |
Definition at line 116 of file CoordinateConverter.h.