18 #ifndef LASER_CONVERTER_HPP
19 #define LASER_CONVERTER_HPP
30 #include <sensor_msgs/LaserScan.h>
40 typedef boost::function<void(sensor_msgs::LaserScan&)>
Callback_t;
47 void callAll(
const std::vector<message_actions::MessageAction>& actions );
55 std::map<message_actions::MessageAction, Callback_t>
callbacks_;
56 sensor_msgs::LaserScan
msg_;
std::string name() const
Definition: converter_base.hpp:54
float frequency() const
Definition: converter_base.hpp:59
sensor_msgs::LaserScan msg_
Definition: laser.hpp:56
MessageAction
Definition: message_actions.h:9
qi::AnyObject p_memory_
Definition: laser.hpp:53
void reset()
Definition: laser.cpp:213
LaserConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
Definition: laser.cpp:131
boost::function< void(sensor_msgs::LaserScan &)> Callback_t
Definition: laser.hpp:40
Definition: converter_base.hpp:40
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: laser.hpp:55
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: laser.cpp:142
void registerCallback(message_actions::MessageAction action, Callback_t cb)
Definition: laser.cpp:137