Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

gps_global_origin: remove LLA to ECEF conversion #1942

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 1 addition & 16 deletions mavros/src/plugins/global_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,22 +233,7 @@ class GlobalPositionPlugin : public plugin::PluginBase {
g_origin->position.longitude = glob_orig.longitude / 1E7;
g_origin->position.altitude = glob_orig.altitude / 1E3 + m_uas->geoid_to_ellipsoid_height(&g_origin->position); // convert height amsl to height above the ellipsoid

try {
/**
* @brief Conversion from geodetic coordinates (LLA) to ECEF (Earth-Centered, Earth-Fixed)
* Note: "earth" frame, in ECEF, of the global origin
*/
GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f());

earth.Forward(g_origin->position.latitude, g_origin->position.longitude, g_origin->position.altitude,
g_origin->position.latitude, g_origin->position.longitude, g_origin->position.altitude);

gp_global_origin_pub.publish(g_origin);
}
catch (const std::exception& e) {
ROS_INFO_STREAM("GP: Caught exception: " << e.what() << std::endl);
}
gp_global_origin_pub.publish(g_origin);
}

/** @todo Handler for GLOBAL_POSITION_INT_COV */
Expand Down
Loading