Mavros IMU
ROS / ros eco / packages / mavros
mavlink messages
- attitude: The attitude in the aeronautical frame (x-front, y-right, z-down).)
- attitude_quaternion: The attitude in the aeronautical frame (q: w, x, y, z)
- highres_imu (105): The IMU readings in SI units in NED body frame
- raw_imu (27): The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging.
- scaled_imu (26): The RAW IMU readings for the usual 9DOF sensor setup.
- scaled_pressure:
ATTITUDE_QUATERNION_COV(61)
This message not use by mavros and Not support by ardupilot
mavlink | mavros topic(message) |
---|---|
ATTITUDE (30) | data (sensor_msgs::msg::Imu) |
ATTITUDE_QUATERNION(31) | data (sensor_msgs::msg::Imu) |
HIGHRES_IMU(105) | data_raw (sensor_msgs::msg::Imu) |
RAW_IMU(27) | data_raw (sensor_msgs::msg::Imu) |
SCALED_IMU(26) | data_raw (sensor_msgs::msg::Imu) |
SCALED_PRESSURE |
Message Topic mapping
there two imu topic and the code map the priorities mavlink message
- ~/data: The topic publish/mapping mavlink
ATTITUDE
orATTITUDE_QUATERNION
if publish by the FCU - ~/data_raw: the topic publish/mapping selected mavlink message with priority
HIGHRES_IMU
orSCALED_IMU
orRAW_IMU
Message priority variables
- has_hr_imu = set to true automaticlay if system send
HIGHRES_IMU
message, disabled handle/publishRAW_IMU
andSCALED_IMU
message. - has_raw_imu = set to true automaticlay if system send
RAW_IMU
message; - has_scaled_imu = set to true automaticlay if system send
SCALED_IMU
message, disabled handle/publishRAW_IMU
message. - has_att_quat : set to true automaticlay if system send
ATTITUDE_QUATERNION
message, disabled handle/publishATTITUDE
message.
data_raw" vs "data
data_raw: Publish only gyro and accelerometer data: Publish Orientation and gyro
ROS Imu msg
sensor_msgs/msg/Imu.msg
Covariance
The message covariance filed by parameters
parameter name | field name |
---|---|
linear_acceleration_stdev | IMU.linear_acceleration_covariance |
angular_velocity_stdev | IMU.angular_velocity_covariance |
orientation_stdev / unk_orientation_cov | IMU.orientation_covariance |
magnetic_stdev | MagneticField.magnetic_field_covariance |
The -1 convention in IMU covariance
Each covariance array (orientation_covariance, angular_velocity_covariance, linear_acceleration_covariance) is a 3×3 matrix stored row-major.
Normally you’d put variances (σ²) on the diagonal.
BUT: If a sensor does not provide that measurement, the convention is to set the first element to -1.
Demo: Attitude message (/mavros/imu/data)
set message stream | |
---|---|
Covariance explain
- orientation_covariance: default orientation_stdev is: 1.0
- angular_velocity_covariance: default angular_velocity_stdev: 0.02*(pi/180)
- linear_acceleration_covariance: -1 , no orientation sensor data
calculate variance from angular_velocity_stdev parameter
\[0.02^\circ = 0.02 \times \frac{\pi}{180} = 0.00034906585 \ \text{rad/s}$$
**Variance = (stdev)²**
$$\sigma^2 = (0.00034906585)^2
= 1.21846968 \times 10^{-7} \ (\text{rad/s})^2\]
Demo: scaled_imu message (/mavros/imu/data_raw)
set message stream | |
---|---|
Covariance explain
- orientation_covariance: -1 , no orientation sensor data
- angular_velocity_covariance: like
data
message - linear_acceleration_covariance: default value 0.0003 is
9e-8