#include <SensorHandlers.hpp>
Public Types | |
enum | { roll = 0, pitch, yaw } |
enum | { p = 0, q, r } |
enum | { ax, ay, az } |
Public Member Functions | |
const double * | acc () const |
void | configure (ros::NodeHandle &nh) |
ImuHandler () | |
const double * | orientation () const |
const double * | rate () const |
void | setGpsHandler (GPSHandler *gps) |
Private Member Functions | |
void | onImu (const sensor_msgs::Imu::ConstPtr &data) |
Private Attributes | |
double | axyz [3] |
tf2_ros::Buffer | buffer |
GPSHandler * | gps |
ros::Subscriber | imu |
tf2_ros::TransformListener | listener |
double | pqr [3] |
double | rpy [3] |
labust::math::unwrap | unwrap |
The imu handler.
Definition at line 103 of file SensorHandlers.hpp.
anonymous enum |
Definition at line 106 of file SensorHandlers.hpp.
anonymous enum |
Definition at line 107 of file SensorHandlers.hpp.
anonymous enum |
Definition at line 108 of file SensorHandlers.hpp.
labust::navigation::ImuHandler::ImuHandler | ( | ) | [inline] |
Definition at line 110 of file SensorHandlers.hpp.
const double* labust::navigation::ImuHandler::acc | ( | ) | const [inline] |
Definition at line 120 of file SensorHandlers.hpp.
void ImuHandler::configure | ( | ros::NodeHandle & | nh | ) |
Definition at line 91 of file SensorHandlers.cpp.
void ImuHandler::onImu | ( | const sensor_msgs::Imu::ConstPtr & | data | ) | [private] |
Definition at line 97 of file SensorHandlers.cpp.
const double* labust::navigation::ImuHandler::orientation | ( | ) | const [inline] |
Definition at line 116 of file SensorHandlers.hpp.
const double* labust::navigation::ImuHandler::rate | ( | ) | const [inline] |
Definition at line 118 of file SensorHandlers.hpp.
void labust::navigation::ImuHandler::setGpsHandler | ( | GPSHandler * | gps | ) | [inline] |
Definition at line 112 of file SensorHandlers.hpp.
double labust::navigation::ImuHandler::axyz[3] [private] |
Definition at line 128 of file SensorHandlers.hpp.
Definition at line 124 of file SensorHandlers.hpp.
GPSHandler* labust::navigation::ImuHandler::gps [private] |
Definition at line 129 of file SensorHandlers.hpp.
Definition at line 127 of file SensorHandlers.hpp.
Definition at line 125 of file SensorHandlers.hpp.
double labust::navigation::ImuHandler::pqr[3] [private] |
Definition at line 128 of file SensorHandlers.hpp.
double labust::navigation::ImuHandler::rpy[3] [private] |
Definition at line 128 of file SensorHandlers.hpp.
Definition at line 126 of file SensorHandlers.hpp.