22 #include "../tools/from_any_value.hpp"    27 #include <boost/assign/list_of.hpp>    28 #include <boost/foreach.hpp>    29 #define for_each BOOST_FOREACH    38     p_memory_( session->service(
"ALMemory") )
    40   keys_.push_back(
"RobotConfig/Head/FullHeadId");
    41   keys_.push_back(
"Device/DeviceList/ChestBoard/BodyId");
    42   keys_.push_back(
"RobotConfig/Body/Type");
    43   keys_.push_back(
"RobotConfig/Body/BaseVersion");
    44   keys_.push_back(
"RobotConfig/Body/Device/LeftArm/Version");
    45   keys_.push_back(
"RobotConfig/Body/Device/RightArm/Version");
    46   keys_.push_back(
"RobotConfig/Body/Device/Hand/Left/Version");
    47   keys_.push_back(
"RobotConfig/Body/Version");
    48   keys_.push_back(
"RobotConfig/Body/SoftwareRequirement");
    49   keys_.push_back(
"RobotConfig/Body/Device/Legs/Version");
    52     keys_.push_back(
"Device/DeviceList/BatteryFuelGauge/SerialNumber");
    53     keys_.push_back(
"Device/DeviceList/BatteryFuelGauge/FirmwareVersion");
    54     keys_.push_back(
"RobotConfig/Body/Device/Platform/Version");
    55     keys_.push_back(
"RobotConfig/Body/Device/Brakes/Version");
    56     keys_.push_back(
"RobotConfig/Body/Device/Wheel/Version");
    71   std::vector<std::string> 
values;
    73       qi::AnyValue anyvalues = 
p_memory_.call<qi::AnyValue>(
"getListData", 
keys_);
    75   } 
catch (
const std::exception& e) {
    76     std::cerr << 
"Exception caught in InfoConverter: " << e.what() << std::endl;
    80   naoqi_bridge_msgs::StringStamped 
msg;
    83   for(
size_t i = 0; i < 
keys_.size(); ++i)
    85     msg.data += 
keys_[i] + 
": " + values[i];
    86     if (i != 
keys_.size()-1)
 
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
std::vector< double > values
InfoConverter(const std::string &name, float frequency, const qi::SessionPtr &sessions)
const robot::Robot & robot_
std::map< message_actions::MessageAction, Callback_t > callbacks_
boost::function< void(naoqi_bridge_msgs::StringStamped)> Callback_t
std::vector< std::string > keys_
void callAll(const std::vector< message_actions::MessageAction > &actions)