Classes | Public Member Functions | Private Attributes | List of all members
hardware_interface::ImuSensorHandle Class Reference

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())
 
 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)
 

Private Attributes

const double * angular_velocity_
 
const double * angular_velocity_covariance_
 
std::string frame_id_
 
const double * linear_acceleration_
 
const double * linear_acceleration_covariance_
 
std::string name_
 
const double * orientation_
 
const double * orientation_covariance_
 

Detailed Description

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.

Constructor & Destructor Documentation

hardware_interface::ImuSensorHandle::ImuSensorHandle ( const Data data = Data())
inline

Definition at line 69 of file imu_sensor_interface.h.

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
nameThe name of the sensor
frame_idThe reference frame to which this sensor is associated
orientationA pointer to the storage of the orientation value: a quaternion (x,y,z,w)
orientation_covarianceA pointer to the storage of the orientation covariance value: a row major 3x3 matrix about (x,y,z)
angular_velocityA pointer to the storage of the angular velocity value: a triplet (x,y,z)
angular_velocity_covarianceA pointer to the storage of the angular velocity covariance value: a row major 3x3 matrix about (x,y,z)
linear_accelerationA pointer to the storage of the linear acceleration value: a triplet (x,y,z)
linear_acceleration_covarianceA pointer to the storage of the linear acceleration covariance value: a row major 3x3 matrix about (x,y,z)

Definition at line 80 of file imu_sensor_interface.h.

Member Function Documentation

const double* hardware_interface::ImuSensorHandle::getAngularVelocity ( ) const
inline

Definition at line 104 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::getAngularVelocityCovariance ( ) const
inline

Definition at line 105 of file imu_sensor_interface.h.

std::string hardware_interface::ImuSensorHandle::getFrameId ( ) const
inline

Definition at line 101 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::getLinearAcceleration ( ) const
inline

Definition at line 106 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::getLinearAccelerationCovariance ( ) const
inline

Definition at line 107 of file imu_sensor_interface.h.

std::string hardware_interface::ImuSensorHandle::getName ( ) const
inline

Definition at line 100 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::getOrientation ( ) const
inline

Definition at line 102 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::getOrientationCovariance ( ) const
inline

Definition at line 103 of file imu_sensor_interface.h.

Member Data Documentation

const double* hardware_interface::ImuSensorHandle::angular_velocity_
private

Definition at line 115 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::angular_velocity_covariance_
private

Definition at line 116 of file imu_sensor_interface.h.

std::string hardware_interface::ImuSensorHandle::frame_id_
private

Definition at line 111 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::linear_acceleration_
private

Definition at line 117 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::linear_acceleration_covariance_
private

Definition at line 118 of file imu_sensor_interface.h.

std::string hardware_interface::ImuSensorHandle::name_
private

Definition at line 110 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::orientation_
private

Definition at line 113 of file imu_sensor_interface.h.

const double* hardware_interface::ImuSensorHandle::orientation_covariance_
private

Definition at line 114 of file imu_sensor_interface.h.


The documentation for this class was generated from the following file:


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Mon Apr 20 2020 03:52:05