<> <> The ROS [[Parameter Server]] can store strings, integers, floats, booleans, lists, dictionaries, iso8601 dates, and base64-encoded data. Dictionaries must have string keys. [[roscpp]]'s parameter API supports all of these, though it is only easy to use strings, integers, floats and booleans. Support for the other options is done using the [[http://docs.ros.org/api/xmlrpcpp/html/classXmlRpc_1_1XmlRpcValue.html|XmlRpc::XmlRpcValue class]] [[roscpp]] has two different parameter APIs: the "bare" versions which live in the [[http://docs.ros.org/api/roscpp/html/namespaceros_1_1param.html|ros::param ]] namespace, and the "handle" versions which are called through the [[http://docs.ros.org/api/roscpp/html/classros_1_1NodeHandle.html|ros::NodeHandle]] interface. Both versions will be explained for each operation below. == Getting Parameters == Fetch a value from the parameter server. Each version supports strings, integers, doubles, booleans and [[http://docs.ros.org/api/xmlrpcpp/html/classXmlRpc_1_1XmlRpcValue.html|XmlRpc::XmlRpcValue]]s. `false` is returned if the parameter does not exist, or is not of the right type. There is also a version that returns a default value. `ros::NodeHandle::getParam()` Parameters retrieved through the `NodeHandle` version are resolved relative to that `NodeHandle`'s namespace. See the [[roscpp/Overview/NodeHandles|roscpp NodeHandles overview]] for more information. {{{ #!cplusplus ros::NodeHandle nh; std::string global_name, relative_name, default_param; if (nh.getParam("/global_name", global_name)) { ... } if (nh.getParam("relative_name", relative_name)) { ... } // Default value version nh.param("default_param", default_param, "default_value"); }}} `ros::param::get()` Parameters retrieved through the "bare" version are resolved relative to the node's namespace. {{{ #!cplusplus std::string global_name, relative_name, default_param; if (ros::param::get("/global_name", global_name)) { ... } if (ros::param::get("relative_name", relative_name)) { ... } // Default value version ros::param::param("default_param", default_param, "default_value"); }}} === Cached Parameters === `ros::NodeHandle::getParamCached()` and `ros::param::getCached()` provide local caching of parameter data. Using these versions informs the [[Parameter Server]] that this node would like to be notified when the parameter is changed, and prevents the node from having to re-lookup the value with the parameter server on subsequent calls. Cached parameters are a significant speed increase (after the first call), but should be used sparingly to avoid overloading the master. Cached parameters are also currently less reliable in the case of intermittent connection problems between your node and the master. == Setting Parameters == Similar to getting parameters, each version supports strings, integers, doubles, booleans and [[http://docs.ros.org/api/xmlrpcpp/html/classXmlRpc_1_1XmlRpcValue.html|XmlRpc::XmlRpcValue]]s. `ros::NodeHandle::setParam()` Parameters retrieved through the `NodeHandle` version are resolved relative to that `NodeHandle`'s namespace. See the [[roscpp/Overview/NodeHandles|roscpp NodeHandle overview]] for more information. {{{ #!cplusplus ros::NodeHandle nh; nh.setParam("/global_param", 5); nh.setParam("relative_param", "my_string"); nh.setParam("bool_param", false); }}} `ros::param::set()` Parameters retrieved through the "bare" version are resolved relative to the node's namespace. {{{ #!cplusplus ros::param::set("/global_param", 5); ros::param::set("relative_param", "my_string"); ros::param::set("bool_param", false); }}} == Checking Parameter Existence == `ros::NodeHandle::hasParam()` {{{ #!cplusplus ros::NodeHandle nh; if (nh.hasParam("my_param")) { ... } }}} `ros::param::has()` {{{ #!cplusplus if (ros::param::has("my_param")) { ... } }}} == Deleting Parameters == `ros::NodeHandle::deleteParam()` {{{ #!cplusplus ros::NodeHandle nh; nh.deleteParam("my_param"); }}} `ros::param::del()` {{{ #!cplusplus ros::param::del("my_param"); }}} == Accessing Private Parameters == Accessing private parameters is done differently depending on whether you're using the "handle" or "bare" interfaces. In the handle interface you must create a new `ros::NodeHandle` with the private namespace as its namespace: {{{ #!cplusplus ros::NodeHandle nh("~"); std::string param; nh.getParam("private_name", param); }}} In the bare interface you can access private parameters with the same notation used to describe them, e.g.: {{{ #!cplusplus std::string param; ros::param::get("~private_name", param); }}} == Searching for Parameter Keys == There are times where you want to get a parameter from the ''closest'' namespace. For example, if you have a "`robot_name`" parameter, you just want to search upwards from your private namespace until you find a matching parameter. Similarly, if you have a group of camera nodes, you may wish to set some parameters commonly in a shared namespace but override others by setting them in a private (`~name`) namespace. '''Note:''' in order to use `search` effectively, you should use it with ''relative'' names instead of `/global` and `~private` names. `ros::NodeHandle::searchParam()` {{{ #!cplusplus std::string key; if (nh.searchParam("bar", key)) { std::string val; nh.getParam(key, val); } }}} `ros::param::search()` {{{ #!cplusplus std::string key; if (ros::param::search("bar", key)) { std::string val; ros::param::get(key, val); } }}} == Retrieve list of parameter names == <> You can get list of existing parameter names as `std::vector` of strings. you can get vectors with both the `ros::NodeHandle::getParamNames` interface or the `ros::param::search` interface: {{{ #!cplugplus // Create a ROS node handle ros::NodeHandle nh; std::vector keys; nh.getParamNames(keys) }}} {{{ #!cplugplus std::vector keys; ros::param::search(keys) }}} == Retrieving Lists == <> You can get and set lists and dictionaries of primitives and strings as `std::vector` and `std::map` containers with the following templated value types: * bool * int * float * double * string For example, you can get vectors and maps with both the `ros::NodeHandle::getParam` / `ros::NodeHandle::setParam` interface or the `ros::param::get` / `ros::param::set` interface: {{{ #!cplusplus // Create a ROS node handle ros::NodeHandle nh; // Construct a map of strings std::map map_s, map_s2; map_s["a"] = "foo"; map_s["b"] = "bar"; map_s["c"] = "baz"; // Set and get a map of strings nh.setParam("my_string_map", map_s); nh.getParam("my_string_map", map_s2); // Sum a list of doubles from the parameter server std::vector my_double_list; double sum = 0; nh.getParam("my_double_list", my_double_list); for(unsigned i=0; i < my_double_list.size(); i++) { sum += my_double_list[i]; } }}} On ROS Fuerte and earlier, lists on the parameter server can only be retreived through the use of the [[http://docs.ros.org/api/xmlrpcpp/html/classXmlRpc_1_1XmlRpcValue.html|XmlRpc::XmlRpcValue]] class, which can represent any of the types on the parameter server. This is still a valid method in later ROS versions. {{{ #!cplusplus XmlRpc::XmlRpcValue my_list; nh.getParam("my_list", my_list); ROS_ASSERT(my_list.getType() == XmlRpc::XmlRpcValue::TypeArray); for (int32_t i = 0; i < my_list.size(); ++i) { ROS_ASSERT(my_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble); sum += static_cast(my_list[i]); } }}}