imu.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2013-2017 Vladimir Ermakov.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <cmath>
18 #include <mavros/mavros_plugin.h>
20 
21 #include <sensor_msgs/Imu.h>
22 #include <sensor_msgs/MagneticField.h>
23 #include <sensor_msgs/Temperature.h>
24 #include <sensor_msgs/FluidPressure.h>
25 #include <geometry_msgs/Vector3.h>
26 
27 namespace mavros {
28 namespace std_plugins {
30 static constexpr double GAUSS_TO_TESLA = 1.0e-4;
32 static constexpr double MILLIT_TO_TESLA = 1000.0;
34 static constexpr double MILLIRS_TO_RADSEC = 1.0e-3;
36 static constexpr double MILLIG_TO_MS2 = 9.80665 / 1000.0;
38 static constexpr double MILLIMS2_TO_MS2 = 1.0e-3;
40 static constexpr double MILLIBAR_TO_PASCAL = 1.0e2;
42 static constexpr double RAD_TO_DEG = 180.0 / M_PI;
43 
44 
46 class IMUPlugin : public plugin::PluginBase {
47 public:
48  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49 
51  imu_nh("~imu"),
52  has_hr_imu(false),
53  has_raw_imu(false),
54  has_scaled_imu(false),
55  has_att_quat(false)
56  { }
57 
58  void initialize(UAS &uas_)
59  {
60  PluginBase::initialize(uas_);
61 
62  double linear_stdev, angular_stdev, orientation_stdev, mag_stdev;
63 
70  imu_nh.param<std::string>("frame_id", frame_id, "base_link");
71  imu_nh.param("linear_acceleration_stdev", linear_stdev, 0.0003); // check default by MPU6000 spec
72  imu_nh.param("angular_velocity_stdev", angular_stdev, 0.02 * (M_PI / 180.0)); // check default by MPU6000 spec
73  imu_nh.param("orientation_stdev", orientation_stdev, 1.0);
74  imu_nh.param("magnetic_stdev", mag_stdev, 0.0);
75 
77  setup_covariance(angular_velocity_cov, angular_stdev);
78  setup_covariance(orientation_cov, orientation_stdev);
79  setup_covariance(magnetic_cov, mag_stdev);
81 
82  imu_pub = imu_nh.advertise<sensor_msgs::Imu>("data", 10);
83  magn_pub = imu_nh.advertise<sensor_msgs::MagneticField>("mag", 10);
84  temp_imu_pub = imu_nh.advertise<sensor_msgs::Temperature>("temperature_imu", 10);
85  temp_baro_pub = imu_nh.advertise<sensor_msgs::Temperature>("temperature_baro", 10);
86  static_press_pub = imu_nh.advertise<sensor_msgs::FluidPressure>("static_pressure", 10);
87  diff_press_pub = imu_nh.advertise<sensor_msgs::FluidPressure>("diff_pressure", 10);
88  imu_raw_pub = imu_nh.advertise<sensor_msgs::Imu>("data_raw", 10);
89 
90  // Reset has_* flags on connection change
92  }
93 
95  return {
102  };
103  }
104 
105 private:
107  std::string frame_id;
108 
116 
121  Eigen::Vector3d linear_accel_vec_flu;
122  Eigen::Vector3d linear_accel_vec_frd;
128 
129  /* -*- helpers -*- */
130 
137  void setup_covariance(ftf::Covariance3d &cov, double stdev)
138  {
139  ftf::EigenMapCovariance3d c(cov.data());
140 
141  c.setZero();
142  if (stdev) {
143  double sr = stdev * stdev;
144  c.diagonal() << sr, sr, sr;
145  }
146  else {
147  c(0,0) = -1.0;
148  }
149  }
150 
159  void publish_imu_data(uint32_t time_boot_ms, Eigen::Quaterniond &orientation_enu,
160  Eigen::Quaterniond &orientation_ned, Eigen::Vector3d &gyro_flu, Eigen::Vector3d &gyro_frd)
161  {
162  auto imu_ned_msg = boost::make_shared<sensor_msgs::Imu>();
163  auto imu_enu_msg = boost::make_shared<sensor_msgs::Imu>();
164 
165  // Fill message header
166  imu_enu_msg->header = m_uas->synchronized_header(frame_id, time_boot_ms);
167  imu_ned_msg->header = m_uas->synchronized_header("aircraft", time_boot_ms);
168 
169  // Convert from Eigen::Quaternond to geometry_msgs::Quaternion
170  tf::quaternionEigenToMsg(orientation_enu, imu_enu_msg->orientation);
171  tf::quaternionEigenToMsg(orientation_ned, imu_ned_msg->orientation);
172 
173  // Convert from Eigen::Vector3d to geometry_msgs::Vector3
174  tf::vectorEigenToMsg(gyro_flu, imu_enu_msg->angular_velocity);
175  tf::vectorEigenToMsg(gyro_frd, imu_ned_msg->angular_velocity);
176 
177  // Eigen::Vector3d from HIGHRES_IMU or RAW_IMU, to geometry_msgs::Vector3
178  tf::vectorEigenToMsg(linear_accel_vec_flu, imu_enu_msg->linear_acceleration);
179  tf::vectorEigenToMsg(linear_accel_vec_frd, imu_ned_msg->linear_acceleration);
180 
181  // Pass ENU msg covariances
182  imu_enu_msg->orientation_covariance = orientation_cov;
183  imu_enu_msg->angular_velocity_covariance = angular_velocity_cov;
184  imu_enu_msg->linear_acceleration_covariance = linear_acceleration_cov;
185 
186  // Pass NED msg covariances
187  imu_ned_msg->orientation_covariance = orientation_cov;
188  imu_ned_msg->angular_velocity_covariance = angular_velocity_cov;
189  imu_ned_msg->linear_acceleration_covariance = linear_acceleration_cov;
190 
194  // [store_enu]
195  m_uas->update_attitude_imu_enu(imu_enu_msg);
196  // [store_enu]
197 
201  // [store_enu]
202  m_uas->update_attitude_imu_ned(imu_ned_msg);
203  // [store_ned]
204 
208  // [pub_enu]
209  imu_pub.publish(imu_enu_msg);
210  // [pub_enu]
211  }
212 
220  void publish_imu_data_raw(std_msgs::Header &header, Eigen::Vector3d &gyro_flu,
221  Eigen::Vector3d &accel_flu, Eigen::Vector3d &accel_frd)
222  {
223  auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
224 
225  // Fill message header
226  imu_msg->header = header;
227 
228  tf::vectorEigenToMsg(gyro_flu, imu_msg->angular_velocity);
229  tf::vectorEigenToMsg(accel_flu, imu_msg->linear_acceleration);
230 
231  // Save readings
232  linear_accel_vec_flu = accel_flu;
233  linear_accel_vec_frd = accel_frd;
234 
235  imu_msg->orientation_covariance = unk_orientation_cov;
236  imu_msg->angular_velocity_covariance = angular_velocity_cov;
237  imu_msg->linear_acceleration_covariance = linear_acceleration_cov;
238 
239  // Publish message [ENU frame]
240  imu_raw_pub.publish(imu_msg);
241  }
242 
248  void publish_mag(std_msgs::Header &header, Eigen::Vector3d &mag_field)
249  {
250  auto magn_msg = boost::make_shared<sensor_msgs::MagneticField>();
251 
252  // Fill message header
253  magn_msg->header = header;
254 
255  tf::vectorEigenToMsg(mag_field, magn_msg->magnetic_field);
256  magn_msg->magnetic_field_covariance = magnetic_cov;
257 
258  // Publish message [ENU frame]
259  magn_pub.publish(magn_msg);
260  }
261 
262  /* -*- message handlers -*- */
263 
270  void handle_attitude(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE &att)
271  {
272  if (has_att_quat)
273  return;
274 
278  // [ned_aircraft_orient1]
279  auto ned_aircraft_orientation = ftf::quaternion_from_rpy(att.roll, att.pitch, att.yaw);
280  // [ned_aircraft_orient1]
281 
285  // [frd_ang_vel1]
286  auto gyro_frd = Eigen::Vector3d(att.rollspeed, att.pitchspeed, att.yawspeed);
287  // [frd_ang_vel1]
288 
293  // [ned->baselink->enu]
294  auto enu_baselink_orientation = ftf::transform_orientation_aircraft_baselink(
295  ftf::transform_orientation_ned_enu(ned_aircraft_orientation));
296  // [ned->baselink->enu]
297 
302  // [rotate_gyro]
303  auto gyro_flu = ftf::transform_frame_aircraft_baselink(gyro_frd);
304  // [rotate_gyro]
305 
306  publish_imu_data(att.time_boot_ms, enu_baselink_orientation, ned_aircraft_orientation, gyro_flu, gyro_frd);
307  }
308 
315  void handle_attitude_quaternion(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE_QUATERNION &att_q)
316  {
317  ROS_INFO_COND_NAMED(!has_att_quat, "imu", "IMU: Attitude quaternion IMU detected!");
318  has_att_quat = true;
319 
323  // [ned_aircraft_orient2]
324  auto ned_aircraft_orientation = Eigen::Quaterniond(att_q.q1, att_q.q2, att_q.q3, att_q.q4);
325  // [ned_aircraft_orient2]
326 
330  // [frd_ang_vel2]
331  auto gyro_frd = Eigen::Vector3d(att_q.rollspeed, att_q.pitchspeed, att_q.yawspeed);
332  // [frd_ang_vel2]
333 
339  auto enu_baselink_orientation = ftf::transform_orientation_aircraft_baselink(
340  ftf::transform_orientation_ned_enu(ned_aircraft_orientation));
341 
346  auto gyro_flu = ftf::transform_frame_aircraft_baselink(gyro_frd);
347 
348  publish_imu_data(att_q.time_boot_ms, enu_baselink_orientation, ned_aircraft_orientation, gyro_flu, gyro_frd);
349  }
350 
357  void handle_highres_imu(const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIGHRES_IMU &imu_hr)
358  {
359  ROS_INFO_COND_NAMED(!has_hr_imu, "imu", "IMU: High resolution IMU detected!");
360  has_hr_imu = true;
361 
362  auto header = m_uas->synchronized_header(frame_id, imu_hr.time_usec);
370  // [accel_available]
371  if (imu_hr.fields_updated & ((7 << 3) | (7 << 0))) {
372  auto gyro_flu = ftf::transform_frame_aircraft_baselink(Eigen::Vector3d(imu_hr.xgyro, imu_hr.ygyro, imu_hr.zgyro));
373 
374  auto accel_frd = Eigen::Vector3d(imu_hr.xacc, imu_hr.yacc, imu_hr.zacc);
375  auto accel_flu = ftf::transform_frame_aircraft_baselink(accel_frd);
376 
377  publish_imu_data_raw(header, gyro_flu, accel_flu, accel_frd);
378  }
379  // [accel_available]
380 
384  // [mag_available]
385  if (imu_hr.fields_updated & (7 << 6)) {
386  auto mag_field = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
387  Eigen::Vector3d(imu_hr.xmag, imu_hr.ymag, imu_hr.zmag) * GAUSS_TO_TESLA);
388 
390  }
391  // [mag_available]
392 
396  // [static_pressure_available]
397  if (imu_hr.fields_updated & (1 << 9)) {
398  auto static_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
399 
400  static_pressure_msg->header = header;
401  static_pressure_msg->fluid_pressure = imu_hr.abs_pressure;
402 
403  static_press_pub.publish(static_pressure_msg);
404  }
405  // [static_pressure_available]
406 
410  // [differential_pressure_available]
411  if (imu_hr.fields_updated & (1 << 10)) {
412  auto differential_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
413 
414  differential_pressure_msg->header = header;
415  differential_pressure_msg->fluid_pressure = imu_hr.diff_pressure;
416 
417  diff_press_pub.publish(differential_pressure_msg);
418  }
419  // [differential_pressure_available]
420 
424  // [temperature_available]
425  if (imu_hr.fields_updated & (1 << 12)) {
426  auto temp_msg = boost::make_shared<sensor_msgs::Temperature>();
427 
428  temp_msg->header = header;
429  temp_msg->temperature = imu_hr.temperature;
430 
431  temp_imu_pub.publish(temp_msg);
432  }
433  // [temperature_available]
434  }
435 
442  void handle_raw_imu(const mavlink::mavlink_message_t *msg, mavlink::common::msg::RAW_IMU &imu_raw)
443  {
444  ROS_INFO_COND_NAMED(!has_raw_imu, "imu", "IMU: Raw IMU message used.");
445  has_raw_imu = true;
446 
447  if (has_hr_imu || has_scaled_imu)
448  return;
449 
450  auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
451  auto header = m_uas->synchronized_header(frame_id, imu_raw.time_usec);
452 
455  auto gyro_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
456  Eigen::Vector3d(imu_raw.xgyro, imu_raw.ygyro, imu_raw.zgyro) * MILLIRS_TO_RADSEC);
457  auto accel_frd = Eigen::Vector3d(imu_raw.xacc, imu_raw.yacc, imu_raw.zacc);
458  auto accel_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(accel_frd);
459 
460  if (m_uas->is_ardupilotmega()) {
461  accel_frd *= MILLIG_TO_MS2;
462  accel_flu *= MILLIG_TO_MS2;
463  } else if (m_uas->is_px4()) {
464  accel_frd *= MILLIMS2_TO_MS2;
465  accel_flu *= MILLIMS2_TO_MS2;
466  }
467 
468  publish_imu_data_raw(header, gyro_flu, accel_flu, accel_frd);
469 
470  if (!m_uas->is_ardupilotmega()) {
471  ROS_WARN_THROTTLE_NAMED(60, "imu", "IMU: linear acceleration on RAW_IMU known on APM only.");
472  ROS_WARN_THROTTLE_NAMED(60, "imu", "IMU: ~imu/data_raw stores unscaled raw acceleration report.");
473  linear_accel_vec_flu.setZero();
474  linear_accel_vec_frd.setZero();
475  }
476 
480  // [mag_field]
481  auto mag_field = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
482  Eigen::Vector3d(imu_raw.xmag, imu_raw.ymag, imu_raw.zmag) * MILLIT_TO_TESLA);
483  // [mag_field]
484 
485  publish_mag(header, mag_field);
486  }
487 
494  void handle_scaled_imu(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SCALED_IMU &imu_raw)
495  {
496  if (has_hr_imu)
497  return;
498 
499  ROS_INFO_COND_NAMED(!has_scaled_imu, "imu", "IMU: Scaled IMU message used.");
500  has_scaled_imu = true;
501 
502  auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
503  auto header = m_uas->synchronized_header(frame_id, imu_raw.time_boot_ms);
504 
505  auto gyro_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
506  Eigen::Vector3d(imu_raw.xgyro, imu_raw.ygyro, imu_raw.zgyro) * MILLIRS_TO_RADSEC);
507  auto accel_frd = Eigen::Vector3d(Eigen::Vector3d(imu_raw.xacc, imu_raw.yacc, imu_raw.zacc) * MILLIG_TO_MS2);
508  auto accel_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(accel_frd);
509 
510  publish_imu_data_raw(header, gyro_flu, accel_flu, accel_frd);
511 
515  auto mag_field = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
516  Eigen::Vector3d(imu_raw.xmag, imu_raw.ymag, imu_raw.zmag) * MILLIT_TO_TESLA);
517 
518  publish_mag(header, mag_field);
519  }
520 
527  void handle_scaled_pressure(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SCALED_PRESSURE &press)
528  {
529  if (has_hr_imu)
530  return;
531 
532  auto header = m_uas->synchronized_header(frame_id, press.time_boot_ms);
533 
534  auto temp_msg = boost::make_shared<sensor_msgs::Temperature>();
535  temp_msg->header = header;
536  temp_msg->temperature = press.temperature / 100.0;
537  temp_baro_pub.publish(temp_msg);
538 
539  auto static_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
540  static_pressure_msg->header = header;
541  static_pressure_msg->fluid_pressure = press.press_abs * 100.0;
542  static_press_pub.publish(static_pressure_msg);
543 
544  auto differential_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
545  differential_pressure_msg->header = header;
546  differential_pressure_msg->fluid_pressure = press.press_diff * 100.0;
547  diff_press_pub.publish(differential_pressure_msg);
548  }
549 
550  // Checks for connection and overrides variable values
551  void connection_cb(bool connected) override
552  {
553  has_hr_imu = false;
554  has_scaled_imu = false;
555  has_att_quat = false;
556  }
557 };
558 } // namespace std_plugins
559 } // namespace mavros
560 
ros::Publisher diff_press_pub
Definition: imu.cpp:115
MAVROS Plugin base class.
Definition: mavros_plugin.h:37
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
#define ROS_INFO_COND_NAMED(cond, name,...)
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
void publish(const boost::shared_ptr< M > &message) const
static constexpr double GAUSS_TO_TESLA
Gauss to Tesla coeff.
Definition: imu.cpp:30
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
MAVROS Plugin base.
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
IMU and attitude data publication plugin.
Definition: imu.cpp:46
Eigen::Vector3d linear_accel_vec_flu
Definition: imu.cpp:121
ftf::Covariance3d magnetic_cov
Definition: imu.cpp:127
void handle_raw_imu(const mavlink::mavlink_message_t *msg, mavlink::common::msg::RAW_IMU &imu_raw)
Handle RAW_IMU MAVlink message. Message specification: https://mavlink.io/en/messages/common.html/#RAW_IMU.
Definition: imu.cpp:442
void publish_imu_data(uint32_t time_boot_ms, Eigen::Quaterniond &orientation_enu, Eigen::Quaterniond &orientation_ned, Eigen::Vector3d &gyro_flu, Eigen::Vector3d &gyro_frd)
Fill and publish IMU data message.
Definition: imu.cpp:159
ros::Publisher imu_raw_pub
Definition: imu.cpp:110
void connection_cb(bool connected) override
Definition: imu.cpp:551
void handle_attitude_quaternion(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE_QUATERNION &att_q)
Handle ATTITUDE_QUATERNION MAVlink message. Message specification: https://mavlink.io/en/messages/common.html/#ATTITUDE_QUATERNION.
Definition: imu.cpp:315
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:75
void update_attitude_imu_enu(sensor_msgs::Imu::Ptr &imu)
Store IMU data [ENU].
Definition: uas_data.cpp:115
ftf::Covariance3d angular_velocity_cov
Definition: imu.cpp:124
ftf::Covariance3d linear_acceleration_cov
Definition: imu.cpp:123
T transform_frame_aircraft_baselink(const T &in)
Transform data expressed in Aircraft frame to Baselink frame.
Definition: frame_tf.h:205
ros::Publisher imu_pub
Definition: imu.cpp:109
UAS for plugins.
Definition: mavros_uas.h:66
ftf::Covariance3d unk_orientation_cov
Definition: imu.cpp:126
EIGEN_MAKE_ALIGNED_OPERATOR_NEW IMUPlugin()
Definition: imu.cpp:50
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
bool is_ardupilotmega()
Check that FCU is APM.
Definition: mavros_uas.h:360
ros::Publisher temp_baro_pub
Definition: imu.cpp:113
static constexpr double MILLIG_TO_MS2
millG to m/s**2 coeff
Definition: imu.cpp:36
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static constexpr double MILLIMS2_TO_MS2
millm/s**2 to m/s**2 coeff
Definition: imu.cpp:38
Eigen::Vector3d linear_accel_vec_frd
Definition: imu.cpp:122
Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapCovariance3d
Eigen::Map for Covariance3d.
Definition: frame_tf.h:46
ros::NodeHandle imu_nh
Definition: imu.cpp:106
void publish_mag(std_msgs::Header &header, Eigen::Vector3d &mag_field)
Publish magnetic field data.
Definition: imu.cpp:248
sensor_msgs::Imu::_angular_velocity_covariance_type Covariance3d
Type matching rosmsg for 3x3 covariance matrix.
Definition: frame_tf.h:37
void handle_scaled_pressure(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SCALED_PRESSURE &press)
Handle SCALED_PRESSURE MAVlink message. Message specification: https://mavlink.io/en/messages/common...
Definition: imu.cpp:527
void publish_imu_data_raw(std_msgs::Header &header, Eigen::Vector3d &gyro_flu, Eigen::Vector3d &accel_flu, Eigen::Vector3d &accel_frd)
Fill and publish IMU data_raw message; store linear acceleration for IMU data.
Definition: imu.cpp:220
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
void handle_attitude(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE &att)
Handle ATTITUDE MAVlink message. Message specification: https://mavlink.io/en/messages/common.html#ATTITUDE.
Definition: imu.cpp:270
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:48
ros::Publisher static_press_pub
Definition: imu.cpp:114
ftf::Covariance3d orientation_cov
Definition: imu.cpp:125
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
void handle_scaled_imu(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SCALED_IMU &imu_raw)
Handle SCALED_IMU MAVlink message. Message specification: https://mavlink.io/en/messages/common.html/#SCALED_IMU.
Definition: imu.cpp:494
void setup_covariance(ftf::Covariance3d &cov, double stdev)
Setup 3x3 covariance matrix.
Definition: imu.cpp:137
const std::string header
void update_attitude_imu_ned(sensor_msgs::Imu::Ptr &imu)
Store IMU data [NED].
Definition: uas_data.cpp:121
static constexpr double MILLIT_TO_TESLA
millTesla to Tesla coeff
Definition: imu.cpp:32
void initialize(UAS &uas_)
Plugin initializer.
Definition: imu.cpp:58
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
ros::Publisher magn_pub
Definition: imu.cpp:111
ros::Publisher temp_imu_pub
Definition: imu.cpp:112
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool is_px4()
Check that FCU is PX4.
Definition: mavros_uas.h:367
static constexpr double MILLIRS_TO_RADSEC
millRad/Sec to Rad/Sec coeff
Definition: imu.cpp:34
static constexpr double RAD_TO_DEG
Radians to degrees.
Definition: imu.cpp:42
static constexpr double MILLIBAR_TO_PASCAL
millBar to Pascal coeff
Definition: imu.cpp:40
void handle_highres_imu(const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIGHRES_IMU &imu_hr)
Handle HIGHRES_IMU MAVlink message. Message specification: https://mavlink.io/en/messages/common.html/#HIGHRES_IMU.
Definition: imu.cpp:357
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
Definition: imu.cpp:94


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