module_param_cache.hpp
Go to the documentation of this file.
00001 /*
00002  * module_param_cache.cpp
00003  *
00004  *  Created on: 19 Jul 2012
00005  *      Author: andreas
00006  */
00007 
00008 template <class ValueType>
00009 std::string ModuleParamCache<ValueType>::baseNamespace = "/tfd_modules/module_cache";
00010 
00011 template <class ValueType>
00012 ModuleParamCache<ValueType>::ModuleParamCache()
00013 {
00014     node = NULL;
00015 }
00016 
00017 template <class ValueType>
00018 void ModuleParamCache<ValueType>::initialize(const std::string& moduleNamespace, ros::NodeHandle* node)
00019 {
00020     this->node = node;
00021     keyPrefix = ModuleParamCache<ValueType>::baseNamespace + "/" + moduleNamespace + "/";
00022 }
00023 
00024 template <class ValueType>
00025 ModuleParamCache<ValueType>::~ModuleParamCache()
00026 {
00027 }
00028 
00029 template <class ValueType>
00030 void ModuleParamCache<ValueType>::clearAll()
00031 {
00032     if(node->hasParam(keyPrefix))
00033     {
00034         node->deleteParam(keyPrefix);
00035     }
00036     _localCache.clear();
00037 }
00038 
00039 template <class ValueType>
00040 void ModuleParamCache<ValueType>::set(const std::string& key, ValueType value, bool allowCacheAsParam)
00041 {
00042 //    ROS_INFO("[cache]: writing to cache: %s -> %f", key.c_str(), value);
00043     if(allowCacheAsParam) {
00044         typename std::map<std::string, ValueType>::iterator it = _localCache.find(key);
00045         // if we found the same key,value in the local cache, it was inserted by this function and thus
00046         // is already on the param server, no need to make an extra setParam call here.
00047         if(it == _localCache.end() || it->second != value) {
00048             node->setParam(keyPrefix + key, value);
00049         }
00050     }
00051     _localCache.insert(std::make_pair(key, value));
00052 }
00053 
00054 template <class ValueType>
00055 bool ModuleParamCache<ValueType>::get(const std::string& key, ValueType& value)
00056 {
00057 //    ROS_INFO("[cache]: lookup in cache: %s -> %f", key.c_str(), value);
00058     typename std::map<std::string, ValueType>::iterator it = _localCache.find(key);
00059     if(it != _localCache.end()) {       // local cache hit
00060         value = it->second;
00061         return true;
00062     }
00063     // local miss, look on param server
00064     bool found = node->getParamCached(keyPrefix + key, value);
00065     if(found) { // we found this on the param server, insert locally to prevent additional setParam calls
00066         _localCache.insert(std::make_pair(key, value));
00067     }
00068     return found;
00069 }
00070 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


planner_modules_pr2
Author(s): Christian Dornhege, Andreas Hertle
autogenerated on Wed Dec 26 2012 15:49:38