#include <module_param_cache.h>
Public Member Functions | |
| void | clearAll () |
| Clear all cache entries for this modules namespace (especially on the param server) | |
| bool | get (const std::string &key, ValueType &value) |
| Retrieve a cached value for key. | |
| void | initialize (const std::string &moduleNamespace, ros::NodeHandle *node) |
| Initialize the module param cache for param lookup. | |
| ModuleParamCache () | |
| void | set (const std::string &key, ValueType value, bool allowCacheAsParam) |
| Add a new cache entry. | |
| ~ModuleParamCache () | |
Private Attributes | |
| std::map< std::string, ValueType > | _localCache |
| local cache only for this planner run | |
| std::string | keyPrefix |
| ros::NodeHandle * | node |
| Param cache across multiple runs. | |
Static Private Attributes | |
| static std::string | baseNamespace = "/tfd_modules/module_cache" |
Module cache that allows to cache entries locally (for one run) or additionally on the param server between multiple runs. ValueType needs to be able to be written as a ROS param. It is assumed that during a planner run only this class accesses the module cache stored on the param server, i.e. nobody interferes.
Definition at line 24 of file module_param_cache.h.
| ModuleParamCache< ValueType >::ModuleParamCache | ( | ) |
Definition at line 12 of file module_param_cache.hpp.
| ModuleParamCache< ValueType >::~ModuleParamCache | ( | ) |
Definition at line 25 of file module_param_cache.hpp.
| void ModuleParamCache< ValueType >::clearAll | ( | ) |
Clear all cache entries for this modules namespace (especially on the param server)
Definition at line 30 of file module_param_cache.hpp.
| bool ModuleParamCache< ValueType >::get | ( | const std::string & | key, |
| ValueType & | value | ||
| ) |
Retrieve a cached value for key.
| [in] | key | the key for the entry |
| [out] | value | the retrieved value, if found. |
Definition at line 55 of file module_param_cache.hpp.
| void ModuleParamCache< ValueType >::initialize | ( | const std::string & | moduleNamespace, |
| ros::NodeHandle * | node | ||
| ) |
Initialize the module param cache for param lookup.
Definition at line 18 of file module_param_cache.hpp.
| void ModuleParamCache< ValueType >::set | ( | const std::string & | key, |
| ValueType | value, | ||
| bool | allowCacheAsParam | ||
| ) |
Add a new cache entry.
| [in] | key | the key for the entry |
| [in] | value | the value to cache for key |
| [in] | allowCacheAsParam | if true, cache entries are entered on the param server and thus are available between multiple planner calls. Therefore their value should obviously not change in the world throughout multiple calls. |
Definition at line 40 of file module_param_cache.hpp.
std::map<std::string, ValueType> ModuleParamCache< ValueType >::_localCache [private] |
local cache only for this planner run
Definition at line 62 of file module_param_cache.h.
std::string ModuleParamCache< ValueType >::baseNamespace = "/tfd_modules/module_cache" [static, private] |
Definition at line 56 of file module_param_cache.h.
std::string ModuleParamCache< ValueType >::keyPrefix [private] |
Definition at line 60 of file module_param_cache.h.
ros::NodeHandle* ModuleParamCache< ValueType >::node [private] |
Param cache across multiple runs.
Definition at line 59 of file module_param_cache.h.