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
60 PluginBase::initialize(uas_);
62 double linear_stdev, angular_stdev, orientation_stdev, mag_stdev;
71 imu_nh.
param(
"linear_acceleration_stdev", linear_stdev, 0.0003);
72 imu_nh.
param(
"angular_velocity_stdev", angular_stdev, 0.02 * (M_PI / 180.0));
73 imu_nh.
param(
"orientation_stdev", orientation_stdev, 1.0);
143 double sr = stdev * stdev;
144 c.diagonal() << sr, sr, sr;
160 Eigen::Quaterniond &orientation_ned, Eigen::Vector3d &gyro_flu, Eigen::Vector3d &gyro_frd)
162 auto imu_ned_msg = boost::make_shared<sensor_msgs::Imu>();
163 auto imu_enu_msg = boost::make_shared<sensor_msgs::Imu>();
221 Eigen::Vector3d &accel_flu, Eigen::Vector3d &accel_frd)
223 auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
226 imu_msg->header = header;
232 linear_accel_vec_flu = accel_flu;
233 linear_accel_vec_frd = accel_frd;
248 void publish_mag(std_msgs::Header &header, Eigen::Vector3d &mag_field)
250 auto magn_msg = boost::make_shared<sensor_msgs::MagneticField>();
253 magn_msg->header = header;
270 void handle_attitude(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE &att)
286 auto gyro_frd = Eigen::Vector3d(att.rollspeed, att.pitchspeed, att.yawspeed);
306 publish_imu_data(att.time_boot_ms, enu_baselink_orientation, ned_aircraft_orientation, gyro_flu, gyro_frd);
324 auto ned_aircraft_orientation = Eigen::Quaterniond(att_q.q1, att_q.q2, att_q.q3, att_q.q4);
331 auto gyro_frd = Eigen::Vector3d(att_q.rollspeed, att_q.pitchspeed, att_q.yawspeed);
348 publish_imu_data(att_q.time_boot_ms, enu_baselink_orientation, ned_aircraft_orientation, gyro_flu, gyro_frd);
357 void handle_highres_imu(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIGHRES_IMU &imu_hr)
371 if (imu_hr.fields_updated & ((7 << 3) | (7 << 0))) {
374 auto accel_frd = Eigen::Vector3d(imu_hr.xacc, imu_hr.yacc, imu_hr.zacc);
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);
397 if (imu_hr.fields_updated & (1 << 9)) {
398 auto static_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
400 static_pressure_msg->header =
header;
401 static_pressure_msg->fluid_pressure = imu_hr.abs_pressure;
403 static_press_pub.
publish(static_pressure_msg);
411 if (imu_hr.fields_updated & (1 << 10)) {
412 auto differential_pressure_msg = boost::make_shared<sensor_msgs::FluidPressure>();
414 differential_pressure_msg->header =
header;
415 differential_pressure_msg->fluid_pressure = imu_hr.diff_pressure;
417 diff_press_pub.
publish(differential_pressure_msg);
425 if (imu_hr.fields_updated & (1 << 12)) {
426 auto temp_msg = boost::make_shared<sensor_msgs::Temperature>();
428 temp_msg->header =
header;
429 temp_msg->temperature = imu_hr.temperature;
431 temp_imu_pub.
publish(temp_msg);
442 void handle_raw_imu(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::RAW_IMU &imu_raw)
447 if (has_hr_imu || has_scaled_imu)
450 auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
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);
473 linear_accel_vec_flu.setZero();
474 linear_accel_vec_frd.setZero();
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);
494 void handle_scaled_imu(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::SCALED_IMU &imu_raw)
500 has_scaled_imu =
true;
502 auto imu_msg = boost::make_shared<sensor_msgs::Imu>();
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);
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);
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);
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);
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);
554 has_scaled_imu =
false;
555 has_att_quat =
false;
ros::Publisher diff_press_pub
MAVROS Plugin base class.
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.
#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.
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
IMU and attitude data publication plugin.
Eigen::Vector3d linear_accel_vec_flu
ftf::Covariance3d magnetic_cov
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.
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.
ros::Publisher imu_raw_pub
void connection_cb(bool connected) override
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.
PluginBase()
Plugin constructor Should not do anything before initialize()
void update_attitude_imu_enu(sensor_msgs::Imu::Ptr &imu)
Store IMU data [ENU].
ftf::Covariance3d angular_velocity_cov
ftf::Covariance3d linear_acceleration_cov
T transform_frame_aircraft_baselink(const T &in)
Transform data expressed in Aircraft frame to Baselink frame.
ftf::Covariance3d unk_orientation_cov
EIGEN_MAKE_ALIGNED_OPERATOR_NEW IMUPlugin()
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool is_ardupilotmega()
Check that FCU is APM.
ros::Publisher temp_baro_pub
static constexpr double MILLIG_TO_MS2
millG to m/s**2 coeff
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
Eigen::Vector3d linear_accel_vec_frd
Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapCovariance3d
Eigen::Map for Covariance3d.
void publish_mag(std_msgs::Header &header, Eigen::Vector3d &mag_field)
Publish magnetic field data.
sensor_msgs::Imu::_angular_velocity_covariance_type Covariance3d
Type matching rosmsg for 3x3 covariance matrix.
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...
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.
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.
void enable_connection_cb()
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
ros::Publisher static_press_pub
ftf::Covariance3d orientation_cov
T transform_orientation_ned_enu(const T &in)
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame...
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.
void setup_covariance(ftf::Covariance3d &cov, double stdev)
Setup 3x3 covariance matrix.
void update_attitude_imu_ned(sensor_msgs::Imu::Ptr &imu)
Store IMU data [NED].
static constexpr double MILLIT_TO_TESLA
millTesla to Tesla coeff
void initialize(UAS &uas_)
Plugin initializer.
T transform_orientation_aircraft_baselink(const T &in)
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame...
ros::Publisher temp_imu_pub
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool is_px4()
Check that FCU is PX4.
static constexpr double MILLIRS_TO_RADSEC
millRad/Sec to Rad/Sec coeff
static constexpr double RAD_TO_DEG
Radians to degrees.
static constexpr double MILLIBAR_TO_PASCAL
millBar to Pascal coeff
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.
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)