#include <sonar.hpp>
|
typedef boost::function< void(std::vector< sensor_msgs::Range > &)> | Callback_t |
|
naoqi::converter::SonarConverter::SonarConverter |
( |
const std::string & |
name, |
|
|
const float & |
frequency, |
|
|
const qi::SessionPtr & |
session |
|
) |
| |
naoqi::converter::SonarConverter::~SonarConverter |
( |
| ) |
|
void naoqi::converter::SonarConverter::reset |
( |
| ) |
|
std::vector<std::string> naoqi::converter::SonarConverter::frames_ |
|
private |
bool naoqi::converter::SonarConverter::is_subscribed_ |
|
private |
Key describeing whether we are subscribed to the ALSonar module
std::vector<std::string> naoqi::converter::SonarConverter::keys_ |
|
private |
The memory keys of the sonars
std::vector<sensor_msgs::Range> naoqi::converter::SonarConverter::msgs_ |
|
private |
Pre-filled messges that are sent
qi::AnyObject naoqi::converter::SonarConverter::p_memory_ |
|
private |
Memory (Proxy) configurations
qi::AnyObject naoqi::converter::SonarConverter::p_sonar_ |
|
private |
Sonar (Proxy) configurations
The documentation for this class was generated from the following files:
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/src/converters/sonar.hpp
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/src/converters/sonar.cpp