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


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03