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 );
51 void setLaserRanges(
const float &range_min,
const float &range_max);
59 std::map<message_actions::MessageAction, Callback_t>
callbacks_;
60 sensor_msgs::LaserScan
msg_;
sensor_msgs::LaserScan msg_
LaserConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
boost::function< void(sensor_msgs::LaserScan &)> Callback_t
std::map< message_actions::MessageAction, Callback_t > callbacks_
void callAll(const std::vector< message_actions::MessageAction > &actions)
void registerCallback(message_actions::MessageAction action, Callback_t cb)
void setLaserRanges(const float &range_min, const float &range_max)