#include <sonar.hpp>
Public Member Functions | |
void | callAll (const std::vector< message_actions::MessageAction > &actions) |
void | registerCallback (message_actions::MessageAction action, Callback_t cb) |
void | reset () |
SonarConverter (const std::string &name, const float &frequency, const qi::SessionPtr &session) | |
~SonarConverter () | |
Public Member Functions inherited from naoqi::converter::BaseConverter< SonarConverter > | |
BaseConverter (const std::string &name, float frequency, qi::SessionPtr session) | |
float | frequency () const |
std::string | name () const |
virtual | ~BaseConverter () |
Private Types | |
typedef boost::function< void(std::vector< sensor_msgs::Range > &)> | Callback_t |
Private Attributes | |
std::map< message_actions::MessageAction, Callback_t > | callbacks_ |
std::vector< std::string > | frames_ |
bool | is_subscribed_ |
std::vector< std::string > | keys_ |
std::vector< sensor_msgs::Range > | msgs_ |
qi::AnyObject | p_memory_ |
qi::AnyObject | p_sonar_ |
Additional Inherited Members | |
Protected Attributes inherited from naoqi::converter::BaseConverter< SonarConverter > | |
float | frequency_ |
std::string | name_ |
bool | record_enabled_ |
const robot::Robot & | robot_ |
qi::SessionPtr | session_ |
Definition at line 37 of file converters/sonar.hpp.
|
private |
Definition at line 40 of file converters/sonar.hpp.
naoqi::converter::SonarConverter::SonarConverter | ( | const std::string & | name, |
const float & | frequency, | ||
const qi::SessionPtr & | session | ||
) |
Definition at line 35 of file converters/sonar.cpp.
naoqi::converter::SonarConverter::~SonarConverter | ( | ) |
Definition at line 75 of file converters/sonar.cpp.
void naoqi::converter::SonarConverter::callAll | ( | const std::vector< message_actions::MessageAction > & | actions | ) |
Definition at line 89 of file converters/sonar.cpp.
void naoqi::converter::SonarConverter::registerCallback | ( | message_actions::MessageAction | action, |
Callback_t | cb | ||
) |
Definition at line 84 of file converters/sonar.cpp.
void naoqi::converter::SonarConverter::reset | ( | ) |
Definition at line 118 of file converters/sonar.cpp.
|
private |
Definition at line 56 of file converters/sonar.hpp.
|
private |
The frames of the sonars
Definition at line 68 of file converters/sonar.hpp.
|
private |
Key describeing whether we are subscribed to the ALSonar module
Definition at line 63 of file converters/sonar.hpp.
|
private |
The memory keys of the sonars
Definition at line 66 of file converters/sonar.hpp.
|
private |
Pre-filled messges that are sent
Definition at line 70 of file converters/sonar.hpp.
|
private |
Memory (Proxy) configurations
Definition at line 61 of file converters/sonar.hpp.
|
private |
Sonar (Proxy) configurations
Definition at line 59 of file converters/sonar.hpp.