21 #ifndef OBJECTMANAGER_HPP_ 22 #define OBJECTMANAGER_HPP_ 27 #include "asr_object_database/ObjectMetaData.h" 46 std::map<std::pair<std::string, std::string>, ObjectMetaData::Response::Ptr>
object_type_cache;
49 object_type_service_client = mNodeHandle.
serviceClient<ObjectMetaData>(
"/asr_object_database/object_meta_data");
65 if (!statePtr->object_type_service_client.exists()) {
69 ObjectTypeResponsePtr responsePtr = statePtr->object_type_cache[std::make_pair(objectTypeName, recognizer)];
72 ObjectMetaData serviceCall;
73 serviceCall.request.object_type = objectTypeName;
74 serviceCall.request.recognizer = recognizer;
75 statePtr->object_type_service_client.call(serviceCall);
76 if (!serviceCall.response.is_valid) {
81 statePtr->object_type_cache[std::make_pair(objectTypeName, recognizer)] = responsePtr;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceClient object_type_service_client
ObjectTypeResponse::Ptr ObjectTypeResponsePtr
ros::NodeHandle mNodeHandle
ObjectMetaData::Response ObjectTypeResponse
::xsd::cxx::tree::string< char, simple_type > string
static boost::shared_ptr< State > InstancePtr()
std::map< std::pair< std::string, std::string >, ObjectMetaData::Response::Ptr > object_type_cache