memory_list.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 "memory_list.hpp"
00022 
00023 /*
00024 * BOOST includes
00025 */
00026 #include <boost/foreach.hpp>
00027 #define for_each BOOST_FOREACH
00028 
00029 namespace naoqi {
00030 
00031 namespace converter {
00032 
00033 MemoryListConverter::MemoryListConverter(const std::vector<std::string>& key_list, const std::string &name, const float &frequency, const qi::SessionPtr &session):
00034     BaseConverter(name, frequency, session),
00035     p_memory_(session->service("ALMemory")),
00036     _key_list(key_list)
00037 {}
00038 
00039 void MemoryListConverter::reset(){
00040 
00041 }
00042 
00043 void MemoryListConverter::callAll(const std::vector<message_actions::MessageAction> &actions){
00044   // Get inertial data
00045   qi::AnyValue memData_anyvalue = p_memory_.call<qi::AnyValue>("getListData", _key_list);
00046 
00047   // Reset message
00048   _msg = naoqi_bridge_msgs::MemoryList();
00049   ros::Time now = ros::Time::now();
00050   _msg.header.stamp = now;
00051 
00052   qi::AnyReferenceVector memData_anyref = memData_anyvalue.asListValuePtr();
00053 
00054   for(int i=0; i<memData_anyref.size();i++)
00055   {
00056     if(memData_anyref[i].content().kind() == qi::TypeKind_Int)
00057     {
00058       naoqi_bridge_msgs::MemoryPairInt tmp_msg;
00059       tmp_msg.memoryKey = _key_list[i];
00060       tmp_msg.data = memData_anyref[i].content().asInt32();
00061       _msg.ints.push_back(tmp_msg);
00062     }
00063     else if(memData_anyref[i].content().kind() == qi::TypeKind_Float)
00064     {
00065         naoqi_bridge_msgs::MemoryPairFloat tmp_msg;
00066         tmp_msg.memoryKey = _key_list[i];
00067         tmp_msg.data = memData_anyref[i].content().asFloat();
00068         _msg.floats.push_back(tmp_msg);
00069     }
00070     else if(memData_anyref[i].content().kind() == qi::TypeKind_String)
00071     {
00072       naoqi_bridge_msgs::MemoryPairString tmp_msg;
00073       tmp_msg.memoryKey = _key_list[i];
00074       tmp_msg.data = memData_anyref[i].content().asString();
00075       _msg.strings.push_back(tmp_msg);
00076     }
00077   }
00078 
00079   for_each( message_actions::MessageAction action, actions )
00080   {
00081     callbacks_[action]( _msg);
00082   }
00083 }
00084 
00085 void MemoryListConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00086 {
00087   callbacks_[action] = cb;
00088 }
00089 
00090 }
00091 
00092 }


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