Contents
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 XmlRpc::XmlRpcValue class
roscpp has two different parameter APIs: the "bare" versions which live in the ros::param namespace, and the "handle" versions which are called through the 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 XmlRpc::XmlRpcValues. 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 NodeHandles overview for more information.
1 ros::NodeHandle nh; 2 std::string global_name, relative_name, default_param; 3 if (nh.getParam("/global_name", global_name)) 4 { 5 ... 6 } 7 8 if (nh.getParam("relative_name", relative_name)) 9 { 10 ... 11 } 12 13 // Default value version 14 nh.param<std::string>("default_param", default_param, "default_value");
ros::param::get()
- Parameters retrieved through the "bare" version are resolved relative to the node's namespace.
1 std::string global_name, relative_name, default_param; 2 if (ros::param::get("/global_name", global_name)) 3 { 4 ... 5 } 6 7 if (ros::param::get("relative_name", relative_name)) 8 { 9 ... 10 } 11 12 // Default value version 13 ros::param::param<std::string>("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 XmlRpc::XmlRpcValues.
ros::NodeHandle::setParam()
Parameters retrieved through the NodeHandle version are resolved relative to that NodeHandle's namespace. See the roscpp NodeHandle overview for more information.
ros::param::set()
- Parameters retrieved through the "bare" version are resolved relative to the node's namespace.
Checking Parameter Existence
ros::NodeHandle::hasParam()
ros::param::has()
Deleting Parameters
ros::NodeHandle::deleteParam()
ros::param::del()
1 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:
In the bare interface you can access private parameters with the same notation used to describe them, e.g.:
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()
ros::param::search()
Retrieve list of parameter names
New in ROS indigo
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:
// Create a ROS node handle ros::NodeHandle nh; std::vector<std::string> keys; nh.getParamNames(keys)
std::vector<std::string> keys; ros::param::search(keys)
Retrieving Lists
New in ROS groovy
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:
1 // Create a ROS node handle
2 ros::NodeHandle nh;
3
4 // Construct a map of strings
5 std::map<std::string,std::string> map_s, map_s2;
6 map_s["a"] = "foo";
7 map_s["b"] = "bar";
8 map_s["c"] = "baz";
9
10 // Set and get a map of strings
11 nh.setParam("my_string_map", map_s);
12 nh.getParam("my_string_map", map_s2);
13
14 // Sum a list of doubles from the parameter server
15 std::vector<double> my_double_list;
16 double sum = 0;
17 nh.getParam("my_double_list", my_double_list);
18 for(unsigned i=0; i < my_double_list.size(); i++) {
19 sum += my_double_list[i];
20 }
On ROS Fuerte and earlier, lists on the parameter server can only be retreived through the use of the XmlRpc::XmlRpcValue class, which can represent any of the types on the parameter server. This is still a valid method in later ROS versions.
1 XmlRpc::XmlRpcValue my_list;
2 nh.getParam("my_list", my_list);
3 ROS_ASSERT(my_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
4
5 for (int32_t i = 0; i < my_list.size(); ++i)
6 {
7 ROS_ASSERT(my_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
8 sum += static_cast<double>(my_list[i]);
9 }