dynamic_reconfigure

GUI :

$ sudo apt-get install ros-$DISTRO-rqt-reconfigure
$ rosrun rqt_reconfigure rqt_reconfigure

CUI :

$ rosrun dynamic_reconfigure dynparam {COMMAND}

  • list : list configurable nodes, $ rosrun dynamic_reconfigure dynparam list
  • get : get node configuration, $ rosrun dynamic_reconfigure dynparam get /node
  • set : configure node
  • Set the configurable parameter of a node to a value. , $ rosrun dynamic_reconfigure dynparam set /node parameter_name value
  • Set multiple configurable parameters of a node to a value.$ rosrun dynamic_reconfigure dynparam set wge100_camera "{'camera_url':'foo', 'brightness':58}"
  • set_from_parameters : copy configuration from parameter server, $ rosrun dynamic_reconfigure dynparam set_from_parameters /node
  • dump : dump configuration to file, $ rosrun dynamic_reconfigure dynparam dump /node dump.yaml
  • load : load configuration from file, $ rosrun dynamic_reconfigure dynparam load /node dump.yaml

1. 설정 파일 지정

1.1 패키지 및 설정 파일 생성

catkin_create_pkg --rosdistro {ROSDISTRO} {dynamic_tutorials} rospy roscpp dynamic_reconfigure
mkdir cfg
vi ./cfg/MY.cfg

1.2 설정 파일 작성

#!/usr/bin/env python
PACKAGE = "dynamic_tutorials"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
gen.add("double_param", double_t, 0, "A double parameter", .5, 0, 1)
gen.add("str_param", str_t, 0, "A string parameter", "Hello World")
gen.add("bool_param", bool_t, 0, "A Boolean parameter", True)
"""
gen.add(name, type, level, description, defaults, min, max)
- add function adds a parameter to the list of parameters
. name - a string which specifies the name under which this parameter should be stored
. type - defines the type of value stored, and can be any of int_t, double_t, str_t, or bool_t
. level - A bitmask which will later be passed to the dynamic reconfigure callback. When the callback is called all of the level values for parameters that have been changed are ORed together and the resulting value is passed to the callback.
. description - string which describes the parameter
. default - specifies the default value
. min - specifies the min value (optional and does not apply to strings and bools)
. max - specifies the max value (optional and does not apply to strings and bools)
"""

exit(gen.generate(PACKAGE, "dynamic_tutorials", "Tutorials"))
"""
The last line simply tells the generator to generate the necessary files and exit the program.
. The second parameter is the name of a node this could run in (used to generate documentation only),
. the third parameter is a name prefix the generated files will get (e.g. "<name>Config.h" for c++, or "<name>Config.py" for python.
. 중요 : 3rd 파라미터는 cfg파일 이름과 같아야 한다(확장자 제외).
"""

1.3 설정 파일 사용 가능하게 permission 조정 CMake에 알림

chmod a+x cfg/NY.cfg
python

vi CMakeLists.txt

#add dynamic reconfigure api
#find_package(catkin REQUIRED dynamic_reconfigure)
generate_dynamic_reconfigure_options(
cfg/Tutorials.cfg
#...
)
# make sure configure headers are built before any node using them
add_dependencies(example_node ${PROJECT_NAME}_gencfg)

2. 노드 생성

cd ~/catkin_ws/src/{dynamic_tutorials}
mkdir src
mkdir node

vi ./node/server.py

#!/usr/bin/env python

import rospy

from dynamic_reconfigure.server import Server
from dynamic_tutorials.cfg import TutorialsConfig #설정 파일
#The name TutorialsConfig is automatically generated by appending Config to the 3rd argument in gen.generate

def callback(config, level):
rospy.loginfo("""Reconfigure Request: {int_param}, {double_param},\
{str_param}, {bool_param}, {size}""".format(**config))
return config

if __name__ == "__main__":
rospy.init_node("dynamic_tutorials", anonymous = True)

srv = Server(TutorialsConfig, callback)
rospy.spin()

3. 실행

chmod +x nodes/server.py
rosrun rqt_gui rqt_gui -s reconfigure

vi ./node/client.py

줄 번호 보이기/숨기기
#!/usr/bin/env python

import rospy

import dynamic_reconfigure.client

def callback(config):
rospy.loginfo("Config set to {int_param}, {double_param}, {str_param}, {bool_param}, {size}".format(**config))

"""
We then define a callback which will print the config returned by the server.
. There are two main differences between this callback and the servers, one it does not need to return an updated config object, two it does not have the "level" argument.
. This callback is optional.
"""


if __name__ == "__main__":
rospy.init_node("dynamic_client")

client = dynamic_reconfigure.client.Client("dynamic_tutorials", timeout=30, config_callback=callback)

r = rospy.Rate(0.1)
x = 0
b = False
while not rospy.is_shutdown():
x = x+1
if x>10:
x=0
b = not b
client.update_configuration({"int_param":x, "double_param":(1/(x+1)), "str_param":str(rospy.get_rostime()), "bool_param":b, "size":1})
r.sleep()

"""
Lastly we initialize ROS and our Client.
. Our main loop runs once every ten seconds and simply calls update_configuration on the client every time.
. Note that you need not use a full configuration and could also pass in a dictionary with only one of the parameters as well.
"""

Run It!

Once again make the node executable: chmod +x nodes/client.py Launch a core and your server node, and launch your new client node. If you've done everything correctly, both your client and server should begin to print out matching configurations every ten seconds.

results matching ""

    No results matching ""