$search

MapXY Class Reference

#include <coordinates.h>

List of all members.

Public Member Functions

 MapXY (const MapXY &pt)
 MapXY (const geometry_msgs::Point32 &pt)
 MapXY (const geometry_msgs::Point &pt)
 MapXY (double _x, double _y)
 MapXY (float _x, float _y)
 MapXY (void)
bool operator!= (const MapXY &that) const
MapXY operator+ (const MapXY &that) const
MapXY operator- (const MapXY &that) const
bool operator== (const MapXY &that) const
void toMsg (geometry_msgs::Point32 &pt)
void toMsg (geometry_msgs::Point &pt)

Public Attributes

float x
float y

Detailed Description

MapXY coordinates

These are two-dimensional Euclidean coordinates in meters, relative to the nearest 10km UTM grid point to the map for this run. East is +x, north is +y.

We define our own class to emphasize its role in the system and the fact that its origin is relative to the map for this run.

Definition at line 74 of file coordinates.h.


Constructor & Destructor Documentation

MapXY::MapXY ( void   )  [inline]

Definition at line 81 of file coordinates.h.

MapXY::MapXY ( float  _x,
float  _y 
) [inline]

Definition at line 82 of file coordinates.h.

MapXY::MapXY ( double  _x,
double  _y 
) [inline]

Definition at line 83 of file coordinates.h.

MapXY::MapXY ( const geometry_msgs::Point pt  )  [inline]

Definition at line 84 of file coordinates.h.

MapXY::MapXY ( const geometry_msgs::Point32 pt  )  [inline]

Definition at line 85 of file coordinates.h.

MapXY::MapXY ( const MapXY pt  )  [inline]

Definition at line 86 of file coordinates.h.


Member Function Documentation

bool MapXY::operator!= ( const MapXY that  )  const [inline]

Definition at line 95 of file coordinates.h.

MapXY MapXY::operator+ ( const MapXY that  )  const [inline]

Definition at line 99 of file coordinates.h.

MapXY MapXY::operator- ( const MapXY that  )  const [inline]

Definition at line 103 of file coordinates.h.

bool MapXY::operator== ( const MapXY that  )  const [inline]

Definition at line 91 of file coordinates.h.

void MapXY::toMsg ( geometry_msgs::Point32 pt  )  [inline]

Definition at line 114 of file coordinates.h.

void MapXY::toMsg ( geometry_msgs::Point pt  )  [inline]

Definition at line 108 of file coordinates.h.


Member Data Documentation

float MapXY::x

Definition at line 77 of file coordinates.h.

float MapXY::y

Definition at line 78 of file coordinates.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


art_map
Author(s): David Li, Patrick Beeson, Bartley Gillen, Tarun Nimmagadda, Mickey Ristroph, Michael Quinlan, Jack O'Quin
autogenerated on Fri Mar 1 14:12:37 2013