Class MapHdl
Defined in File map_handler.hpp
Inheritance Relationships
Derived Types
public tuw::GeoHdl
(Class GeoHdl)public tuw::WorldScopedMaps
(Class WorldScopedMaps)
Class Documentation
-
class MapHdl
class to handle transformations form world system [meter] to image system [pixel]
Subclassed by tuw::GeoHdl, tuw::WorldScopedMaps
Public Functions
-
MapHdl()
-
virtual ~MapHdl() = default
-
void init(int width_pixel, int height_pixel, cv::Matx33d Mw2m)
used to initialize the figure
- Parameters:
width_pixel – pixel size of the canvas
height_pixel – pixel size of the canvas
Mw2m – transformation world to map
-
std::string info_map() const
- Returns:
map information as string to print
-
void init(cv::Size canvas_size, double resolution, cv::Point2d origin, double rotation = 0.)
used to initialize the figure
- Parameters:
canvas_size – pixel size of the canvas [pix]
resolution – resolution size of a pixel [m/pix]
origin – origin in relative to the top left [m]
rotation – origin in relative to the top left [m]
-
void init(int width_pixel, int height_pixel, double min_x, double max_x, double min_y, double max_y, double rotation = 0, bool enforce_positive_axis = true)
used to initialize the figure
- Parameters:
width_pixel – pixel size of the canvas
height_pixel – pixel size of the canvas
min_x – minimal x of the visualized space
max_x – maximal x of the visualized space
min_y – minimal y of the visualized space
max_y – maximal y of the visualized space
rotation – rotation of the visualized spaces
enforce_positive_axis – on true it will check that min_y < max_y and min_x < max_x and corrects if needed
-
template<typename T>
inline void init(const T &metadata) used to initialize the figure based on a ROS nav_msgs/MapMetaData
- Parameters:
T – nav_msgs/MapMetaData
-
bool initialized()
- Returns:
true if the figure is initialized
-
const cv::Matx33d &Mw2m() const
- Returns:
transformation matrix from the visualization space to image space (world -> map)
-
const cv::Matx33d &Mm2w() const
- Returns:
transformation matrix from the image space to visualization space (map -> world)
-
Point2D w2m(const Point2D &src) const
transforms a point from the visualization space to image space (world -> map)
- Parameters:
src – point in visualization space (world)
- Returns:
point in image space (map [pixel])
-
Point2D w2m(double x, double y) const
transforms a point from the visualization space to image space (world -> map)
- Parameters:
x – x coordinate in visualization space (world) eg. [m]
y – y coordinate in visualization space (world) eg. [m]
- Returns:
point in image space eg. [pixel]
-
Point2D &w2m(const Point2D &src, Point2D &des) const
transforms a point from the visualization space to image space (world -> map)
- Parameters:
src – point in visualization space (world)
des – point in image space (map [pixel])
- Returns:
reference to des
-
cv::Point2d &w2m(const cv::Point2d &src, cv::Point2d &des) const
transforms a point from the visualization space to image space (world -> map)
- Parameters:
src – point in visualization space (world)
des – point in image space (map [pixel])
- Returns:
reference to des
-
cv::Point w2m(const cv::Point2d &src) const
transforms a point from the visualization space to image space (world -> map)
- Parameters:
src – point in visualization space (world)
- Returns:
point in image space (map [pixel])
-
cv::Point &w2m(const cv::Point2d &src, cv::Point &des) const
transforms a point from the visualization space to image space (world -> map)
- Parameters:
src – point in visualization space (world)
des – point in image space (map [pixel])
- Returns:
reference to des
-
Point2D m2w(const Point2D &src) const
transforms a point from the image space to visualization space (map -> world)
- Parameters:
src – point in image space (map [pixel])
- Returns:
point in visualization space (world)
-
Point2D m2w(double x, double y) const
transforms a point from the image space to visualization space (map -> world)
- Parameters:
x – x coordinate in image space eg. [pixel]
y – y coordinate in image space eg. [pixel]
- Returns:
point in visualization space (world) eg. [m]
-
Point2D &m2w(const Point2D &src, Point2D &des) const
transforms a point from the image space to visualization space (map -> world)
- Parameters:
src – point in image space (map [pixel])
des – point in visualization space (world)
- Returns:
reference to des
-
cv::Point2d &m2w(const cv::Point2d &src, cv::Point2d &des) const
transforms a point from the image space to visualization space (map -> world)
- Parameters:
src – point in image space (map [pixel])
des – point in visualization space (world)
- Returns:
reference to des
-
cv::Point2d m2w(const cv::Point &src) const
transforms a point from the image space to visualization space (map -> world)
- Parameters:
src – point in image space (map [pixel])
- Returns:
point in visualization space (world)
-
cv::Point2d &m2w(const cv::Point &src, cv::Point2d &des) const
transforms a point from the image space to visualization space (map -> world)
- Parameters:
src – point in image space (map [pixel])
des – point in visualization space (world)
- Returns:
reference to des
-
int width() const
- Returns:
canvas (image) width
-
int height() const
- Returns:
canvas (image) height
-
cv::Size size() const
- Returns:
canvas (image) size
-
double origin_x() const
- Returns:
offest to the the zero x in [m]
-
double origin_y() const
- Returns:
offest to the the zero y in [m]
-
double resolution_x() const
- Returns:
computed x resolution
-
double scale_x() const
- Returns:
computed x scale
-
double scale_y() const
- Returns:
computed y scale
-
double resolution_y() const
- Returns:
computed y resolution
-
double min_x() const
- Returns:
minimal x of the visualized space
-
double max_x() const
- Returns:
maximal x of the visualized space
-
double min_y() const
- Returns:
minimal y of the visualized space
-
double max_y() const
- Returns:
maximal y of the visualized space
-
double scale_w2m(double v) const
returns a distance measure scaled
- Parameters:
v – value to be scaledt
- Returns:
distance
-
std::string infoHeader() const
returns information about the maps metadata
- Parameters:
format – using printf format
- Returns:
string
-
MapHdl()