vulp
2.2.2
|
Data filtered from an onboard IMU such as the pi3hat's. More...
#include <ImuData.h>
Public Attributes | |
Eigen::Quaterniond | orientation_imu_in_ars = Eigen::Quaterniond::Identity() |
Orientation from the IMU frame to the attitude reference system (ARS) frame. More... | |
Eigen::Vector3d | angular_velocity_imu_in_imu = Eigen::Vector3d::Zero() |
Body angular velocity of the IMU frame in [rad] / [s]. More... | |
Eigen::Vector3d | linear_acceleration_imu_in_imu = Eigen::Vector3d::Zero() |
Body linear acceleration of the IMU, in [m] / [s]². More... | |
Eigen::Vector3d vulp::actuation::ImuData::angular_velocity_imu_in_imu = Eigen::Vector3d::Zero() |
Body angular velocity of the IMU frame in [rad] / [s].
Eigen::Vector3d vulp::actuation::ImuData::linear_acceleration_imu_in_imu = Eigen::Vector3d::Zero() |
Body linear acceleration of the IMU, in [m] / [s]².
Eigen::Quaterniond vulp::actuation::ImuData::orientation_imu_in_ars = Eigen::Quaterniond::Identity() |
Orientation from the IMU frame to the attitude reference system (ARS) frame.
The attitude reference system frame has +x forward, +y right and +z down, whereas our world frame has +x forward, +y left and +z up: https://github.com/mjbots/pi3hat/blob/ab632c82bd501b9fcb6f8200df0551989292b7a1/docs/reference.md#orientation