18 #ifndef IMU_CONVERTER_HPP
19 #define IMU_CONVERTER_HPP
30 #include <sensor_msgs/Imu.h>
48 typedef boost::function<void(sensor_msgs::Imu&) >
Callback_t;
59 virtual void callAll(
const std::vector<message_actions::MessageAction>& actions);
67 std::map<message_actions::MessageAction, Callback_t>
callbacks_;
74 #endif // IMU_CONVERTER_HPP
std::string name() const
Definition: converter_base.hpp:54
Location
Definition: imu.hpp:38
float frequency() const
Definition: converter_base.hpp:59
~ImuConverter()
Definition: imu.cpp:73
MessageAction
Definition: message_actions.h:9
boost::function< void(sensor_msgs::Imu &) > Callback_t
Definition: imu.hpp:48
sensor_msgs::Imu msg_imu_
Definition: imu.hpp:62
virtual void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: imu.cpp:88
qi::AnyObject p_memory_
Definition: imu.hpp:63
ImuConverter(const std::string &name, const IMU::Location &location, const float &frequency, const qi::SessionPtr &session)
Definition: imu.cpp:41
Definition: converter_base.hpp:40
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
Definition: imu.cpp:83
virtual void reset()
Definition: imu.cpp:78
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: imu.hpp:67
std::vector< std::string > data_names_list_
Definition: imu.hpp:64