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>
28 namespace std_plugins {
48 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 PluginBase::initialize(uas_);
65 double linear_stdev, angular_stdev, orientation_stdev, mag_stdev;
74 imu_nh.
param(
"linear_acceleration_stdev", linear_stdev, 0.0003);
75 imu_nh.
param(
"angular_velocity_stdev", angular_stdev, 0.02 * (M_PI / 180.0));
76 imu_nh.
param(
"orientation_stdev", orientation_stdev, 1.0);
147 double sr = stdev * stdev;
148 c.diagonal() << sr, sr, sr;
164 Eigen::Quaterniond &orientation_ned, Eigen::Vector3d &gyro_flu, Eigen::Vector3d &gyro_frd)
166 auto imu_ned_msg = boost::make_shared<sensor_msgs::Imu>();
167 auto imu_enu_msg = boost::make_shared<sensor_msgs::Imu>();
197 imu_enu_msg->linear_acceleration_covariance[0] = -1;
198 imu_ned_msg->linear_acceleration_covariance[0] = -1;
231 Eigen::Vector3d &accel_flu, Eigen::Vector3d &accel_frd)
233 auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
259 void publish_mag(std_msgs::Header &header, Eigen::Vector3d &mag_field)
261 auto magn_msg = boost::make_shared<sensor_msgs::MagneticField>();
264 magn_msg->header =
header;
281 void handle_attitude(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE &att)
297 auto gyro_frd = Eigen::Vector3d(att.rollspeed, att.pitchspeed, att.yawspeed);
317 publish_imu_data(att.time_boot_ms, enu_baselink_orientation, ned_aircraft_orientation, gyro_flu, gyro_frd);
335 auto ned_aircraft_orientation = Eigen::Quaterniond(att_q.q1, att_q.q2, att_q.q3, att_q.q4);
342 auto gyro_frd = Eigen::Vector3d(att_q.rollspeed, att_q.pitchspeed, att_q.yawspeed);
359 publish_imu_data(att_q.time_boot_ms, enu_baselink_orientation, ned_aircraft_orientation, gyro_flu, gyro_frd);
368 void handle_highres_imu(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIGHRES_IMU &imu_hr)
382 if (imu_hr.fields_updated & ((7 << 3) | (7 << 0))) {
385 auto accel_frd = Eigen::Vector3d(imu_hr.xacc, imu_hr.yacc, imu_hr.zacc);
396 if (imu_hr.fields_updated & (7 << 6)) {
397 auto mag_field = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
398 Eigen::Vector3d(imu_hr.xmag, imu_hr.ymag, imu_hr.zmag) *
GAUSS_TO_TESLA);
408 if (imu_hr.fields_updated & (1 << 9)) {
409 auto static_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
411 static_pressure_msg->header =
header;
412 static_pressure_msg->fluid_pressure = imu_hr.abs_pressure;
422 if (imu_hr.fields_updated & (1 << 10)) {
423 auto differential_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
425 differential_pressure_msg->header =
header;
426 differential_pressure_msg->fluid_pressure = imu_hr.diff_pressure;
436 if (imu_hr.fields_updated & (1 << 12)) {
437 auto temp_msg = boost::make_shared<sensor_msgs::Temperature>();
439 temp_msg->header =
header;
440 temp_msg->temperature = imu_hr.temperature;
453 void handle_raw_imu(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::RAW_IMU &imu_raw)
461 auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
466 auto gyro_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
467 Eigen::Vector3d(imu_raw.xgyro, imu_raw.ygyro, imu_raw.zgyro) *
MILLIRS_TO_RADSEC);
468 auto accel_frd = Eigen::Vector3d(imu_raw.xacc, imu_raw.yacc, imu_raw.zacc);
469 auto accel_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(accel_frd);
492 auto mag_field = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
493 Eigen::Vector3d(imu_raw.xmag, imu_raw.ymag, imu_raw.zmag) *
MILLIT_TO_TESLA);
505 void handle_scaled_imu(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::SCALED_IMU &imu_raw)
513 auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
516 auto gyro_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
517 Eigen::Vector3d(imu_raw.xgyro, imu_raw.ygyro, imu_raw.zgyro) *
MILLIRS_TO_RADSEC);
518 auto accel_frd = Eigen::Vector3d(Eigen::Vector3d(imu_raw.xacc, imu_raw.yacc, imu_raw.zacc) *
MILLIG_TO_MS2);
519 auto accel_flu = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(accel_frd);
526 auto mag_field = ftf::transform_frame_aircraft_baselink<Eigen::Vector3d>(
527 Eigen::Vector3d(imu_raw.xmag, imu_raw.ymag, imu_raw.zmag) *
MILLIT_TO_TESLA);
545 auto temp_msg = boost::make_shared<sensor_msgs::Temperature>();
546 temp_msg->header =
header;
547 temp_msg->temperature = press.temperature / 100.0;
550 auto static_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
551 static_pressure_msg->header =
header;
552 static_pressure_msg->fluid_pressure = press.press_abs * 100.0;
555 auto differential_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
556 differential_pressure_msg->header =
header;
557 differential_pressure_msg->fluid_pressure = press.press_diff * 100.0;