24 #include <GeographicLib/Geocentric.hpp>
25 #include <GeographicLib/Geoid.hpp>
27 #include <geometry_msgs/PoseStamped.h>
28 #include <geometry_msgs/PoseWithCovarianceStamped.h>
29 #include <geometry_msgs/TransformStamped.h>
32 #define GPS_LEAPSECONDS_MILLIS 18000ULL
34 #define MSEC_PER_WEEK (7ULL * 86400ULL * 1000ULL)
35 #define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)
38 namespace extra_plugins {
39 using mavlink::common::GPS_FIX_TYPE;
40 using mavlink::common::GPS_INPUT_IGNORE_FLAGS;
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59 earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f()),
83 double origin_lat, origin_lon, origin_alt;
91 fix_type =
static_cast<GPS_FIX_TYPE
>(ft_i);
102 fp_nh.
param(
"geo_origin/lat", origin_lat, 47.3667);
103 fp_nh.
param(
"geo_origin/lon", origin_lon, 8.5500);
104 fp_nh.
param(
"geo_origin/alt", origin_alt, 408.0);
107 map_origin = {origin_lat, origin_lon, origin_alt};
117 catch (
const std::exception& e) {
217 Eigen::Vector3d geodetic;
218 Eigen::Vector3d current_ecef(
ecef_origin.x() + ecef_offset.x(),
223 earth.Reverse(current_ecef.x(), current_ecef.y(), current_ecef.z(),
224 geodetic.x(), geodetic.y(), geodetic.z());
226 catch (
const std::exception& e) {
243 mavlink::common::msg::HIL_GPS hil_gps {};
249 if (vel.x() == 0 && vel.y() == 0) {
252 else if (vel.x() >= 0 && vel.y() < 0) {
253 cog = M_PI * 5 / 2 - atan2(vel.x(), vel.y());
256 cog = M_PI / 2 - atan2(vel.x(), vel.y());
260 hil_gps.time_usec = stamp.
toNSec() / 1000;
261 hil_gps.lat = geodetic.x() * 1e7;
262 hil_gps.lon = geodetic.y() * 1e7;
263 hil_gps.alt = (geodetic.z() + GeographicLib::Geoid::ELLIPSOIDTOGEOID *
265 hil_gps.vel = vel.block<2, 1>(0, 0).norm();
266 hil_gps.vn = vel.x();
267 hil_gps.ve = vel.y();
268 hil_gps.vd = vel.z();
269 hil_gps.cog = cog * 1e2;
270 hil_gps.eph =
eph * 1e2;
271 hil_gps.epv =
epv * 1e2;
282 mavlink::common::msg::GPS_INPUT gps_input {};
285 gps_input.time_usec = stamp.
toNSec() / 1000;
286 gps_input.gps_id =
gps_id;
287 gps_input.ignore_flags = 0;
289 gps_input.ignore_flags |=
utils::enum_value(GPS_INPUT_IGNORE_FLAGS::FLAG_SPEED_ACCURACY);
294 if (fabs(vel.x()) <= 0.01f && fabs(vel.y()) <= 0.01f)
295 gps_input.ignore_flags |=
utils::enum_value(GPS_INPUT_IGNORE_FLAGS::FLAG_VEL_HORIZ);
296 if (fabs(vel.z()) <= 0.01f)
297 gps_input.ignore_flags |=
utils::enum_value(GPS_INPUT_IGNORE_FLAGS::FLAG_VEL_VERT);
300 gps_input.time_week_ms = tdiff - (gps_input.time_week *
MSEC_PER_WEEK);
304 gps_input.lat = geodetic.x() * 1e7;
305 gps_input.lon = geodetic.y() * 1e7;
306 gps_input.alt = (geodetic.z() + GeographicLib::Geoid::ELLIPSOIDTOGEOID *
308 gps_input.vn = vel.x();
309 gps_input.ve = vel.y();
310 gps_input.vd = vel.z();
311 gps_input.hdop =
eph;
312 gps_input.vdop =
epv;
323 Eigen::Affine3d pos_enu;
331 Eigen::Affine3d pos_enu;
333 horiz_accuracy = (req->pose.covariance[0] + req->pose.covariance[7]) / 2.0
f;
341 Eigen::Affine3d pos_enu;
349 Eigen::Affine3d pos_enu;
357 Eigen::Affine3d pos_enu;