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;
51 ImuConverter(
const std::string& name,
const IMU::Location& location,
const float& frequency,
const qi::SessionPtr& session);
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
boost::function< void(sensor_msgs::Imu &) > Callback_t
sensor_msgs::Imu msg_imu_
std::map< message_actions::MessageAction, Callback_t > callbacks_
std::vector< std::string > data_names_list_