[UPDATED ANSWER]
Hello,
If you want to update the parameters in run-time, you should use the "dynamic reconfigure".
Basically, what you need is a parameter file, like below:
<your_package>/cfg/MyParams.cfg
#!/usr/bin/env python
PACKAGE = 'my_dyn_rec'
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
#list of parameters
gen.add('int_param', int_t, 0, "description for the integer parameter", 50, 0, 100)
gen.add('str_param', str_t, 0, "description for the string parameter", "Hello world!")
exit(gen.generate(PACKAGE, "my_dyn_rec", "MyParams"))
The node you want to work with the parameters, here is an example:
<your_package>/src/my_node.cpp
#include <ros/ros.h>
#include <dynamic_reconfigure/server.h>
#include <my_dyn_rec/MyParamsConfig.h>
void callback(my_dyn_rec::MyParamsConfig &config, uint32_t level) {
ROS_INFO("New values: [%d] - [%s]", config.int_param, config.str_param.c_str());
}
int main(int argc, char **argv) {
ros::init(argc, argv, "my_node");
dynamic_reconfigure::Server<my_dyn_rec::MyParamsConfig> server;
dynamic_reconfigure::Server<my_dyn_rec::MyParamsConfig>::Callback f;
f = boost::bind(&callback, _1, _2);
server.setCallback(f);
ros::spin();
return 0;
}
Finally, you CMakeLists.txt must be configured. For this example, this should be enough:
cmake_minimum_required(VERSION 2.8.3)
project(my_dyn_rec)
find_package(catkin REQUIRED COMPONENTS
dynamic_reconfigure
roscpp
rospy
)
generate_dynamic_reconfigure_options(
cfg/MyParams.cfg
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(my_node src/my_node.cpp)
add_dependencies(my_node ${PROJECT_NAME}_gencfg)
target_link_libraries(my_node
${catkin_LIBRARIES}
)
You can follow some the tutorials below:
ROS wiki oficial tutorial:
http://wiki.ros.org/dynamic_reconfigu...
And a video I created:
https://youtu.be/YKZkZSVcsnI
Just making sure we understand what you want to do: if the node doesn't repeatedly reloads its parameters, setting them 'in runtime' vs using
rosparam load ..
is not going to change anything.rosparam load ..
I believe does what you are asking: it updates parameters on the parameters server .... potentially while nodes are running. But it doesn't magically change the values of configuration variables inside nodes. For that, the node must reread the parameters itself.
But: for dynamically changing parameters, it's better to use dyn_recfg.