Public Member Functions | Private Member Functions | Private Attributes | List of all members
mavros::std_plugins::IMUPlugin Class Reference

IMU and attitude data publication plugin. More...

Inheritance diagram for mavros::std_plugins::IMUPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions () override
 Return vector of MAVLink message subscriptions (handlers) More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW IMUPlugin ()
 
void initialize (UAS &uas_) override
 Plugin initializer. More...
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void connection_cb (bool connected) override
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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.html/#SCALED_PRESSURE. More...
 
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. More...
 
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. More...
 
void publish_mag (std_msgs::Header &header, Eigen::Vector3d &mag_field)
 Publish magnetic field data. More...
 
void setup_covariance (ftf::Covariance3d &cov, double stdev)
 Setup 3x3 covariance matrix. More...
 

Private Attributes

ftf::Covariance3d angular_velocity_cov
 
ros::Publisher diff_press_pub
 
std::string frame_id
 
bool has_att_quat
 
bool has_hr_imu
 
bool has_raw_imu
 
bool has_scaled_imu
 
ros::NodeHandle imu_nh
 
ros::Publisher imu_pub
 
ros::Publisher imu_raw_pub
 
Eigen::Vector3d linear_accel_vec_flu
 
Eigen::Vector3d linear_accel_vec_frd
 
ftf::Covariance3d linear_acceleration_cov
 
ros::Publisher magn_pub
 
ftf::Covariance3d magnetic_cov
 
ftf::Covariance3d orientation_cov
 
bool received_linear_accel
 
ros::Publisher static_press_pub
 
ros::Publisher temp_baro_pub
 
ros::Publisher temp_imu_pub
 
ftf::Covariance3d unk_orientation_cov
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
using ConstPtr = boost::shared_ptr< PluginBase const >
 
using HandlerCb = mavconn::MAVConnInterface::ReceivedCb
 generic message handler callback More...
 
using HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb >
 Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More...
 
using Ptr = boost::shared_ptr< PluginBase >
 
using Subscriptions = std::vector< HandlerInfo >
 Subscriptions vector. More...
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void capabilities_cb (UAS::MAV_CAP capabilities)
 
void enable_capabilities_cb ()
 
void enable_connection_cb ()
 
template<class _C >
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
template<class _C , class _T >
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 Plugin constructor Should not do anything before initialize() More...
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

IMU and attitude data publication plugin.

Definition at line 46 of file imu.cpp.


The documentation for this class was generated from the following file:


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:50