Functions | |
| static void | fix_to_ecef (const sensor_msgs::NavSatFix &fix, double ecef[3]) |
| void | fix_to_point (const sensor_msgs::NavSatFix &fix, const sensor_msgs::NavSatFix &datum, geometry_msgs::Point *point_ptr) |
| Converts an LLH coordinate into the corresponding ENU coordinate. | |
| void | point_to_fix (const geometry_msgs::Point &point, const sensor_msgs::NavSatFix &datum, sensor_msgs::NavSatFix *fix_ptr) |
| Converts an ENU coordinate into the corresponding LLH coordinate Note that no population of the NavSatFix header occurs; that is the responsibility of the calling function. | |
| static void enu::fix_to_ecef | ( | const sensor_msgs::NavSatFix & | fix, |
| double | ecef[3] | ||
| ) | [static] |
| void enu::fix_to_point | ( | const sensor_msgs::NavSatFix & | fix, |
| const sensor_msgs::NavSatFix & | datum, | ||
| geometry_msgs::Point * | point_ptr | ||
| ) |
Converts an LLH coordinate into the corresponding ENU coordinate.
Requires a datum (passed as a NavSatFix)
| [in] | fix | NavSatFix with a valid latitude, longitude, and altitude representing the current position |
| [in] | datum | Datum point in LLH format |
| [out] | point_ptr | ENU of current position relative to datum |
| void enu::point_to_fix | ( | const geometry_msgs::Point & | point, |
| const sensor_msgs::NavSatFix & | datum, | ||
| sensor_msgs::NavSatFix * | fix_ptr | ||
| ) |
Converts an ENU coordinate into the corresponding LLH coordinate Note that no population of the NavSatFix header occurs; that is the responsibility of the calling function.
Requires a datum (passed as a NavSatFix)
| [in] | point | ENU position with respect to datum point |
| [in] | datum | Datum point in LLH format |
| [out] | fix_ptr | LLH corresponding to ENU + datum combination |