ROS Imu
message (MessageType::ROS_IMU, version 1.0).
Per the ROS IMU message specification:
- If the a value is known but its covariance is not, its covariance matrix will be set to 0.0
- If a value is not known or not available, its covariance matrix will be set to -1.0
- The value itself will be set to
NAN
, as this is not specified in the ROS message definition
Note that the ROS IMU message does not use NAN
in the covariance matrix to represent either data or covariance not known.
See http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html.
- Note
- The data contained in this message has been corrected for accelerometer and gyro biases and scale factors, and has been rotated into the vehicle body frame from the original IMU orientation using the FusionEngine sensor calibration data.
Definition at line 269 of file ros.h.
|
double | acceleration_covariance [9] = {-1, -1, -1, -1, -1, -1, -1, -1, -1} |
| Vehicle x/y/z acceleration covariance matrix. More...
|
|
double | acceleration_mps2 [3] = {NAN, NAN, NAN} |
| Vehicle x/y/z linear acceleration (in meters/second^2), resolved in the body frame. More...
|
|
double | angular_velocity_covariance [9] = {-1, -1, -1, -1, -1, -1, -1, -1, -1} |
| Vehicle rate of rotation covariance matrix. More...
|
|
double | angular_velocity_rps [3] = {NAN, NAN, NAN} |
| Vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame. More...
|
|
double | orientation [4] = {NAN, NAN, NAN, NAN} |
| The platform body orientation with respect to the local ENU frame, represented as a quaternion with the scalar component last (x, y, z, w). More...
|
|
double | orientation_covariance [9] = {-1, -1, -1, -1, -1, -1, -1, -1, -1} |
| Orientation covariance matrix. More...
|
|
Timestamp | p1_time |
| The time of the message, in P1 time (beginning at power-on). More...
|
|