mavros_uas.h
Go to the documentation of this file.
1 
10 /*
11  * Copyright 2014,2015,2016,2017 Vladimir Ermakov.
12  *
13  * This file is part of the mavros package and subject to the license terms
14  * in the top-level LICENSE file of the mavros repository.
15  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
16  */
17 
18 #pragma once
19 
20 #include <array>
21 #include <mutex>
22 #include <atomic>
23 #include <type_traits>
29 #include <mavconn/interface.h>
30 #include <mavros/utils.h>
31 #include <mavros/frame_tf.h>
32 
33 #include <GeographicLib/Geoid.hpp>
34 
35 #include <sensor_msgs/Imu.h>
36 #include <sensor_msgs/NavSatFix.h>
37 
38 namespace mavros {
42 #define UAS_FCU(uasobjptr) \
43  ((uasobjptr)->fcu_link)
44 
48 #define UAS_DIAG(uasobjptr) \
49  ((uasobjptr)->diag_updater)
50 
51 
67 class UAS {
68 public:
69  // common enums used by UAS
70  using MAV_TYPE = mavlink::minimal::MAV_TYPE;
71  using MAV_AUTOPILOT = mavlink::minimal::MAV_AUTOPILOT;
72  using MAV_MODE_FLAG = mavlink::minimal::MAV_MODE_FLAG;
73  using MAV_STATE = mavlink::minimal::MAV_STATE;
74  using MAV_CAP = mavlink::common::MAV_PROTOCOL_CAPABILITY;
76 
77  // other UAS aliases
78  using ConnectionCb = std::function<void(bool)>;
79  using CapabilitiesCb = std::function<void(MAV_CAP)>;
80  using lock_guard = std::lock_guard<std::recursive_mutex>;
81  using unique_lock = std::unique_lock<std::recursive_mutex>;
82 
83  UAS();
84  ~UAS() {};
85 
90 
95 
99  inline bool is_connected() {
100  return connected;
101  }
102 
103  /* -*- HEARTBEAT data -*- */
104 
108  void update_heartbeat(uint8_t type_, uint8_t autopilot_, uint8_t base_mode_);
109 
113  void update_connection_status(bool conn_);
114 
119 
123  inline MAV_TYPE get_type() {
124  std::underlying_type<MAV_TYPE>::type type_ = type;
125  return static_cast<MAV_TYPE>(type_);
126  }
127 
132  std::underlying_type<MAV_AUTOPILOT>::type autopilot_ = autopilot;
133  return static_cast<MAV_AUTOPILOT>(autopilot_);
134  }
135 
141  inline bool get_armed() {
142  uint8_t base_mode_ = base_mode;
143  return base_mode_ & utils::enum_value(MAV_MODE_FLAG::SAFETY_ARMED);
144  }
145 
149  inline bool get_hil_state() {
150  uint8_t base_mode_ = base_mode;
151  return base_mode_ & utils::enum_value(MAV_MODE_FLAG::HIL_ENABLED);
152  }
153 
154  /* -*- FCU target id pair -*- */
155 
159  inline uint8_t get_tgt_system() {
160  return target_system; // not changed after configuration
161  }
162 
166  inline uint8_t get_tgt_component() {
167  return target_component;// not changed after configuration
168  }
169 
170  inline void set_tgt(uint8_t sys, uint8_t comp) {
171  target_system = sys;
172  target_component = comp;
173  }
174 
175 
176  /* -*- IMU data -*- */
177 
182 
187 
192 
197 
202  geometry_msgs::Quaternion get_attitude_orientation_enu();
203 
208  geometry_msgs::Quaternion get_attitude_orientation_ned();
209 
214  geometry_msgs::Vector3 get_attitude_angular_velocity_enu();
215 
220  geometry_msgs::Vector3 get_attitude_angular_velocity_ned();
221 
222 
223  /* -*- GPS data -*- */
224 
227  float eph, float epv,
228  int fix_type, int satellites_visible);
229 
231  void get_gps_epts(float &eph, float &epv, int &fix_type, int &satellites_visible);
232 
235 
236  /* -*- GograpticLib utils -*- */
237 
243  std::shared_ptr<GeographicLib::Geoid> egm96_5;
244 
249  template <class T>
250  inline double geoid_to_ellipsoid_height(T lla)
251  {
252  if (egm96_5)
253  return GeographicLib::Geoid::GEOIDTOELLIPSOID * (*egm96_5)(lla->latitude, lla->longitude);
254  else
255  return 0.0;
256  }
257 
262  template <class T>
263  inline double ellipsoid_to_geoid_height(T lla)
264  {
265  if (egm96_5)
266  return GeographicLib::Geoid::ELLIPSOIDTOGEOID * (*egm96_5)(lla->latitude, lla->longitude);
267  else
268  return 0.0;
269  }
270 
271  /* -*- transform -*- */
272 
277 
286  void add_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr, std::vector<geometry_msgs::TransformStamped>& vector);
287 
295  void publish_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr);
296 
297  /* -*- time sync -*- */
298 
299  inline void set_time_offset(uint64_t offset_ns) {
300  time_offset = offset_ns;
301  }
302 
303  inline uint64_t get_time_offset(void) {
304  return time_offset;
305  }
306 
307  inline void set_timesync_mode(timesync_mode mode) {
308  tsync_mode = mode;
309  }
310 
312  return tsync_mode;
313  }
314 
315  /* -*- autopilot version -*- */
316  uint64_t get_capabilities();
317 
323  template<typename T>
324  bool has_capability(T capability){
325  static_assert(std::is_enum<T>::value, "Only query capabilities using the UAS::MAV_CAP enum.");
326  return get_capabilities() & utils::enum_value(capability);
327  }
328 
335  template<typename ... Ts>
336  bool has_capabilities(Ts ... capabilities){
337  bool ret = true;
338  std::initializer_list<bool> capabilities_list{has_capability<Ts>(capabilities) ...};
339  for (auto has_cap : capabilities_list) ret &= has_cap;
340  return ret;
341  }
342 
346  void update_capabilities(bool known, uint64_t caps = 0);
347 
354 
362  ros::Time synchronise_stamp(uint32_t time_boot_ms);
363  ros::Time synchronise_stamp(uint64_t time_usec);
364 
374  template<typename T>
375  inline std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp) {
376  std_msgs::Header out;
377  out.frame_id = frame_id;
378  out.stamp = synchronise_stamp(time_stamp);
379  return out;
380  }
381 
382  /* -*- utils -*- */
383 
387  template<typename _T>
388  inline void msg_set_target(_T &msg) {
389  msg.target_system = get_tgt_system();
390  msg.target_component = get_tgt_component();
391  }
392 
396  inline bool is_my_target(uint8_t sysid, uint8_t compid) {
397  return sysid == get_tgt_system() && compid == get_tgt_component();
398  }
399 
403  inline bool is_my_target(uint8_t sysid) {
404  return sysid == get_tgt_system();
405  }
406 
410  inline bool is_ardupilotmega() {
411  return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
412  }
413 
417  inline bool is_px4() {
418  return MAV_AUTOPILOT::PX4 == get_autopilot();
419  }
420 
434  std::string str_mode_v10(uint8_t base_mode, uint32_t custom_mode);
435 
445  bool cmode_from_str(std::string cmode_str, uint32_t &custom_mode);
446 
447  inline void set_base_link_frame_id(const std::string frame_id) {
448  base_link_frame_id = frame_id;
449  }
450  inline void set_odom_frame_id(const std::string frame_id) {
451  odom_frame_id = frame_id;
452  }
453  inline void set_map_frame_id(const std::string frame_id) {
454  map_frame_id = frame_id;
455  }
456  inline std::string get_base_link_frame_id() {
457  return base_link_frame_id;
458  }
459  inline std::string get_odom_frame_id() {
460  return odom_frame_id;
461  }
462  inline std::string get_map_frame_id() {
463  return map_frame_id;
464  }
465  void setup_static_tf();
466 
467 private:
468  std::recursive_mutex mutex;
469 
470  std::atomic<uint8_t> type;
471  std::atomic<uint8_t> autopilot;
472  std::atomic<uint8_t> base_mode;
473 
474  uint8_t target_system;
476 
477  std::atomic<bool> connected;
478  std::vector<ConnectionCb> connection_cb_vec;
479  std::vector<CapabilitiesCb> capabilities_cb_vec;
480 
483 
485  float gps_eph;
486  float gps_epv;
489 
490  std::atomic<uint64_t> time_offset;
492 
493  std::atomic<bool> fcu_caps_known;
494  std::atomic<uint64_t> fcu_capabilities;
495 
497 };
498 } // namespace mavros
mavros::UAS::has_capability
bool has_capability(T capability)
Function to check if the flight controller has a capability.
Definition: mavros_uas.h:324
mavros::UAS::tf2_broadcaster
tf2_ros::TransformBroadcaster tf2_broadcaster
Definition: mavros_uas.h:275
mavros::utils::timesync_mode
timesync_mode
Definition: utils.h:44
mavros::UAS::capabilities_cb_vec
std::vector< CapabilitiesCb > capabilities_cb_vec
Definition: mavros_uas.h:479
mavros::UAS::mutex
std::recursive_mutex mutex
Definition: mavros_uas.h:468
mavros::UAS::base_mode
std::atomic< uint8_t > base_mode
Definition: mavros_uas.h:472
mavros::UAS::update_attitude_imu_ned
void update_attitude_imu_ned(sensor_msgs::Imu::Ptr &imu)
Store IMU data [NED].
Definition: uas_data.cpp:142
mavros::UAS::get_timesync_mode
timesync_mode get_timesync_mode(void)
Definition: mavros_uas.h:311
msg
msg
mavros::UAS::MAV_CAP
mavlink::common::MAV_PROTOCOL_CAPABILITY MAV_CAP
Definition: mavros_uas.h:74
mavros::UAS::update_attitude_imu_enu
void update_attitude_imu_enu(sensor_msgs::Imu::Ptr &imu)
Store IMU data [ENU].
Definition: uas_data.cpp:136
mavros::UAS
UAS for plugins.
Definition: mavros_uas.h:67
mavros::UAS::get_attitude_orientation_ned
geometry_msgs::Quaternion get_attitude_orientation_ned()
Get Attitude orientation quaternion.
Definition: uas_data.cpp:173
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
mavros::UAS::get_map_frame_id
std::string get_map_frame_id()
Definition: mavros_uas.h:462
mavros::UAS::fcu_capabilities
std::atomic< uint64_t > fcu_capabilities
Definition: mavros_uas.h:494
diagnostic_updater::Updater
mavros::UAS::set_odom_frame_id
void set_odom_frame_id(const std::string frame_id)
Definition: mavros_uas.h:450
mavros::UAS::odom_frame_id
std::string odom_frame_id
Definition: mavros_uas.h:496
mavros::UAS::tf2_buffer
tf2_ros::Buffer tf2_buffer
Definition: mavros_uas.h:273
mavros::UAS::autopilot
std::atomic< uint8_t > autopilot
Definition: mavros_uas.h:471
mavros::UAS::is_ardupilotmega
bool is_ardupilotmega()
Check that FCU is APM.
Definition: mavros_uas.h:410
mavros::UAS::type
std::atomic< uint8_t > type
Definition: mavros_uas.h:470
mavros::UAS::get_tgt_component
uint8_t get_tgt_component()
Return communication target component.
Definition: mavros_uas.h:166
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::UAS::~UAS
~UAS()
Definition: mavros_uas.h:84
mavros::UAS::add_connection_change_handler
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
Definition: uas_data.cpp:78
mavros::UAS::tsync_mode
timesync_mode tsync_mode
Definition: mavros_uas.h:491
mavros::UAS::get_attitude_imu_ned
sensor_msgs::Imu::Ptr get_attitude_imu_ned()
Get IMU data [NED].
Definition: uas_data.cpp:154
mavros::UAS::gps_fix
sensor_msgs::NavSatFix::Ptr gps_fix
Definition: mavros_uas.h:484
transform_broadcaster.h
mavros::UAS::connection_cb_vec
std::vector< ConnectionCb > connection_cb_vec
Definition: mavros_uas.h:478
mavros::UAS::connected
std::atomic< bool > connected
Definition: mavros_uas.h:477
diagnostic_updater.h
mavros::UAS::MAV_AUTOPILOT
mavlink::minimal::MAV_AUTOPILOT MAV_AUTOPILOT
Definition: mavros_uas.h:71
tf2_ros::TransformListener
tf2_ros::StaticTransformBroadcaster
mavros::UAS::is_my_target
bool is_my_target(uint8_t sysid, uint8_t compid)
Check that sys/comp id's is my target.
Definition: mavros_uas.h:396
mavros::UAS::cmode_from_str
bool cmode_from_str(std::string cmode_str, uint32_t &custom_mode)
Lookup custom mode for given string.
Definition: uas_stringify.cpp:254
utils.h
some useful utils
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
mavros::UAS::is_my_target
bool is_my_target(uint8_t sysid)
Check that system id is my target.
Definition: mavros_uas.h:403
mavros::UAS::get_time_offset
uint64_t get_time_offset(void)
Definition: mavros_uas.h:303
mavros::UAS::fcu_link
mavconn::MAVConnInterface::Ptr fcu_link
MAVLink FCU device conection.
Definition: mavros_uas.h:84
mavros::UAS::target_system
uint8_t target_system
Definition: mavros_uas.h:474
mavros::UAS::get_armed
bool get_armed()
Returns arming status.
Definition: mavros_uas.h:141
mavros::UAS::get_capabilities
uint64_t get_capabilities()
Definition: uas_data.cpp:92
mavros::UAS::get_attitude_orientation_enu
geometry_msgs::Quaternion get_attitude_orientation_enu()
Get Attitude orientation quaternion.
Definition: uas_data.cpp:160
mavros::UAS::gps_fix_type
int gps_fix_type
Definition: mavros_uas.h:487
mavros::UAS::msg_set_target
void msg_set_target(_T &msg)
Definition: mavros_uas.h:388
eigen_msg.h
mavros::UAS::has_capabilities
bool has_capabilities(Ts ... capabilities)
Function to check if the flight controller has a set of capabilities.
Definition: mavros_uas.h:336
mavros::UAS::tf2_listener
tf2_ros::TransformListener tf2_listener
Definition: mavros_uas.h:274
mavros::UAS::time_offset
std::atomic< uint64_t > time_offset
Definition: mavros_uas.h:490
mavros::UAS::diag_updater
diagnostic_updater::Updater diag_updater
Mavros diagnostic updater.
Definition: mavros_uas.h:94
mavros::UAS::get_autopilot
MAV_AUTOPILOT get_autopilot()
Returns autopilot type.
Definition: mavros_uas.h:131
mavros::UAS::imu_ned_data
sensor_msgs::Imu::Ptr imu_ned_data
Definition: mavros_uas.h:482
tf2_ros::Buffer
mavros::UAS::set_map_frame_id
void set_map_frame_id(const std::string frame_id)
Definition: mavros_uas.h:453
mavros::UAS::update_connection_status
void update_connection_status(bool conn_)
Definition: uas_data.cpp:67
mavros::UAS::add_static_transform
void add_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr, std::vector< geometry_msgs::TransformStamped > &vector)
Add static transform. To publish all static transforms at once, we stack them in a std::vector.
Definition: uas_data.cpp:249
mavros::UAS::get_odom_frame_id
std::string get_odom_frame_id()
Definition: mavros_uas.h:459
mavconn::MAVConnInterface::Ptr
std::shared_ptr< MAVConnInterface > Ptr
mavros::UAS::get_attitude_imu_enu
sensor_msgs::Imu::Ptr get_attitude_imu_enu()
Get IMU data [ENU].
Definition: uas_data.cpp:148
mavros::UAS::gps_epv
float gps_epv
Definition: mavros_uas.h:486
mavros::UAS::base_link_frame_id
std::string base_link_frame_id
Definition: mavros_uas.h:496
mavros::UAS::ConnectionCb
std::function< void(bool)> ConnectionCb
Definition: mavros_uas.h:78
mavros::UAS::get_hil_state
bool get_hil_state()
Returns HIL status.
Definition: mavros_uas.h:149
mavros::UAS::set_base_link_frame_id
void set_base_link_frame_id(const std::string frame_id)
Definition: mavros_uas.h:447
mavros::UAS::imu_enu_data
sensor_msgs::Imu::Ptr imu_enu_data
Definition: mavros_uas.h:481
mavros::UAS::gps_satellites_visible
int gps_satellites_visible
Definition: mavros_uas.h:488
mavros::UAS::is_px4
bool is_px4()
Check that FCU is PX4.
Definition: mavros_uas.h:417
mavros::UAS::get_attitude_angular_velocity_enu
geometry_msgs::Vector3 get_attitude_angular_velocity_enu()
Get angular velocity from IMU data.
Definition: uas_data.cpp:186
mavros
Definition: frame_tf.h:34
transform_listener.h
mavros::UAS::get_base_link_frame_id
std::string get_base_link_frame_id()
Definition: mavros_uas.h:456
mavros::UAS::update_capabilities
void update_capabilities(bool known, uint64_t caps=0)
Update the capabilities if they've changed every VERSION/timeout.
Definition: uas_data.cpp:104
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::map_frame_id
std::string map_frame_id
Definition: mavros_uas.h:496
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
ros::Time
mavros::UAS::get_tgt_system
uint8_t get_tgt_system()
Return communication target system.
Definition: mavros_uas.h:159
mavros::UAS::str_mode_v10
std::string str_mode_v10(uint8_t base_mode, uint32_t custom_mode)
Represent FCU mode as string.
Definition: uas_stringify.cpp:189
mavros::UAS::synchronise_stamp
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Compute FCU message time from time_boot_ms or time_usec field.
Definition: uas_timesync.cpp:32
mavros::UAS::is_connected
bool is_connected()
Return connection status.
Definition: mavros_uas.h:99
tf2_ros::TransformBroadcaster
mavros::UAS::MAV_TYPE
mavlink::minimal::MAV_TYPE MAV_TYPE
Definition: mavros_uas.h:70
mavros::UAS::target_component
uint8_t target_component
Definition: mavros_uas.h:475
mavros::UAS::publish_static_transform
void publish_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr)
Publishes static transform.
Definition: uas_data.cpp:262
static_transform_broadcaster.h
mavros::UAS::setup_static_tf
void setup_static_tf()
Publish helper TFs used for frame transformation in the odometry plugin.
Definition: uas_data.cpp:275
mavros::UAS::MAV_MODE_FLAG
mavlink::minimal::MAV_MODE_FLAG MAV_MODE_FLAG
Definition: mavros_uas.h:72
frame_tf.h
Frame transformation utilities.
mavros::UAS::set_time_offset
void set_time_offset(uint64_t offset_ns)
Definition: mavros_uas.h:299
mavros::UAS::fcu_caps_known
std::atomic< bool > fcu_caps_known
Definition: mavros_uas.h:493
mavros::UAS::add_capabilities_change_handler
void add_capabilities_change_handler(CapabilitiesCb cb)
Adds a function to the capabilities callback queue.
Definition: uas_data.cpp:128
mavros::UAS::egm96_5
std::shared_ptr< GeographicLib::Geoid > egm96_5
Geoid dataset used to convert between AMSL and WGS-84.
Definition: mavros_uas.h:243
interface.h
mavros::utils::enum_value
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
mavros::UAS::set_timesync_mode
void set_timesync_mode(timesync_mode mode)
Definition: mavros_uas.h:307
mavros::UAS::update_heartbeat
void update_heartbeat(uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
Definition: uas_data.cpp:60
mavros::UAS::UAS
UAS()
Definition: uas_data.cpp:24
mavros::UAS::get_type
MAV_TYPE get_type()
Returns vehicle type.
Definition: mavros_uas.h:123
mavros::UAS::set_tgt
void set_tgt(uint8_t sys, uint8_t comp)
Definition: mavros_uas.h:170
mavros::UAS::MAV_STATE
mavlink::minimal::MAV_STATE MAV_STATE
Definition: mavros_uas.h:73
mavros::UAS::tf2_static_broadcaster
tf2_ros::StaticTransformBroadcaster tf2_static_broadcaster
Definition: mavros_uas.h:276
mavros::UAS::lock_guard
std::lock_guard< std::recursive_mutex > lock_guard
Definition: mavros_uas.h:80
mavros::UAS::unique_lock
std::unique_lock< std::recursive_mutex > unique_lock
Definition: mavros_uas.h:81
mavros::UAS::CapabilitiesCb
std::function< void(MAV_CAP)> CapabilitiesCb
Definition: mavros_uas.h:79
mavros::UAS::get_attitude_angular_velocity_ned
geometry_msgs::Vector3 get_attitude_angular_velocity_ned()
Get angular velocity from IMU data.
Definition: uas_data.cpp:199
mavros::UAS::get_gps_fix
sensor_msgs::NavSatFix::Ptr get_gps_fix()
Retunrs last GPS RAW message.
Definition: uas_data.cpp:240
mavros::UAS::gps_eph
float gps_eph
Definition: mavros_uas.h:485


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