Go to the documentation of this file.
43 sensor_msgs::Imu& msg)
47 msg.header = msg_header;
57 msg.linear_acceleration.x = measurements.at(
IMU_X_ACC);
58 msg.linear_acceleration.y = measurements.at(
IMU_Y_ACC);
59 msg.linear_acceleration.z = measurements.at(
IMU_Z_ACC);
61 msg.angular_velocity.x = measurements.at(
IMU_WX);
62 msg.angular_velocity.y = measurements.at(
IMU_WY);
63 msg.angular_velocity.z = measurements.at(
IMU_WZ);
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
@ IMU_WY
angular velocity - y (local/vehicle frame) (rad/sec)
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
@ IMU_WZ
angular velocity - z (local/vehicle frame) (rad/sec)
This namespace contains representation of robot actions and observations.
@ IMU_ORI_QUAT_W
Orientation Quaternion W (global/navigation frame)
@ IMU_Z_ACC
z-axis acceleration (local/vehicle frame) (m/sec2)
@ IMU_ORI_QUAT_Y
Orientation Quaternion Y (global/navigation frame)
@ IMU_X_ACC
x-axis acceleration (local/vehicle frame) (m/sec2)
@ IMU_ORI_QUAT_Z
Orientation Quaternion Z (global/navigation frame)
bool fromROS(const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
@ IMU_Y_ACC
y-axis acceleration (local/vehicle frame) (m/sec2)
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github...
bool toROS(const mrpt::obs::CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix The user must supply the "msg_header" fie...
void set(TIMUDataIndex idx, double value)
Sets a given data type, and mark it as present.
@ IMU_WX
angular velocity - x (local/vehicle frame) (rad/sec)
@ IMU_ORI_QUAT_X
Orientation Quaternion X (global/navigation frame)
Page generated by Doxygen 1.8.17 for MRPT 2.0.3 at Fri May 15 15:49:54 UTC 2020 | |