A handle used to read the state of a IMU sensor.
More...
#include <imu_sensor_interface.h>
A handle used to read the state of a IMU sensor.
Depending on the sensor, not all readings exposed by the handle class might be available. TODO: Document more!
Definition at line 44 of file imu_sensor_interface.h.
◆ ImuSensorHandle() [1/2]
hardware_interface::ImuSensorHandle::ImuSensorHandle |
( |
const Data & |
data = {} | ) |
|
|
inline |
◆ ImuSensorHandle() [2/2]
hardware_interface::ImuSensorHandle::ImuSensorHandle |
( |
const std::string & |
name, |
|
|
const std::string & |
frame_id, |
|
|
const double * |
orientation, |
|
|
const double * |
orientation_covariance, |
|
|
const double * |
angular_velocity, |
|
|
const double * |
angular_velocity_covariance, |
|
|
const double * |
linear_acceleration, |
|
|
const double * |
linear_acceleration_covariance |
|
) |
| |
|
inline |
- Parameters
-
name | The name of the sensor |
frame_id | The reference frame to which this sensor is associated |
orientation | A pointer to the storage of the orientation value: a quaternion (x,y,z,w) |
orientation_covariance | A pointer to the storage of the orientation covariance value: a row major 3x3 matrix about (x,y,z) |
angular_velocity | A pointer to the storage of the angular velocity value: a triplet (x,y,z) |
angular_velocity_covariance | A pointer to the storage of the angular velocity covariance value: a row major 3x3 matrix about (x,y,z) |
linear_acceleration | A pointer to the storage of the linear acceleration value: a triplet (x,y,z) |
linear_acceleration_covariance | A pointer to the storage of the linear acceleration covariance value: a row major 3x3 matrix about (x,y,z) |
Definition at line 73 of file imu_sensor_interface.h.
◆ getAngularVelocity()
const double* hardware_interface::ImuSensorHandle::getAngularVelocity |
( |
| ) |
const |
|
inline |
◆ getAngularVelocityCovariance()
const double* hardware_interface::ImuSensorHandle::getAngularVelocityCovariance |
( |
| ) |
const |
|
inline |
◆ getFrameId()
std::string hardware_interface::ImuSensorHandle::getFrameId |
( |
| ) |
const |
|
inline |
◆ getLinearAcceleration()
const double* hardware_interface::ImuSensorHandle::getLinearAcceleration |
( |
| ) |
const |
|
inline |
◆ getLinearAccelerationCovariance()
const double* hardware_interface::ImuSensorHandle::getLinearAccelerationCovariance |
( |
| ) |
const |
|
inline |
◆ getName()
std::string hardware_interface::ImuSensorHandle::getName |
( |
| ) |
const |
|
inline |
◆ getOrientation()
const double* hardware_interface::ImuSensorHandle::getOrientation |
( |
| ) |
const |
|
inline |
◆ getOrientationCovariance()
const double* hardware_interface::ImuSensorHandle::getOrientationCovariance |
( |
| ) |
const |
|
inline |
◆ angular_velocity_
const double* hardware_interface::ImuSensorHandle::angular_velocity_ |
|
private |
◆ angular_velocity_covariance_
const double* hardware_interface::ImuSensorHandle::angular_velocity_covariance_ |
|
private |
◆ frame_id_
std::string hardware_interface::ImuSensorHandle::frame_id_ |
|
private |
◆ linear_acceleration_
const double* hardware_interface::ImuSensorHandle::linear_acceleration_ |
|
private |
◆ linear_acceleration_covariance_
const double* hardware_interface::ImuSensorHandle::linear_acceleration_covariance_ |
|
private |
◆ name_
std::string hardware_interface::ImuSensorHandle::name_ |
|
private |
◆ orientation_
const double* hardware_interface::ImuSensorHandle::orientation_ |
|
private |
◆ orientation_covariance_
const double* hardware_interface::ImuSensorHandle::orientation_covariance_ |
|
private |
The documentation for this class was generated from the following file: