info.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 /*
00019 * LOCAL includes
00020 */
00021 #include "info.hpp"
00022 #include "../tools/from_any_value.hpp"
00023 
00024 /*
00025 * BOOST includes
00026 */
00027 #include <boost/assign/list_of.hpp>
00028 #include <boost/foreach.hpp>
00029 #define for_each BOOST_FOREACH
00030 
00031 namespace naoqi
00032 {
00033 namespace converter
00034 {
00035 
00036 InfoConverter::InfoConverter( const std::string& name, float frequency, const qi::SessionPtr& session )
00037   : BaseConverter( name, frequency, session ),
00038     p_memory_( session->service("ALMemory") )
00039 {
00040   keys_.push_back("RobotConfig/Head/FullHeadId");
00041   keys_.push_back("Device/DeviceList/ChestBoard/BodyId");
00042   keys_.push_back("RobotConfig/Body/Type");
00043   keys_.push_back("RobotConfig/Body/BaseVersion");
00044   keys_.push_back("RobotConfig/Body/Device/LeftArm/Version");
00045   keys_.push_back("RobotConfig/Body/Device/RightArm/Version");
00046   keys_.push_back("RobotConfig/Body/Device/Hand/Left/Version");
00047   keys_.push_back("RobotConfig/Body/Version");
00048   keys_.push_back("RobotConfig/Body/SoftwareRequirement");
00049   keys_.push_back("RobotConfig/Body/Device/Legs/Version");
00050   if(robot_ == robot::PEPPER)
00051   {
00052     keys_.push_back("Device/DeviceList/BatteryFuelGauge/SerialNumber");
00053     keys_.push_back("Device/DeviceList/BatteryFuelGauge/FirmwareVersion");
00054     keys_.push_back("RobotConfig/Body/Device/Platform/Version");
00055     keys_.push_back("RobotConfig/Body/Device/Brakes/Version");
00056     keys_.push_back("RobotConfig/Body/Device/Wheel/Version");
00057   }
00058 }
00059 
00060 void InfoConverter::reset()
00061 {
00062 }
00063 
00064 void InfoConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00065 {
00066   callbacks_[action] = cb;
00067 }
00068 
00069 void InfoConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
00070 {
00071   std::vector<std::string> values;
00072   try {
00073       qi::AnyValue anyvalues = p_memory_.call<qi::AnyValue>("getListData", keys_);
00074       tools::fromAnyValueToStringVector(anyvalues, values);
00075   } catch (const std::exception& e) {
00076     std::cerr << "Exception caught in InfoConverter: " << e.what() << std::endl;
00077     return;
00078   }
00079 
00080   naoqi_bridge_msgs::StringStamped msg;
00081 
00082   msg.header.stamp = ros::Time::now();
00083   for(size_t i = 0; i < keys_.size(); ++i)
00084   {
00085     msg.data += keys_[i] + ": " + values[i];
00086     if (i != keys_.size()-1)
00087     msg.data += " ; ";
00088   }
00089   for_each( const message_actions::MessageAction& action, actions )
00090   {
00091     callbacks_[action](msg);
00092   }
00093 }
00094 
00095 } // converter
00096 } //naoqi


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sun Sep 17 2017 02:57:14