global_position.cpp
Go to the documentation of this file.
1 
10 /*
11  * Copyright 2014,2017 Nuno Marques.
12  * Copyright 2015,2016 Vladimir Ermakov.
13  *
14  * This file is part of the mavros package and subject to the license terms
15  * in the top-level LICENSE file of the mavros repository.
16  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
17  */
18 
19 #include <angles/angles.h>
20 #include <mavros/mavros_plugin.h>
22 #include <GeographicLib/Geocentric.hpp>
23 
24 #include <std_msgs/Float64.h>
25 #include <nav_msgs/Odometry.h>
26 #include <sensor_msgs/NavSatFix.h>
27 #include <sensor_msgs/NavSatStatus.h>
28 #include <geometry_msgs/PoseStamped.h>
29 #include <geometry_msgs/TwistStamped.h>
30 #include <geometry_msgs/TransformStamped.h>
31 #include <geographic_msgs/GeoPointStamped.h>
32 
33 #include <mavros_msgs/HomePosition.h>
34 
35 namespace mavros {
36 namespace std_plugins {
45 public:
46  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 
49  gp_nh("~global_position"),
50  tf_send(false),
51  rot_cov(99999.0),
52  use_relative_alt(true),
53  is_map_init(false)
54  { }
55 
56  void initialize(UAS &uas_)
57  {
58  PluginBase::initialize(uas_);
59 
60  // general params
61  gp_nh.param<std::string>("frame_id", frame_id, "map");
62  gp_nh.param<std::string>("child_frame_id", child_frame_id, "base_link");
63  gp_nh.param("rot_covariance", rot_cov, 99999.0);
64  gp_nh.param("gps_uere", gps_uere, 1.0);
65  gp_nh.param("use_relative_alt", use_relative_alt, true);
66  // tf subsection
67  gp_nh.param("tf/send", tf_send, false);
68  gp_nh.param<std::string>("tf/frame_id", tf_frame_id, "map");
69  gp_nh.param<std::string>("tf/global_frame_id", tf_global_frame_id, "earth"); // The global_origin should be represented as "earth" coordinate frame (ECEF) (REP 105)
70  gp_nh.param<std::string>("tf/child_frame_id", tf_child_frame_id, "base_link");
71 
73 
74  // gps data
75  raw_fix_pub = gp_nh.advertise<sensor_msgs::NavSatFix>("raw/fix", 10);
76  raw_vel_pub = gp_nh.advertise<geometry_msgs::TwistStamped>("raw/gps_vel", 10);
77 
78  // fused global position
79  gp_fix_pub = gp_nh.advertise<sensor_msgs::NavSatFix>("global", 10);
80  gp_odom_pub = gp_nh.advertise<nav_msgs::Odometry>("local", 10);
81  gp_rel_alt_pub = gp_nh.advertise<std_msgs::Float64>("rel_alt", 10);
82  gp_hdg_pub = gp_nh.advertise<std_msgs::Float64>("compass_hdg", 10);
83 
84  // global origin
85  gp_global_origin_pub = gp_nh.advertise<geographic_msgs::GeoPointStamped>("gp_origin", 10);
87 
88  // home position subscriber to set "map" origin
89  // TODO use UAS
91 
92  // offset from local position to the global origin ("earth")
93  gp_global_offset_pub = gp_nh.advertise<geometry_msgs::PoseStamped>("gp_lp_offset", 10);
94  }
95 
97  {
98  return {
100  // GPS_STATUS: there no corresponding ROS message, and it is not supported by APM
104  };
105  }
106 
107 private:
109 
118 
121 
122  std::string frame_id;
123  std::string child_frame_id;
124  std::string tf_frame_id;
125  std::string tf_global_frame_id;
126  std::string tf_child_frame_id;
127 
128  bool tf_send;
131 
132  double rot_cov;
133  double gps_uere;
134 
135  Eigen::Vector3d map_origin {};
136  Eigen::Vector3d ecef_origin {};
137  Eigen::Vector3d local_ecef {};
138 
139  template<typename MsgT>
140  inline void fill_lla(MsgT &msg, sensor_msgs::NavSatFix::Ptr fix)
141  {
142  fix->latitude = msg.lat / 1E7; // deg
143  fix->longitude = msg.lon / 1E7; // deg
144  fix->altitude = msg.alt / 1E3 + m_uas->geoid_to_ellipsoid_height(fix); // in meters
145  }
146 
148  {
149  fix->position_covariance.fill(0.0);
150  fix->position_covariance[0] = -1.0;
151  fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
152  }
153 
154  /* -*- message handlers -*- */
155 
156  void handle_gps_raw_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RAW_INT &raw_gps)
157  {
158  auto fix = boost::make_shared<sensor_msgs::NavSatFix>();
159 
160  fix->header = m_uas->synchronized_header(child_frame_id, raw_gps.time_usec);
161 
162  fix->status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
163  if (raw_gps.fix_type > 2)
164  fix->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
165  else {
166  ROS_WARN_THROTTLE_NAMED(30, "global_position", "GP: No GPS fix");
167  fix->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
168  }
169 
170  fill_lla(raw_gps, fix);
171 
172  float eph = (raw_gps.eph != UINT16_MAX) ? raw_gps.eph / 1E2F : NAN;
173  float epv = (raw_gps.epv != UINT16_MAX) ? raw_gps.epv / 1E2F : NAN;
174 
175  ftf::EigenMapCovariance3d gps_cov(fix->position_covariance.data());
176 
177  // With mavlink v2.0 use accuracies reported by sensor
178  if (msg->magic == MAVLINK_STX &&
179  raw_gps.h_acc > 0 && raw_gps.v_acc > 0) {
180  gps_cov.diagonal() << std::pow(raw_gps.h_acc / 1E3, 2), std::pow(raw_gps.h_acc / 1E3, 2), std::pow(raw_gps.v_acc / 1E3, 2);
181  fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
182  }
183  // With mavlink v1.0 approximate accuracies by DOP
184  else if (!std::isnan(eph) && !std::isnan(epv)) {
185  gps_cov.diagonal() << std::pow(eph * gps_uere, 2), std::pow(eph * gps_uere, 2), std::pow(epv * gps_uere, 2);
186  fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
187  }
188  else {
189  fill_unknown_cov(fix);
190  }
191 
192  // store & publish
193  m_uas->update_gps_fix_epts(fix, eph, epv, raw_gps.fix_type, raw_gps.satellites_visible);
194  raw_fix_pub.publish(fix);
195 
196  if (raw_gps.vel != UINT16_MAX &&
197  raw_gps.cog != UINT16_MAX) {
198  double speed = raw_gps.vel / 1E2; // m/s
199  double course = angles::from_degrees(raw_gps.cog / 1E2); // rad
200 
201  auto vel = boost::make_shared<geometry_msgs::TwistStamped>();
202 
203  vel->header.stamp = fix->header.stamp;
204  vel->header.frame_id = frame_id;
205 
206  // From nmea_navsat_driver
207  vel->twist.linear.x = speed * std::sin(course);
208  vel->twist.linear.y = speed * std::cos(course);
209 
210  raw_vel_pub.publish(vel);
211  }
212  }
213 
214  void handle_gps_global_origin(const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_GLOBAL_ORIGIN &glob_orig)
215  {
216  auto g_origin = boost::make_shared<geographic_msgs::GeoPointStamped>();
217  // auto header = m_uas->synchronized_header(frame_id, glob_orig.time_boot_ms); #TODO: requires Mavlink msg update
218 
219  g_origin->header.frame_id = tf_global_frame_id;
220  g_origin->header.stamp = ros::Time::now();
221 
222  try {
227  GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
228  GeographicLib::Constants::WGS84_f());
229 
230  earth.Forward(glob_orig.latitude / 1E7, glob_orig.longitude / 1E7, glob_orig.altitude / 1E3,
231  g_origin->position.latitude, g_origin->position.longitude, g_origin->position.altitude);
232 
233  gp_global_origin_pub.publish(g_origin);
234  }
235  catch (const std::exception& e) {
236  ROS_INFO_STREAM("GP: Caught exception: " << e.what() << std::endl);
237  }
238  }
239 
242  void handle_global_position_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::GLOBAL_POSITION_INT &gpos)
243  {
244  auto odom = boost::make_shared<nav_msgs::Odometry>();
245  auto fix = boost::make_shared<sensor_msgs::NavSatFix>();
246  auto relative_alt = boost::make_shared<std_msgs::Float64>();
247  auto compass_heading = boost::make_shared<std_msgs::Float64>();
248 
249  auto header = m_uas->synchronized_header(child_frame_id, gpos.time_boot_ms);
250 
251  // Global position fix
252  fix->header = header;
253 
254  fill_lla(gpos, fix);
255 
256  // fill GPS status fields using GPS_RAW data
257  auto raw_fix = m_uas->get_gps_fix();
258  if (raw_fix) {
259  fix->status.service = raw_fix->status.service;
260  fix->status.status = raw_fix->status.status;
261  fix->position_covariance = raw_fix->position_covariance;
262  fix->position_covariance_type = raw_fix->position_covariance_type;
263  }
264  else {
265  // no GPS_RAW_INT -> fix status unknown
266  fix->status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
267  fix->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
268 
269  // we don't know covariance
270  fill_unknown_cov(fix);
271  }
272 
273  relative_alt->data = gpos.relative_alt / 1E3; // in meters
274  compass_heading->data = (gpos.hdg != UINT16_MAX) ? gpos.hdg / 1E2 : NAN; // in degrees
275 
289  odom->header.stamp = header.stamp;
290  odom->header.frame_id = frame_id;
291  odom->child_frame_id = child_frame_id;
292 
293  // Linear velocity
294  tf::vectorEigenToMsg(Eigen::Vector3d(gpos.vy, gpos.vx, gpos.vz) / 1E2,
295  odom->twist.twist.linear);
296 
297  // Velocity covariance unknown
298  ftf::EigenMapCovariance6d vel_cov_out(odom->twist.covariance.data());
299  vel_cov_out.fill(0.0);
300  vel_cov_out(0) = -1.0;
301 
302  // Current fix in ECEF
303  Eigen::Vector3d map_point;
304 
305  try {
313  GeographicLib::Geocentric map(GeographicLib::Constants::WGS84_a(),
314  GeographicLib::Constants::WGS84_f());
315 
323  // Current fix to ECEF
324  map.Forward(fix->latitude, fix->longitude, fix->altitude,
325  map_point.x(), map_point.y(), map_point.z());
326 
327  // Set the current fix as the "map" origin if it's not set
328  if (!is_map_init) {
329  map_origin.x() = fix->latitude;
330  map_origin.y() = fix->longitude;
331  map_origin.z() = fix->altitude;
332 
333  ecef_origin = map_point; // Local position is zero
334  is_map_init = true;
335  }
336  }
337  catch (const std::exception& e) {
338  ROS_INFO_STREAM("GP: Caught exception: " << e.what() << std::endl);
339  }
340 
341  // Compute the local coordinates in ECEF
342  local_ecef = map_point - ecef_origin;
343  // Compute the local coordinates in ENU
344  tf::pointEigenToMsg(ftf::transform_frame_ecef_enu(local_ecef, map_origin), odom->pose.pose.position);
345 
350  if (use_relative_alt)
351  odom->pose.pose.position.z = relative_alt->data;
352 
353  odom->pose.pose.orientation = m_uas->get_attitude_orientation_enu();
354 
355  // Use ENU covariance to build XYZRPY covariance
356  ftf::EigenMapConstCovariance3d gps_cov(fix->position_covariance.data());
357  ftf::EigenMapCovariance6d pos_cov_out(odom->pose.covariance.data());
358  pos_cov_out.setZero();
359  pos_cov_out.block<3, 3>(0, 0) = gps_cov;
360  pos_cov_out.block<3, 3>(3, 3).diagonal() <<
361  rot_cov,
362  rot_cov,
363  rot_cov;
364 
365  // publish
366  gp_fix_pub.publish(fix);
367  gp_odom_pub.publish(odom);
368  gp_rel_alt_pub.publish(relative_alt);
369  gp_hdg_pub.publish(compass_heading);
370 
371  // TF
372  if (tf_send) {
373  geometry_msgs::TransformStamped transform;
374 
375  transform.header.stamp = odom->header.stamp;
376  transform.header.frame_id = tf_frame_id;
377  transform.child_frame_id = tf_child_frame_id;
378 
379  // setRotation()
380  transform.transform.rotation = odom->pose.pose.orientation;
381 
382  // setOrigin()
383  transform.transform.translation.x = odom->pose.pose.position.x;
384  transform.transform.translation.y = odom->pose.pose.position.y;
385  transform.transform.translation.z = odom->pose.pose.position.z;
386 
387  m_uas->tf2_broadcaster.sendTransform(transform);
388  }
389  }
390 
391  void handle_lpned_system_global_offset(const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET &offset)
392  {
393  auto global_offset = boost::make_shared<geometry_msgs::PoseStamped>();
394  global_offset->header = m_uas->synchronized_header(tf_global_frame_id, offset.time_boot_ms);
395 
396  auto enu_position = ftf::transform_frame_ned_enu(Eigen::Vector3d(offset.x, offset.y, offset.z));
397  auto enu_baselink_orientation = ftf::transform_orientation_aircraft_baselink(
399  ftf::quaternion_from_rpy(offset.roll, offset.pitch, offset.yaw)));
400 
401  tf::pointEigenToMsg(enu_position, global_offset->pose.position);
402  tf::quaternionEigenToMsg(enu_baselink_orientation, global_offset->pose.orientation);
403 
404  gp_global_offset_pub.publish(global_offset);
405 
406  // TF
407  if (tf_send) {
408  geometry_msgs::TransformStamped transform;
409 
410  transform.header.stamp = global_offset->header.stamp;
411  transform.header.frame_id = tf_global_frame_id;
412  transform.child_frame_id = tf_frame_id;
413 
414  // setRotation()
415  transform.transform.rotation = global_offset->pose.orientation;
416 
417  // setOrigin()
418  transform.transform.translation.x = global_offset->pose.position.x;
419  transform.transform.translation.y = global_offset->pose.position.y;
420  transform.transform.translation.z = global_offset->pose.position.z;
421 
422  m_uas->tf2_broadcaster.sendTransform(transform);
423  }
424  }
425 
426  /* -*- diagnostics -*- */
428  {
429  int fix_type, satellites_visible;
430  float eph, epv;
431 
432  m_uas->get_gps_epts(eph, epv, fix_type, satellites_visible);
433 
434  if (satellites_visible <= 0)
435  stat.summary(2, "No satellites");
436  else if (fix_type < 2)
437  stat.summary(1, "No fix");
438  else if (fix_type == 2)
439  stat.summary(0, "2D fix");
440  else if (fix_type >= 3)
441  stat.summary(0, "3D fix");
442 
443  stat.addf("Satellites visible", "%zd", satellites_visible);
444  stat.addf("Fix type", "%d", fix_type);
445 
446  if (!std::isnan(eph))
447  stat.addf("EPH (m)", "%.2f", eph);
448  else
449  stat.add("EPH (m)", "Unknown");
450 
451  if (!std::isnan(epv))
452  stat.addf("EPV (m)", "%.2f", epv);
453  else
454  stat.add("EPV (m)", "Unknown");
455  }
456 
457  /* -*- callbacks -*- */
458 
460  {
461  map_origin.x() = req->geo.latitude;
462  map_origin.y() = req->geo.longitude;
463  map_origin.z() = req->geo.altitude;
464 
465  try {
469  GeographicLib::Geocentric map(GeographicLib::Constants::WGS84_a(),
470  GeographicLib::Constants::WGS84_f());
471 
472  // map_origin to ECEF
473  map.Forward(map_origin.x(), map_origin.y(), map_origin.z(),
474  ecef_origin.x(), ecef_origin.y(), ecef_origin.z());
475  }
476  catch (const std::exception& e) {
477  ROS_INFO_STREAM("GP: Caught exception: " << e.what() << std::endl);
478  }
479 
480  is_map_init = true;
481  }
482 
484  {
485  mavlink::common::msg::SET_GPS_GLOBAL_ORIGIN gpo;
486 
487  Eigen::Vector3d global_position;
488 
489  gpo.target_system = m_uas->get_tgt_system();
490  // gpo.time_boot_ms = stamp.toNSec() / 1000; #TODO: requires Mavlink msg update
491 
492  gpo.latitude = req->position.latitude * 1E7;
493  gpo.longitude = req->position.longitude * 1E7;
494  gpo.altitude = req->position.altitude * 1E3 + m_uas->ellipsoid_to_geoid_height(&req->position);
495 
496  UAS_FCU(m_uas)->send_message_ignore_drop(gpo);
497  }
498 };
499 } // namespace std_plugins
500 } // namespace mavros
501 
std::string frame_id
origin frame for topic headers
MAVROS Plugin base class.
Definition: mavros_plugin.h:37
Eigen::Vector3d ecef_origin
geocentric origin of map frame [m]
std::shared_ptr< MAVConnInterface const > ConstPtr
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
Create message header from time_boot_ms or time_usec stamps and frame_id.
Definition: mavros_uas.h:325
void fill_lla(MsgT &msg, sensor_msgs::NavSatFix::Ptr fix)
double ellipsoid_to_geoid_height(T lla)
Conversion from height above ellipsoid (WGS-84) to height above geoid (AMSL)
Definition: mavros_uas.h:259
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Quaternion get_attitude_orientation_enu()
Get Attitude orientation quaternion.
Definition: uas_data.cpp:139
void summary(unsigned char lvl, const std::string s)
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
void handle_lpned_system_global_offset(const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET &offset)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void fill_unknown_cov(sensor_msgs::NavSatFix::Ptr fix)
MAVROS Plugin base.
std::string tf_global_frame_id
global origin for TF
void handle_global_position_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::GLOBAL_POSITION_INT &gpos)
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
Definition: mavros_plugin.h:88
Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapCovariance6d
Eigen::Map for Covariance6d.
Definition: frame_tf.h:50
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapConstCovariance3d
Definition: frame_tf.h:47
#define UAS_DIAG(uasobjptr)
helper accessor to diagnostic updater
Definition: mavros_uas.h:47
void set_gp_origin_cb(const geographic_msgs::GeoPointStamped::ConstPtr &req)
void addf(const std::string &key, const char *format,...)
void gps_diag_run(diagnostic_updater::DiagnosticStatusWrapper &stat)
tf2_ros::TransformBroadcaster tf2_broadcaster
Definition: mavros_uas.h:271
Eigen::Vector3d local_ecef
local ECEF coordinates on map frame [m]
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:75
void home_position_cb(const mavros_msgs::HomePosition::ConstPtr &req)
uint8_t get_tgt_system()
Return communication target system.
Definition: mavros_uas.h:155
UAS for plugins.
Definition: mavros_uas.h:66
static double from_degrees(double degrees)
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
Definition: mavros_uas.h:41
std::string tf_child_frame_id
frame for TF and Pose
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
Definition: frame_tf.h:187
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void initialize(UAS &uas_)
Plugin initializer.
void handle_gps_global_origin(const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_GLOBAL_ORIGIN &glob_orig)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GlobalPositionPlugin()
void sendTransform(const geometry_msgs::TransformStamped &transform)
Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapCovariance3d
Eigen::Map for Covariance3d.
Definition: frame_tf.h:46
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
std::string child_frame_id
body-fixed frame for topic headers
#define ROS_INFO_STREAM(args)
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:48
sensor_msgs::NavSatFix::Ptr get_gps_fix()
Retunrs last GPS RAW message.
Definition: uas_data.cpp:219
T transform_frame_ecef_enu(const T &in, const T &map_origin)
Transform data expressed in ECEF frame to ENU frame.
Definition: frame_tf.h:226
T transform_orientation_ned_enu(const T &in)
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame...
Definition: frame_tf.h:152
static Time now()
void handle_gps_raw_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RAW_INT &raw_gps)
Eigen::Vector3d map_origin
geodetic origin of map frame [lla]
const std::string header
void add(const std::string &key, const T &val)
T transform_orientation_aircraft_baselink(const T &in)
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame...
Definition: frame_tf.h:170
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void update_gps_fix_epts(sensor_msgs::NavSatFix::Ptr &fix, float eph, float epv, int fix_type, int satellites_visible)
Store GPS RAW data.
Definition: uas_data.cpp:194
double geoid_to_ellipsoid_height(T lla)
Conversion from height above geoid (AMSL) to height above ellipsoid (WGS-84)
Definition: mavros_uas.h:246
void get_gps_epts(float &eph, float &epv, int &fix_type, int &satellites_visible)
Returns EPH, EPV, Fix type and satellites visible.
Definition: uas_data.cpp:208
std::shared_ptr< MAVConnInterface > Ptr


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11