A handle used to read the state of a IMU sensor. More...
#include <imu_sensor_interface.h>
Classes | |
struct | Data |
Public Member Functions | |
const double * | getAngularVelocity () const |
const double * | getAngularVelocityCovariance () const |
std::string | getFrameId () const |
const double * | getLinearAcceleration () const |
const double * | getLinearAccelerationCovariance () const |
std::string | getName () const |
const double * | getOrientation () const |
const double * | getOrientationCovariance () const |
ImuSensorHandle (const Data &data=Data()) | |
Private Attributes | |
double * | angular_velocity_ |
double * | angular_velocity_covariance_ |
std::string | frame_id_ |
double * | linear_acceleration_ |
double * | linear_acceleration_covariance_ |
std::string | name_ |
double * | orientation_ |
double * | orientation_covariance_ |
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.
hardware_interface::ImuSensorHandle::ImuSensorHandle | ( | const Data & | data = Data() | ) | [inline] |
Definition at line 69 of file imu_sensor_interface.h.
const double* hardware_interface::ImuSensorHandle::getAngularVelocity | ( | ) | const [inline] |
Definition at line 84 of file imu_sensor_interface.h.
const double* hardware_interface::ImuSensorHandle::getAngularVelocityCovariance | ( | ) | const [inline] |
Definition at line 85 of file imu_sensor_interface.h.
std::string hardware_interface::ImuSensorHandle::getFrameId | ( | ) | const [inline] |
Definition at line 81 of file imu_sensor_interface.h.
const double* hardware_interface::ImuSensorHandle::getLinearAcceleration | ( | ) | const [inline] |
Definition at line 86 of file imu_sensor_interface.h.
const double* hardware_interface::ImuSensorHandle::getLinearAccelerationCovariance | ( | ) | const [inline] |
Definition at line 87 of file imu_sensor_interface.h.
std::string hardware_interface::ImuSensorHandle::getName | ( | ) | const [inline] |
Definition at line 80 of file imu_sensor_interface.h.
const double* hardware_interface::ImuSensorHandle::getOrientation | ( | ) | const [inline] |
Definition at line 82 of file imu_sensor_interface.h.
const double* hardware_interface::ImuSensorHandle::getOrientationCovariance | ( | ) | const [inline] |
Definition at line 83 of file imu_sensor_interface.h.
double* hardware_interface::ImuSensorHandle::angular_velocity_ [private] |
Definition at line 95 of file imu_sensor_interface.h.
double* hardware_interface::ImuSensorHandle::angular_velocity_covariance_ [private] |
Definition at line 96 of file imu_sensor_interface.h.
std::string hardware_interface::ImuSensorHandle::frame_id_ [private] |
Definition at line 91 of file imu_sensor_interface.h.
double* hardware_interface::ImuSensorHandle::linear_acceleration_ [private] |
Definition at line 97 of file imu_sensor_interface.h.
double* hardware_interface::ImuSensorHandle::linear_acceleration_covariance_ [private] |
Definition at line 98 of file imu_sensor_interface.h.
std::string hardware_interface::ImuSensorHandle::name_ [private] |
Definition at line 90 of file imu_sensor_interface.h.
double* hardware_interface::ImuSensorHandle::orientation_ [private] |
Definition at line 93 of file imu_sensor_interface.h.
double* hardware_interface::ImuSensorHandle::orientation_covariance_ [private] |
Definition at line 94 of file imu_sensor_interface.h.