#include <CoordinateConverter.h>
Public Member Functions | |
CoordinateConverter () | |
BoundingBox2 | GetBoundingBox () const |
const Vector2d & | GetOffset () const |
kt_double | GetResolution () const |
kt_double | GetScale () const |
const Size2< kt_int32s > & | GetSize () const |
Vector2d | GridToWorld (const Vector2i &rGrid, kt_bool flipY=false) const |
void | SetOffset (const Vector2d &rOffset) |
void | SetResolution (kt_double resolution) |
void | SetScale (kt_double scale) |
void | SetSize (const Size2< kt_int32s > &rSize) |
KARTO_DEPRECATED kt_double | Transform (kt_double value) |
Vector2i | WorldToGrid (const Vector2d &rWorld, kt_bool flipY=false) const |
Private Attributes | |
Vector2d | m_Offset |
kt_double | m_Scale |
Size2< kt_int32s > | m_Size |
Convert coordinates between world and grid coordinates. In world coordinates, 1.0 = 1 meter, whereas in grid coordinates, 1 = 1 pixel! The conversion from pixels to meters is 1.0 meter = 1 pixel / scale.
Definition at line 40 of file CoordinateConverter.h.
|
inline |
Constructs a converter with a scale of 20.0 (conversion: 1 pixel = 0.05 meters)
Definition at line 46 of file CoordinateConverter.h.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
Converts the given grid coordinate to world coordinates
rGrid | grid coordinate |
flipY | whether to flip the y-coordinate (useful for drawing applications with inverted y-coordinates) |
Definition at line 91 of file CoordinateConverter.h.
|
inline |
|
inline |
Sets the resolution
resolution | new resolution |
Definition at line 175 of file CoordinateConverter.h.
|
inline |
|
inline |
Scales the given value
value | value to scale |
Definition at line 57 of file CoordinateConverter.h.
|
inline |
Converts the given world coordinate to grid coordinates
rWorld | world coordinate |
flipY | whether to flip the y-coordinate (useful for drawing applications with inverted y-coordinates) |
Definition at line 68 of file CoordinateConverter.h.
|
private |
Definition at line 202 of file CoordinateConverter.h.
|
private |
Definition at line 200 of file CoordinateConverter.h.
Definition at line 199 of file CoordinateConverter.h.