ROS2의 파라미터(Parameter)는 ROS1의 parameter server
와 dynamic_reconfigure
패키지의 기능을 모두 가지고 있어 노드가 동작하는 동안 특정값에 대한 저장, 변경, 회수가 가능하다.
ROS2의 모든 노드는 파라미터 서버(Parameter server)를 가지고 있어서 파라미터 클라이언트(Parameter client)와 서비스 통신을 통해 파라미터에 접근할 수 있도록 구현되어 있다.
서비스가 특정 태스크 수행을 위한 요청과 응답이라는 RPC(Remote Procedure Call)에 가까운 목적이었다면, 파라미터는 특정 매개변수를 노드 내부 또는 외부에서 쉽게 저장(Set)하거나 변경할수 있고, 쉽게 회수(Get)하여 사용할 수 있게 하는 점에서 그 사용 목적이 다르다고 할 수 있다. 파라미터의 개념이 부족하다면 아래 링크를 보고 오는것을 추천한다.
우리는 이전 장에서 토픽, 서비스, 액션 프로그래밍을 익히기 위하여 argument, operator, calculator, checker 노드를 작성해 봤다. 이들 노드 중에서 아래 그림과 같이 argument 노드와 calcultor 노드는 파라미터를 사용하고 있다. argument 노드는 QoS 설정과 랜덤으로 생성되는 변수 a, b 의 생성 범위를 파라미터를 통해 생성할 수 있고, calculator 노드는 QoS 설정에 파라미터를 사용하였다. 우리는 여기서 argument 노드에서 사용되는 파라미터에 대해 자세히 알아볼것이다.
argument 노드에서 파라미터를 선언하고 해당 파라미터 값이 변경되는 함수에 대해 알아보자.
⭐️ROS2에서 파라미터를 사용하려면 다음과 같이 크게 3가지 함수가 필요하다.
1) declare_parameter 함수
2) get_parameter 함수
3) add_on_set_parameters_callback 함수
declar_parameter
함수는 노드에서 사용할 파라미터의 고유 이름을 지정하고 초깃값을 설정한다. 파라미터를 설명하는 descriptor를 추가하기도 하는데 여기서는 생략했다.
get_parameter
함수는 노드에서 사용할 파라미터의 값을 불러오는 것으로 선언된 파라미터 고유 이름을 이용한다. 이는 주로 런치 파일에서 호출된 *.yaml
확장자를 가지는 파라미터 파일에 저장된 값을 불러오는데 사용된다.
add_on_set_parameters_callback
함수는 서비스 형태로 파라미터 변경 요청이 있을 때 사용되는 함수로 지정된 콜백 함수를 호출하게 된다.
class Argument(Node):
def __init__(self):
super().__init__('argument')
self.declare_parameter('qos_depth', 10)
qos_depth = self.get_parameter('qos_depth').value
self.declare_parameter('min_random_num', 0)
self.min_random_num = self.get_parameter('min_random_num').value
self.declare_parameter('max_random_num', 9)
self.max_random_num = self.get_parameter('max_random_num').value
self.add_on_set_parameters_callback(self.update_parameter)
<생략>
def update_parameter(self, params):
for param in params:
if param.name == 'min_random_num' and param.type_ == Parameter.Type.INTEGER:
self.min_random_num = param.value
elif param.name == 'max_random_num' and param.type_ == Parameter.Type.INTEGER:
self.max_random_num = param.value
return SetParametersResult(successful=True)
예를 들어 다음과 같이 declare_parameter 함수로 max_random_num 파라미터를 선언했을때, 노드 실행 시 get_paramter 함수를 통해 호출된 파라미터 파일에 저장된 파라미터 초깃값을 가져와 설정할 수 있다. 그 뒤 파라미터 변경 요청이 있을 때는 add_on_set_parameters_callback 함수를 통해 지정된 콜백 함수인 update_parameter 함수를 실행하게 된다. update_parameter 콜백 함수에서는 변경하려는 파라미터의 이름과 파라미터 타입이 같을 때에 해당 파라미터 값을 변경하게 된다.
self.declare_parameter('max_random_num', 9)
self.max_random_num = self.get_parameter('max_random_num').value
<생략>
def update_parameter(self, params):
for param in params:
if param.name == 'min_random_num' and param.type_ == Parameter.Type.INTEGER:
self.min_random_num = param.value
elif param.name == 'max_random_num' and param.type_ == Parameter.Type.INTEGER:
self.max_random_num = param.value
return SetParametersResult(successful=True)
argument 노드는 랜덤으로 생성되는 변수 a, b의 생성 범위를 파라미터를 통해 설정할 수 있도록 했는데 다음 코드와 같이 파라미터 값을 담고 있는 min_random_num 변수와 max_random_num 변수를 이용하였다.
def publish_random_arithmetic_arguments(self):
msg = ArithmeticArgument()
msg.stamp = self.get_clock().now().to_msg()
msg.argument_a = float(random.randint(self.min_random_num, self.max_random_num))
msg.argument_b = float(random.randint(self.min_random_num, self.max_random_num))
self.arithmetic_argument_publisher.publish(msg)
self.get_logger().info('Published argument a: {0}'.format(msg.argument_a))
self.get_logger().info('Published argument b: {0}'.format(msg.argument_b))
파라미터 관련 설정을 모두 마쳤으면 argument 노드를 실행시키고 ros2 param CLI를 이용하여 파라미터를 조회하고, 변경하고 읽어보는 실습을 하겠다. 우선 다음과 같이 argument 노드를 실행하면 변수 a, b는 0과 9 사이의 랜덤한 값으로 퍼블리시 되는 것을 확인할 수 있다.
$ ros2 run topic_service_action_rclpy_example argument
[INFO]: Published argument a: 8.0
[INFO]: Published argument b: 6.0
[INFO]: Published argument a: 9.0
[INFO]: Published argument b: 4.0
...
파라미터들의 목록을 확인하는 방법은 ros2 param list
명령어를 이용하는 것이다. 이를 이용하면 argument 노드에 max_random_num, min_random_num, qos_depth 파라미터가 있음을 확인할 수 있다. 이는 위 코드에서 declar_parameter 함수로 선언한 3가지 파라미터와 동일함을 알 수 있다. use_sim_time 파라미터는 모든 노드의 기본 파라미터이기에 함께 표시되고 있다.
$ ros2 param list
/argument:
max_random_num
min_random_num
qos_depth
use_sim_time
현재의 파라미터의 값을 확인하는 방법은 다음과 같이 ros2 param get
명령어를 이용하여 특정 노드 이름과 파라미터 이름을 인자로 사용하면 된다. 그 결과 max_random_num 파라미터의 값은 9임을 알 수 있다.
$ ros2 param get /argument max_random_num
Integer value is: 9
이번에는 max_random_num 파라미터 값을 100으로 변경해보자. 현재의 파라미터의 값을 변경하는 방법은 ros2 param set
명령어를 이용해 특정 노드 이름과 파라미터 이름 그리고 변경하고자 하는 값을 인자로 사용하면 된다.
$ ros2 param set /argument max_random_num 100
Set parameter successful
이 변경이 완료되면 다음과 같이 argument 노드가 실행된 창에 출력되는 값을 통해 랜덤으로 생성되는 변수 a, b의 범위가 달라졌음을 확인할 수 있다.
[INFO]: Published argument a: 42.0
[INFO]: Published argument b: 52.0
[INFO]: Published argument a: 51.0
[INFO]: Published argument b: 65.0
...
CLI를 이용하여 파라미터를 조회하고, 변경하고, 읽어보는 실습을 해보았다. 파라미터는 다른 노드를 통해서도 읽고 변경할 수 있다. 예를 들어 다음의 코드를 통해 SetParameters 인터페이스를 이용하여 서비스 클라이언트를 만들고 서비스 요청을 통해 파라미터를 변경할 수 있는 모습을 확인할 수 있다.
여기서 클라이언트 선언 부분 및 서비스를 요청하는 부분은 서비스 클라이언트와 완전히 동일하다. 다른 부분을 꼽자면 서비스 요청값으로 파라미터의 이름과 형태, 값을 지정하는 게 다르다. 이 부분은 set_max_random_num_parameter 함수에 자세히 기술되어 있는데 Parameter 클래스를 선언하고 매개변수로 매개변수로 name, type, integer_value 등을 설정하게 되어 있다. 이를 통해 A노드에서 B노드의 파라미터를 변경할 수 있게 된다.
from rcl_interfaces.msg import Parameter
from rcl_interfaces.msg import ParameterType
from rcl_interfaces.msg import ParameterValue
from rcl_interfaces.srv import SetParameters
(생략)
self.random_num_parameter_client = self.create_client(
SetParameters,
'argument/set_parameters')
(생략)
def set_max_random_num_parameter(self, max_value):
request = SetParameters.Request()
parameter = ParameterValue(type=ParameterType.PARAMETER_INTEGER, integer_value=max_value)
request.parameters = [Parameter(name='max_random_num', value=parameter)]
service_client = self.random_num_parameter_client
return self.call_service(service_client, request, 'max_random_num parameter')
def call_service(self, service_client, request, service_name):
wait_count = 1
while not service_client.wait_for_service(timeout_sec=0.1):
if wait_count > 3:
self.get_logger().warn(service_name + ' service is not available.')
return False
wait_count += 1
service_client.call_async(request)
return True
한두 개의 파라미터의 경우 이를 선언(Declare)하고, 읽어(Get)오고, 변경(Set)하는 방법을 어려움 없이 사용 가능하다. 하지만 하나의 노드에 수 십 개의 파라미터 그리고 수 십 개의 노드가 실행된다면 관리해야 할 파라미터가 많아져서 매번 설정하기 어렵다. 이에 복수 개의 파라미터를 저장하고 노드 실행 시 지정된 파라미터로 초깃값을 주고 싶을 때에는 파라미터 파일(*.yaml)을 작성하고 이를 런치 파일에서 불러오는 방법을 사용한다.
우선 다음과 같은 파라미터 파일을 arithmetic_config.yaml
이름으로 지정한 후에 패키지의 param 폴더에 저장한다. 위 설명에서 살펴본 3개의 파라미터 이름과 초깃값이 기재되어 있음을 확인할 수 있다.
/**: # namespace and node name
ros__parameters:
qos_depth: 30
min_random_num: 0
max_random_num: 9
정석대로라면 다음과 같이 네임스페이스와 노드 이름으로 구분을 해줘야 하는데 네임스페이스와 노드 이름은 변경의 가능성이 높기에 위와 같이 /**을 사용하는게 편하다.
namespace:
node_name:
ros__parameters:
qos_depth: 30
min_random_num: 0
max_random_num: 9
그 뒤 다음과 같이 런치 파일에서 LaunchConfiguration
함수의 인자로 파라미터 파일의 경로를 지정하고 LaunchDescription
함수의 인자로 Node
함수를 이용하여 parameters 인자에 앞서 지정한 파라미터 파일의 경로를 지정하면 된다. 런치 파일에 대해서는 추후에 자세히 알아보겠다.
def generate_launch_description():
param_dir = LaunchConfiguration(
'param_dir',
default=os.path.join(
get_package_share_directory('topic_service_action_rclpy_example'),
'param',
'arithmetic_config.yaml'))
return LaunchDescription([
DeclareLaunchArgument(
'param_dir',
default_value=param_dir,
description='Full path of parameter file'),
Node(
package='topic_service_action_rclpy_example',
executable='argument',
name='argument',
parameters=[param_dir],
output='screen'),
Node(
package='topic_service_action_rclpy_example',
executable='calculator',
name='calculator',
parameters=[param_dir],
output='screen'),
])
새롭게 지정된 *.yaml
파일 및 *.launch.py
파일을 ROS 파일 시스템에 맞추어 설치하려면 다음과 같이 파이썬 패키지 설정 파일(setup.py)에 옵션을 추가해야한다.
(share_dir + '/launch', glob.glob(os.path.join('launch', '*.launch.py'))),
(share_dir + '/param', glob.glob(os.path.join('param', '*.yaml'))),
위와 같이 런치 파일에 특정 파라미터 파일을 추가해주면 해당 런치 파일로 노드를 실행할 때에는 지정된 파라미터 파일의 파라미터 이름과 파라미터 값을 확인하여 해당 노드의 파라미터를 초기화해 사용할 수 있다.
ROS2의 파라미터 프로그래밍에 대해 알아보았다. 다음 장에서는 실행인자 프로그래밍 코드를 분석해보겠다.