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

#include <sonar.hpp>

Inheritance diagram for naoqi::converter::SonarConverter:
Inheritance graph
[legend]

List of all members.

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 ()

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_

Detailed Description

Definition at line 37 of file converters/sonar.hpp.


Member Typedef Documentation

typedef boost::function<void(std::vector<sensor_msgs::Range>&)> naoqi::converter::SonarConverter::Callback_t [private]

Definition at line 40 of file converters/sonar.hpp.


Constructor & Destructor Documentation

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

Definition at line 35 of file converters/sonar.cpp.

Definition at line 75 of file converters/sonar.cpp.


Member Function Documentation

Definition at line 89 of file converters/sonar.cpp.

Definition at line 84 of file converters/sonar.cpp.

Definition at line 118 of file converters/sonar.cpp.


Member Data Documentation

Definition at line 56 of file converters/sonar.hpp.

std::vector<std::string> naoqi::converter::SonarConverter::frames_ [private]

The frames of the sonars

Definition at line 68 of file converters/sonar.hpp.

Key describeing whether we are subscribed to the ALSonar module

Definition at line 63 of file converters/sonar.hpp.

std::vector<std::string> naoqi::converter::SonarConverter::keys_ [private]

The memory keys of the sonars

Definition at line 66 of file converters/sonar.hpp.

std::vector<sensor_msgs::Range> naoqi::converter::SonarConverter::msgs_ [private]

Pre-filled messges that are sent

Definition at line 70 of file converters/sonar.hpp.

Memory (Proxy) configurations

Definition at line 61 of file converters/sonar.hpp.

Sonar (Proxy) configurations

Definition at line 59 of file converters/sonar.hpp.


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


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56