From 33fcc864c1ad4c9c6e8b8d5e23d4ead740de6893 Mon Sep 17 00:00:00 2001 From: Tully Foote Date: Fri, 10 Mar 2017 16:16:03 -0800 Subject: [PATCH] Proposed new messages to replace IMU message. From https://groups.google.com/forum/#!topic/ros-sig-drivers/2NvgNBOjcFQ --- sensor_msgs/msg/AngularVelocity.msg | 4 ++++ sensor_msgs/msg/Attitude.msg | 14 ++++++++++++++ sensor_msgs/msg/LinearAcceleration.msg | 3 +++ 3 files changed, 21 insertions(+) create mode 100644 sensor_msgs/msg/AngularVelocity.msg create mode 100644 sensor_msgs/msg/Attitude.msg create mode 100644 sensor_msgs/msg/LinearAcceleration.msg diff --git a/sensor_msgs/msg/AngularVelocity.msg b/sensor_msgs/msg/AngularVelocity.msg new file mode 100644 index 00000000..8ffc2c7c --- /dev/null +++ b/sensor_msgs/msg/AngularVelocity.msg @@ -0,0 +1,4 @@ +std_msgs/Header header + +geometry_msgs/Vector3 angular_velocity +float64[9] angular_velocity_covariance # Row major about x, y, z axes diff --git a/sensor_msgs/msg/Attitude.msg b/sensor_msgs/msg/Attitude.msg new file mode 100644 index 00000000..7005b149 --- /dev/null +++ b/sensor_msgs/msg/Attitude.msg @@ -0,0 +1,14 @@ +# This message represents 3D attitude + +int8 ENU=1 +int8 NED=2 +int8 ENU_FLOATING=3 +int8 NED_FLOATING=4 + +std_msgs/Header header + +geometry_msgs/Quaternion orientation +float64[9] orientation_covariance # Row major about x, y, z axes + +uint8 reference_frame_type # NED, ENU, NED_FLOATING, ENU_FLOATING +string sensor_frame # The coordinate frame in the system of the observation. diff --git a/sensor_msgs/msg/LinearAcceleration.msg b/sensor_msgs/msg/LinearAcceleration.msg new file mode 100644 index 00000000..e113fc1e --- /dev/null +++ b/sensor_msgs/msg/LinearAcceleration.msg @@ -0,0 +1,3 @@ +std_msgs/Header header +geometry_msgs/Vector3 linear_acceleration +float64[9] linear_acceleration_covariance # Row major x, y z