$search
#include <imu_input.h>
Public Types | |
enum | InputIndex { ACCEL_X = 1, ACCEL_Y, ACCEL_Z, GYRO_X, GYRO_Y, GYRO_Z } |
typedef ColumnVector_ < InputDimension > | InputVector |
Public Member Functions | |
virtual ColumnVector_< 3 > | getAccel () const |
virtual ColumnVector_< 3 > | getRate () const |
virtual InputVector const & | getVector () const |
ImuInput (const sensor_msgs::Imu &imu) | |
ImuInput (InputVector const &u) | |
ImuInput () | |
virtual InputVector & | operator= (const sensor_msgs::Imu &imu) |
virtual InputVector & | operator= (InputVector const &u) |
virtual void | setValue (const sensor_msgs::Imu &imu) |
virtual void | setValue (InputVector const &u) |
virtual | ~ImuInput () |
Static Public Attributes | |
static const unsigned int | InputDimension = GYRO_Z |
Protected Attributes | |
InputVector | u_ |
Definition at line 38 of file imu_input.h.
Definition at line 50 of file imu_input.h.
Definition at line 41 of file imu_input.h.
hector_pose_estimation::ImuInput::ImuInput | ( | ) | [inline] |
Definition at line 52 of file imu_input.h.
hector_pose_estimation::ImuInput::ImuInput | ( | InputVector const & | u | ) | [inline] |
Definition at line 55 of file imu_input.h.
hector_pose_estimation::ImuInput::ImuInput | ( | const sensor_msgs::Imu & | imu | ) | [inline] |
Definition at line 60 of file imu_input.h.
virtual hector_pose_estimation::ImuInput::~ImuInput | ( | ) | [inline, virtual] |
Definition at line 65 of file imu_input.h.
virtual ColumnVector_<3> hector_pose_estimation::ImuInput::getAccel | ( | ) | const [inline, virtual] |
Definition at line 78 of file imu_input.h.
virtual ColumnVector_<3> hector_pose_estimation::ImuInput::getRate | ( | ) | const [inline, virtual] |
Definition at line 79 of file imu_input.h.
virtual InputVector const& hector_pose_estimation::ImuInput::getVector | ( | ) | const [inline, virtual] |
Definition at line 77 of file imu_input.h.
virtual InputVector& hector_pose_estimation::ImuInput::operator= | ( | const sensor_msgs::Imu & | imu | ) | [inline, virtual] |
Definition at line 82 of file imu_input.h.
virtual InputVector& hector_pose_estimation::ImuInput::operator= | ( | InputVector const & | u | ) | [inline, virtual] |
Definition at line 81 of file imu_input.h.
virtual void hector_pose_estimation::ImuInput::setValue | ( | const sensor_msgs::Imu & | imu | ) | [inline, virtual] |
Definition at line 68 of file imu_input.h.
virtual void hector_pose_estimation::ImuInput::setValue | ( | InputVector const & | u | ) | [inline, virtual] |
Definition at line 67 of file imu_input.h.
const unsigned int hector_pose_estimation::ImuInput::InputDimension = GYRO_Z [static] |
Definition at line 49 of file imu_input.h.
InputVector hector_pose_estimation::ImuInput::u_ [protected] |
Definition at line 85 of file imu_input.h.