Go to the documentation of this file.00001
00038 #ifndef INCLUDE_ENU_ENU_H_
00039 #define INCLUDE_ENU_ENU_H_
00040
00041 #include "ros/message_forward.h"
00042
00043 namespace sensor_msgs { ROS_DECLARE_MESSAGE(NavSatFix); }
00044
00045 namespace geometry_msgs { ROS_DECLARE_MESSAGE(Point); }
00046
00047 namespace enu {
00048
00058 void fix_to_point(const sensor_msgs::NavSatFix& fix,
00059 const sensor_msgs::NavSatFix& datum,
00060 geometry_msgs::Point* point_ptr);
00061
00072 void point_to_fix(const geometry_msgs::Point& point,
00073 const sensor_msgs::NavSatFix& datum,
00074 sensor_msgs::NavSatFix* fix_ptr);
00075 }
00076
00077 #endif // INCLUDE_ENU_ENU_H_