naoqidriver
|
#include <imu.hpp>
Public Member Functions | |
ImuConverter (const std::string &name, const IMU::Location &location, const float &frequency, const qi::SessionPtr &session) | |
~ImuConverter () | |
virtual void | reset () |
void | registerCallback (const message_actions::MessageAction action, Callback_t cb) |
virtual void | callAll (const std::vector< message_actions::MessageAction > &actions) |
Public Member Functions inherited from naoqi::converter::BaseConverter< ImuConverter > | |
BaseConverter (const std::string &name, float frequency, qi::SessionPtr session) | |
virtual | ~BaseConverter () |
std::string | name () const |
float | frequency () const |
Private Types | |
typedef boost::function< void(sensor_msgs::Imu &) > | Callback_t |
Private Attributes | |
sensor_msgs::Imu | msg_imu_ |
qi::AnyObject | p_memory_ |
std::vector< std::string > | data_names_list_ |
std::map< message_actions::MessageAction, Callback_t > | callbacks_ |
Additional Inherited Members | |
Protected Attributes inherited from naoqi::converter::BaseConverter< ImuConverter > | |
std::string | name_ |
float | frequency_ |
const robot::Robot & | robot_ |
qi::SessionPtr | session_ |
bool | record_enabled_ |
|
private |
naoqi::converter::ImuConverter::ImuConverter | ( | const std::string & | name, |
const IMU::Location & | location, | ||
const float & | frequency, | ||
const qi::SessionPtr & | session | ||
) |
naoqi::converter::ImuConverter::~ImuConverter | ( | ) |
|
virtual |
void naoqi::converter::ImuConverter::registerCallback | ( | const message_actions::MessageAction | action, |
Callback_t | cb | ||
) |
|
virtual |
|
private |
Registered Callbacks
|
private |
|
private |
|
private |