naoqidriver
Public Member Functions | Private Types | Private Attributes
naoqi::converter::LaserConverter Class Reference

#include <laser.hpp>

Inheritance diagram for naoqi::converter::LaserConverter:
naoqi::converter::BaseConverter< LaserConverter >

Public Member Functions

 LaserConverter (const std::string &name, const float &frequency, const qi::SessionPtr &session)
 
void registerCallback (message_actions::MessageAction action, Callback_t cb)
 
void callAll (const std::vector< message_actions::MessageAction > &actions)
 
void reset ()
 
- Public Member Functions inherited from naoqi::converter::BaseConverter< LaserConverter >
 BaseConverter (const std::string &name, float frequency, qi::SessionPtr session)
 
virtual ~BaseConverter ()
 
std::string name () const
 
float frequency () const
 

Private Types

typedef boost::function< void(sensor_msgs::LaserScan &)> Callback_t
 

Private Attributes

qi::AnyObject p_memory_
 
std::map< message_actions::MessageAction, Callback_tcallbacks_
 
sensor_msgs::LaserScan msg_
 

Additional Inherited Members

- Protected Attributes inherited from naoqi::converter::BaseConverter< LaserConverter >
std::string name_
 
float frequency_
 
const robot::Robotrobot_
 
qi::SessionPtr session_
 
bool record_enabled_
 

Member Typedef Documentation

typedef boost::function<void(sensor_msgs::LaserScan&)> naoqi::converter::LaserConverter::Callback_t
private

Constructor & Destructor Documentation

naoqi::converter::LaserConverter::LaserConverter ( const std::string &  name,
const float &  frequency,
const qi::SessionPtr &  session 
)

Member Function Documentation

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

void naoqi::converter::LaserConverter::registerCallback ( message_actions::MessageAction  action,
Callback_t  cb 
)
void naoqi::converter::LaserConverter::reset ( )

Field Documentation

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

The documentation for this class was generated from the following files: