#include <laser.hpp>

Public Member Functions | |
| void | callAll (const std::vector< message_actions::MessageAction > &actions) |
| LaserConverter (const std::string &name, const float &frequency, const qi::SessionPtr &session) | |
| void | registerCallback (message_actions::MessageAction action, Callback_t cb) |
| void | reset () |
Private Types | |
| typedef boost::function< void(sensor_msgs::LaserScan &)> | Callback_t |
Private Attributes | |
| std::map < message_actions::MessageAction, Callback_t > | callbacks_ |
| sensor_msgs::LaserScan | msg_ |
| qi::AnyObject | p_memory_ |
typedef boost::function<void(sensor_msgs::LaserScan&)> naoqi::converter::LaserConverter::Callback_t [private] |
| naoqi::converter::LaserConverter::LaserConverter | ( | const std::string & | name, |
| const float & | frequency, | ||
| const qi::SessionPtr & | session | ||
| ) |
| void naoqi::converter::LaserConverter::callAll | ( | const std::vector< message_actions::MessageAction > & | actions | ) |
there are two things done here: 1.) we have to reorder the array indices since there are ordered from left-to-right, ros laserscans are ordered from 2.) in order to combine all lasers into one message, we transform (statically) from laser frame into base_footprint
std::map<message_actions::MessageAction, Callback_t> naoqi::converter::LaserConverter::callbacks_ [private] |
sensor_msgs::LaserScan naoqi::converter::LaserConverter::msg_ [private] |
qi::AnyObject naoqi::converter::LaserConverter::p_memory_ [private] |