22 #include "../tools/from_any_value.hpp"    27 #include <boost/foreach.hpp>    28 #define for_each BOOST_FOREACH    37     p_memory_( session->service(
"ALMemory") ),
    38     p_sonar_( session->service(
"ALSonar") ),
    41   std::vector<std::string> keys;
    43     keys.push_back(
"Device/SubDeviceList/Platform/Front/Sonar/Sensor/Value");
    44     keys.push_back(
"Device/SubDeviceList/Platform/Back/Sonar/Sensor/Value");
    45     frames_.push_back(
"SonarFront_frame");
    46     frames_.push_back(
"SonarBack_frame");
    50     keys.push_back(
"Device/SubDeviceList/US/Left/Sensor/Value");
    51     keys.push_back(
"Device/SubDeviceList/US/Right/Sensor/Value");
    52     frames_.push_back(
"LSonar_frame");
    53     frames_.push_back(
"RSonar_frame");
    60   for(
size_t i = 0; i < 
msgs_.size(); ++i)
    63       msgs_[i].min_range = 0.25;
    64       msgs_[i].max_range = 2.55;
    65       msgs_[i].field_of_view = 0.523598776;
    66       msgs_[i].radiation_type = sensor_msgs::Range::ULTRASOUND;
    69   keys_.resize(keys.size());
    71   for(std::vector<std::string>::const_iterator it = keys.begin(); it != keys.end(); ++it, ++i)
    79     p_sonar_.call<
void>(
"unsubscribe", 
"ROS");
    93     p_sonar_.call<
void>(
"subscribe", 
"ROS");
    99       qi::AnyValue anyvalues = 
p_memory_.call<qi::AnyValue>(
"getListData", 
keys_);
   101   } 
catch (
const std::exception& e) {
   102     std::cerr << 
"Exception caught in SonarConverter: " << e.what() << std::endl;
   106   for(
size_t i = 0; i < 
msgs_.size(); ++i)
   108     msgs_[i].header.stamp = now;
   109     msgs_[i].range = float(values[i]);
   122     p_sonar_.call<
void>(
"unsubscribe", 
"ROS");
 
std::vector< double > values
SonarConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
std::vector< std::string > frames_
void registerCallback(message_actions::MessageAction action, Callback_t cb)
const robot::Robot & robot_
boost::function< void(std::vector< sensor_msgs::Range > &)> Callback_t
void callAll(const std::vector< message_actions::MessageAction > &actions)
std::vector< std::string > keys_
std::map< message_actions::MessageAction, Callback_t > callbacks_
std::vector< sensor_msgs::Range > msgs_