uas_data.cpp
Go to the documentation of this file.
1 
6 /*
7  * Copyright 2014,2015 Vladimir Ermakov.
8  *
9  * This file is part of the mavros package and subject to the license terms
10  * in the top-level LICENSE file of the mavros repository.
11  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
12  */
13 
14 #include <array>
15 #include <unordered_map>
16 #include <stdexcept>
17 #include <mavros/mavros_uas.h>
18 #include <mavros/utils.h>
19 #include <mavros/px4_custom_mode.h>
20 
21 using namespace mavros;
22 using utils::enum_value;
23 
25  tf2_listener(tf2_buffer, true),
26  type(enum_value(MAV_TYPE::GENERIC)),
27  autopilot(enum_value(MAV_AUTOPILOT::GENERIC)),
28  base_mode(0),
29  target_system(1),
30  target_component(1),
31  connected(false),
32  gps_eph(NAN),
33  gps_epv(NAN),
34  gps_fix_type(0),
35  gps_satellites_visible(0),
36  time_offset(0),
37  tsync_mode(UAS::timesync_mode::NONE),
38  fcu_caps_known(false),
39  fcu_capabilities(0),
40  base_link_frame_id("base_link"),
41  odom_frame_id("odom"),
42  map_frame_id("map")
43 {
44  try {
45  // Using smallest dataset with 5' grid,
46  // From default location,
47  // Use cubic interpolation, Thread safe
48  egm96_5 = std::make_shared<GeographicLib::Geoid>("egm96-5", "", true, true);
49  }
50  catch (const std::exception &e) {
51  // catch exception and shutdown node
52  ROS_FATAL_STREAM("UAS: GeographicLib exception: " << e.what() <<
53  " | Run install_geographiclib_dataset.sh script in order to install Geoid Model dataset!");
54  ros::shutdown();
55  }
56 }
57 
58 /* -*- heartbeat handlers -*- */
59 
60 void UAS::update_heartbeat(uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
61 {
62  type = type_;
63  autopilot = autopilot_;
64  base_mode = base_mode_;
65 }
66 
68 {
69  if (conn_ != connected) {
70  connected = conn_;
71 
72  // call all change cb's
73  for (auto &cb : connection_cb_vec)
74  cb(conn_);
75  }
76 }
77 
79 {
80  lock_guard lock(mutex);
81  connection_cb_vec.push_back(cb);
82 }
83 
84 /* -*- autopilot version -*- */
85 
86 static uint64_t get_default_caps(UAS::MAV_AUTOPILOT ap_type)
87 {
88  // TODO: return default caps mask for known FCU's
89  return 0;
90 }
91 
93 {
94  if (fcu_caps_known) {
95  uint64_t caps = fcu_capabilities;
96  return caps;
97  }
98  else {
100  }
101 }
102 
103 // This function may need a mutex now
104 void UAS::update_capabilities(bool known, uint64_t caps)
105 {
106  bool process_cb_queue = false;
107 
108  if (known != fcu_caps_known) {
109  if (!fcu_caps_known) {
110  process_cb_queue = true;
111  }
112  fcu_caps_known = known;
113  } else if (fcu_caps_known) { // Implies fcu_caps_known == known
114  if (caps != fcu_capabilities) {
115  process_cb_queue = true;
116  }
117  }
118  else {} // Capabilities werent known before and arent known after update
119 
120  if (process_cb_queue) {
121  fcu_capabilities = caps;
122  for (auto &cb : capabilities_cb_vec) {
123  cb(static_cast<MAV_CAP>(caps));
124  }
125  }
126 }
127 
129 {
130  lock_guard lock(mutex);
131  capabilities_cb_vec.push_back(cb);
132 }
133 
134 /* -*- IMU data -*- */
135 
137 {
138  lock_guard lock(mutex);
139  imu_enu_data = imu;
140 }
141 
143 {
144  lock_guard lock(mutex);
145  imu_ned_data = imu;
146 }
147 
149 {
150  lock_guard lock(mutex);
151  return imu_enu_data;
152 }
153 
155 {
156  lock_guard lock(mutex);
157  return imu_ned_data;
158 }
159 
160 geometry_msgs::Quaternion UAS::get_attitude_orientation_enu()
161 {
162  lock_guard lock(mutex);
163  if (imu_enu_data)
164  return imu_enu_data->orientation;
165  else {
166  // fallback - return identity
167  geometry_msgs::Quaternion q;
168  q.w = 1.0; q.x = q.y = q.z = 0.0;
169  return q;
170  }
171 }
172 
173 geometry_msgs::Quaternion UAS::get_attitude_orientation_ned()
174 {
175  lock_guard lock(mutex);
176  if (imu_ned_data)
177  return imu_ned_data->orientation;
178  else {
179  // fallback - return identity
180  geometry_msgs::Quaternion q;
181  q.w = 1.0; q.x = q.y = q.z = 0.0;
182  return q;
183  }
184 }
185 
187 {
188  lock_guard lock(mutex);
189  if (imu_enu_data)
190  return imu_enu_data->angular_velocity;
191  else {
192  // fallback
193  geometry_msgs::Vector3 v;
194  v.x = v.y = v.z = 0.0;
195  return v;
196  }
197 }
198 
200 {
201  lock_guard lock(mutex);
202  if (imu_ned_data)
203  return imu_ned_data->angular_velocity;
204  else {
205  // fallback
206  geometry_msgs::Vector3 v;
207  v.x = v.y = v.z = 0.0;
208  return v;
209  }
210 }
211 
212 
213 /* -*- GPS data -*- */
214 
216  float eph, float epv,
217  int fix_type, int satellites_visible)
218 {
219  lock_guard lock(mutex);
220 
221  gps_fix = fix;
222  gps_eph = eph;
223  gps_epv = epv;
224  gps_fix_type = fix_type;
225  gps_satellites_visible = satellites_visible;
226 }
227 
229 void UAS::get_gps_epts(float &eph, float &epv, int &fix_type, int &satellites_visible)
230 {
231  lock_guard lock(mutex);
232 
233  eph = gps_eph;
234  epv = gps_epv;
235  fix_type = gps_fix_type;
236  satellites_visible = gps_satellites_visible;
237 }
238 
241 {
242  lock_guard lock(mutex);
243  return gps_fix;
244 }
245 
246 /* -*- transform -*- */
247 
249 void UAS::add_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr, std::vector<geometry_msgs::TransformStamped>& vector)
250 {
251  geometry_msgs::TransformStamped static_transform;
252 
253  static_transform.header.stamp = ros::Time::now();
254  static_transform.header.frame_id = frame_id;
255  static_transform.child_frame_id = child_id;
256  tf::transformEigenToMsg(tr, static_transform.transform);
257 
258  vector.emplace_back(static_transform);
259 }
260 
262 void UAS::publish_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr)
263 {
264  geometry_msgs::TransformStamped static_transformStamped;
265 
266  static_transformStamped.header.stamp = ros::Time::now();
267  static_transformStamped.header.frame_id = frame_id;
268  static_transformStamped.child_frame_id = child_id;
269  tf::transformEigenToMsg(tr, static_transformStamped.transform);
270 
271  tf2_static_broadcaster.sendTransform(static_transformStamped);
272 }
273 
276 {
277  std::vector<geometry_msgs::TransformStamped> transform_vector;
278  add_static_transform(map_frame_id, map_frame_id+"_ned", Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, M_PI_2)),transform_vector);
279  add_static_transform(odom_frame_id, odom_frame_id+"_ned", Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, M_PI_2)),transform_vector);
280  add_static_transform(base_link_frame_id, base_link_frame_id+"_frd", Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, 0)),transform_vector);
281  tf2_static_broadcaster.sendTransform(transform_vector);
282 }
tf2_ros::StaticTransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
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::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::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::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
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
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::fcu_capabilities
std::atomic< uint64_t > fcu_capabilities
Definition: mavros_uas.h:494
mavros::UAS::odom_frame_id
std::string odom_frame_id
Definition: mavros_uas.h:496
mavros::UAS::autopilot
std::atomic< uint8_t > autopilot
Definition: mavros_uas.h:471
ros::shutdown
ROSCPP_DECL void shutdown()
mavros::UAS::type
std::atomic< uint8_t > type
Definition: mavros_uas.h:470
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::add_connection_change_handler
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
Definition: uas_data.cpp:78
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
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
mavros::UAS::MAV_AUTOPILOT
mavlink::minimal::MAV_AUTOPILOT MAV_AUTOPILOT
Definition: mavros_uas.h:71
get_default_caps
static uint64_t get_default_caps(UAS::MAV_AUTOPILOT ap_type)
Definition: uas_data.cpp:86
utils.h
some useful utils
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::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
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
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
px4_custom_mode.h
PX4 custom mode constants.
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::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::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
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::MAV_TYPE
mavlink::minimal::MAV_TYPE MAV_TYPE
Definition: mavros_uas.h:70
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
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
tf::transformEigenToMsg
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
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.h
MAVROS Plugin context.
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
mavros::utils::enum_value
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
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::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::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
ros::Time::now
static Time now()
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