Study/[ROS2] ROS2 Basic

ROS2 with python - Executors and Callback Groups

soohwan_justin 2023. 7. 28. 20:31

본 포스트는 ROS1에 대한 전반적인 지식이 있다는 가정 하에 작성되었으며, The Construct Youtube 영상을 참고하였습니다.

또한, 시뮬레이션 환경은 turtlebot3 waffle_pi를 사용합니다 : https://github.com/ROBOTIS-GIT/turtlebot3_simulations

 

 

 

1. 좀 더 복잡한 노드 다뤄보기

1. 다음과 같이 패키지를 만듭니다.

ros2 pkg create --build-type ament_python unit5_pkg --dependencies rclpy std_msgs sensor_msgs geometry_msgs nav_msgs

 

2. 위 패키지에 exercise51.py 파일을 만듭니다

exercise51.py

import rclpy
from rclpy.node import Node
import time
import numpy as np
from sensor_msgs.msg import LaserScan
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Twist
from rclpy.qos import ReliabilityPolicy, QoSProfile


class ControlClass(Node):

    def __init__(self, seconds_sleeping=5):
        super().__init__('sub_node')
        self._seconds_sleeping = seconds_sleeping
        self.vel_pub = self.create_publisher(Twist, 'cmd_vel', 10)
        self.odom_sub = self.create_subscription(Odometry, 'odom', self.odom_callback, 10)
        self.scan_sub = self.create_subscription(LaserScan, 'scan', self.scan_callback,
                                                 QoSProfile(depth=10, reliability=ReliabilityPolicy.BEST_EFFORT))

        self.timer = self.create_timer(0.5, self.timer_callback)
        self.cmd = Twist()
        self.laser_msg = LaserScan()

        self.roll = 0.0
        self.pitch = 0.0
        self.yaw = 0.0

    def odom_callback(self, msg):
        self.get_logger().info("Odom CallBack")
        orientation_q = msg.pose.pose.orientation
        orientation_list = [orientation_q.x,
                            orientation_q.y,
                            orientation_q.z,
                            orientation_q.w]
        (self.roll, self.pitch, self.yaw) = self.euler_from_quaternion(orientation_list)

    def scan_callback(self, msg):
        self.get_logger().info("Scan CallBack")
        self.laser_msg = msg

    def get_front_laser(self):
        return self.laser_msg.ranges[360]

    def get_yaw(self):
        return self.yaw

    def euler_from_quaternion(self, quaternion):
        """
        쿼터니언을 to 오일러 각 roll, pitch, yaw
        quaternion = [x, y, z, w]
        나중에 tf 패키지를 사용할 경우, 해당 패키지에서 제공하는 함수를 사용하면 된다.
        """
        x = quaternion[0]
        y = quaternion[1]
        z = quaternion[2]
        w = quaternion[3]

        sinr_cosp = 2 * (w * x + y * z)
        cosr_cosp = 1 - 2 * (x * x + y * y)
        roll = np.arctan2(sinr_cosp, cosr_cosp)

        sinp = 2 * (w * y - z * x)
        pitch = np.arcsin(sinp)

        siny_cosp = 2 * (w * z + x * y)
        cosy_cosp = 1 - 2 * (y * y + z * z)
        yaw = np.arctan2(siny_cosp, cosy_cosp)

        return roll, pitch, yaw

    def stop_robot(self):
        self.cmd.linear.x = 0.0
        self.cmd.angular.z = 0.0
        self.vel_pub.publish(self.cmd)

    def move_straight(self):
        self.cmd.linear.x = 0.15
        self.cmd.angular.z = 0.0
        self.vel_pub.publish(self.cmd)

    def rotate(self):
        self.cmd.angular.z = -0.2
        self.cmd.linear.x = 0.0
        self.vel_pub.publish(self.cmd)

        self.get_logger().info(f'Rotating for {self._seconds_sleeping} seconds')
        for i in range(self._seconds_sleeping):
            self.get_logger().info(f'SLEEPING == {i} seconds')
            time.sleep(1)

        self.stop_robot()

    def timer_callback(self):
        self.get_logger().info("Timer CallBack")
        try:
            self.get_logger().warning(f'>>>>> RANGES Value = {self.laser_msg.ranges[359]}')
            if not self.laser_msg.ranges[359] < 0.3:
                self.get_logger().info("MOVE STRAIGHT")
                self.move_straight()
            else:
                self.get_logger().info("STOP and ROTATE")
                self.stop_robot()
                self.rotate()
        except:
            pass


def main(args=None):
    rclpy.init(args=args)
    control_node = ControlClass()
    try:
        rclpy.spin(control_node)
    finally:
        control_node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

 

위 코드의 내용을 요약하자면,

- 전방 라이다의 0.3미터 이내에 장애물이 감지될 때 까지 전진합니다.

- 장애물이 감지되면 로봇이 멈추고, 회전합니다.

- 회전하는 시간은 self._seconds_sleeping 에 저장된 값입니다.

 

 

3. launch 파일을 만듭니다.

exercise51.launch.py

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='unit5_pkg',
            executable='exercise51',
            output='screen',
            emulate_tty=True), # 로그 메시지
    ])

 

4. setup.py 파일을 수정합니다

setup.py

from setuptools import setup
import os
from glob import glob

package_name = 'unit5_pkg'

setup(
    name=package_name,
    version='0.0.0',
    packages=[package_name],
    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        (os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py'))
    ],
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='somebody very awesome',
    maintainer_email='user@user.com',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
        'console_scripts': [
            'exercise51 = unit5_pkg.exercise51:main'
        ],
    },
)

 

5. 컴파일 후, 실행합니다

$ ros2 launch unit5_pkg exercise51.launch.py

 

사실 위의 코드에는 몇 가지 문제점이 있습니다.

- 우리는 센서 데이터를 받으면서 해당 데이터를 업데이트 해야합니다. 그러므로 timer_callback이 센서의 callback을 막으면 안됩니다. 위의 결과를 보면, timer_callback에 의해 제자리 회전하는 함수가 실행되는 동안 sensor callback이 실행되지 않는 것을 확인할 수 있습니다. 

- 근데, 실제 자동차를 생각해보면... 자동차가 새로운 센서 데이터를 얻을 때까지 기다린다고 기존의 이동 명령이 끝날 때까지 기다릴 수는 없습니다. 그래서 동시에 여러 프로세스를 실행해야 하는데, 이렇게 콜백끼리의 충돌을 피하기 위해 다수의 쓰레드를 사용합니다.

 

 

 

 

 

2. Executor와 Callback 그룹

우리는 Executors, Callback Groups을 사용해서 Callback의 실행을 제어할 수 있습니다.

- Executors는 Callbacks의 실행에 대한 권한을 갖습니다

- Callback Groups는 multiple Callbacks의 실행을 제어하기 위해 사용됩니다.

 

Executors

executor는 Callbacks를 처리하기 위해 사용되는 쓰레드 모델입니다. Callbacks란, Subscription Callbacks, Timer Callbacks, Service Callbacks...등 과 같은 work units입니다.

 

executors에는 다음과 같이 두 종류가 있습니다

- SingleThreadedExecutor : 단순한 executor입니다. 메인 쓰레드에서 Callbacks를 실행합니다(executor.spin()을 호출합니다)

- MultiThreadedExecutor : Callbacks를 병렬로 실행하기 위해 여러 개의 쓰레드를 돌릴 수 있게 해줍니다.

 

 

Callback Groups

Callback Groups는 Callbacks가 실행 될 수 있게 허가되었을 때, 이를 제어합니다.

 

Callback Groups는 다음과 같이 두 종류가 있습니다.

- ReentrantCallbackGroup : Callbacks가 제한 없이 병렬로 실행될 수 있도록 합니다

- MutuallyExeclusiveCallbackGroup : 특정 시간에 단 하나의 Callback만이 실행되도록 합니다

 

 

이제, 이전의 코드를 조금 수정해서 Callback Groups를 사용해보겠습니다.

 

1. exercise52.py 파일을 만듭니다.

exercise52.py

import rclpy
from rclpy.node import Node
import time
import numpy as np
from sensor_msgs.msg import LaserScan
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Twist
from rclpy.qos import ReliabilityPolicy, QoSProfile
# executors와 callback groups를 import
from rclpy.callback_groups import ReentrantCallbackGroup, MutuallyExclusiveCallbackGroup
from rclpy.executors import MultiThreadedExecutor, SingleThreadedExecutor

class ControlClass(Node):

    def __init__(self, seconds_sleeping=5):
        super().__init__('sub_node')
        self._seconds_sleeping = seconds_sleeping
        self.vel_pub = self.create_publisher(Twist, 'cmd_vel', 10)
        
        # callback group 생성
        self.group = MutuallyExclusiveCallbackGroup()

        self.odom_sub = self.create_subscription(Odometry, 'odom', self.odom_callback, 10, callback_group=self.group)
        self.scan_sub = self.create_subscription(LaserScan, 'scan', self.scan_callback,
                                                 QoSProfile(depth=10, reliability=ReliabilityPolicy.BEST_EFFORT),
                                                 callback_group=self.group)
        self.timer = self.create_timer(0.5, self.timer_callback, callback_group=self.group)

        self.cmd = Twist()
        self.laser_msg = LaserScan()

        self.roll = 0.0
        self.pitch = 0.0
        self.yaw = 0.0

    def odom_callback(self, msg):
        self.get_logger().info("Odom CallBack")
        orientation_q = msg.pose.pose.orientation
        orientation_list = [orientation_q.x,
                            orientation_q.y,
                            orientation_q.z,
                            orientation_q.w]
        (self.roll, self.pitch, self.yaw) = self.euler_from_quaternion(orientation_list)

    def scan_callback(self, msg):
        self.get_logger().info("Scan CallBack")
        self.laser_msg = msg

    def get_front_laser(self):
        return self.laser_msg.ranges[360]

    def get_yaw(self):
        return self.yaw

    def euler_from_quaternion(self, quaternion):
        """
        쿼터니언을 to 오일러 각 roll, pitch, yaw
        quaternion = [x, y, z, w]
        나중에 tf 패키지를 사용할 경우, 해당 패키지에서 제공하는 함수를 사용하면 된다.
        """
        x = quaternion[0]
        y = quaternion[1]
        z = quaternion[2]
        w = quaternion[3]

        sinr_cosp = 2 * (w * x + y * z)
        cosr_cosp = 1 - 2 * (x * x + y * y)
        roll = np.arctan2(sinr_cosp, cosr_cosp)

        sinp = 2 * (w * y - z * x)
        pitch = np.arcsin(sinp)

        siny_cosp = 2 * (w * z + x * y)
        cosy_cosp = 1 - 2 * (y * y + z * z)
        yaw = np.arctan2(siny_cosp, cosy_cosp)

        return roll, pitch, yaw

    def stop_robot(self):
        self.cmd.linear.x = 0.0
        self.cmd.angular.z = 0.0
        self.vel_pub.publish(self.cmd)

    def move_straight(self):
        self.cmd.linear.x = 0.10
        self.cmd.angular.z = 0.0
        self.vel_pub.publish(self.cmd)

    def rotate(self):
        self.cmd.angular.z = -0.2
        self.cmd.linear.x = 0.0
        self.vel_pub.publish(self.cmd)

        self.get_logger().info(f'Rotating for {self._seconds_sleeping} seconds')
        for i in range(self._seconds_sleeping):
            self.get_logger().info(f'SLEEPING == {i} seconds')
            time.sleep(1)

        self.stop_robot()

    def timer_callback(self):
        self.get_logger().info("Timer CallBack")
        try:
            self.get_logger().warning(f'>>>>> RANGES Value = {self.laser_msg.ranges[359]}')
            if not self.laser_msg.ranges[359] < 0.5:
                self.get_logger().info("MOVE STRAIGHT")
                self.move_straight()
            else:
                self.get_logger().info("STOP and ROTATE")
                self.stop_robot()
                self.rotate()
        except:
            pass


def main(args=None):
    rclpy.init(args=args)
    control_node = ControlClass()

    executor = SingleThreadedExecutor()
    executor.add_node(control_node)

    try:
        executor.spin()
    finally:
        executor.shutdown()
        control_node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

 

2. launch 파일을 만듭니다.

exercise52.launch.py

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='unit5_pkg',
            executable='exercise52',
            output='screen',
            emulate_tty=True),
    ])

 

3. setup.py 파일을 수정합니다.

setup.py

from setuptools import setup
import os
from glob import glob

package_name = 'unit5_pkg'

setup(
    name=package_name,
    version='0.0.0',
    packages=[package_name],
    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        (os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py'))
    ],
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='somebody very awesome',
    maintainer_email='user@user.com',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
        'console_scripts': [
            'exercise51 = unit5_pkg.exercise51:main',
            'exercise52 = unit5_pkg.exercise52:main',
        ],
    },
)

 

 

4.빌드 후, 실행해봅니다.

 

근데 실행해보면 이전과 별 다를게 없을 것입니다. 왜냐면 단일 쓰레드 executor를 사용했기 때문입니다. 그럼 이번엔 다중 쓰레드 executor를 사용해보겠습니다.

 

이전과 똑같은 과정을 진행하는데,

- 파이썬 파일은 exercise53.py라고 하고,

- 3개의 Callback을 위해 3개의 MutuallyExeclusiveCallbackGroup를 만듭니다.

- SingleThreadedExecutorMultiThreadedExecutor 바꿉니다.

 

setup.py

import rclpy
from rclpy.node import Node
import time
import numpy as np
from sensor_msgs.msg import LaserScan
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Twist
from rclpy.qos import ReliabilityPolicy, QoSProfile
# executors와 callback groups를 import
from rclpy.callback_groups import ReentrantCallbackGroup, MutuallyExclusiveCallbackGroup
from rclpy.executors import MultiThreadedExecutor, SingleThreadedExecutor

class ControlClass(Node):

    def __init__(self, seconds_sleeping=5):
        super().__init__('sub_node')
        self._seconds_sleeping = seconds_sleeping
        self.vel_pub = self.create_publisher(Twist, 'cmd_vel', 10)
        
        # callback group 생성
        self.group1 = MutuallyExclusiveCallbackGroup()
        self.group2 = MutuallyExclusiveCallbackGroup()
        self.group3 = MutuallyExclusiveCallbackGroup()

        self.odom_sub = self.create_subscription(Odometry, 'odom', self.odom_callback, 10, callback_group=self.group1)
        self.scan_sub = self.create_subscription(LaserScan, 'scan', self.scan_callback,
                                                 QoSProfile(depth=10, reliability=ReliabilityPolicy.BEST_EFFORT),
                                                 callback_group=self.group2)
        self.timer = self.create_timer(0.5, self.timer_callback, callback_group=self.group3)

        self.cmd = Twist()
        self.laser_msg = LaserScan()

        self.roll = 0.0
        self.pitch = 0.0
        self.yaw = 0.0

    def odom_callback(self, msg):
        self.get_logger().info("Odom CallBack")
        orientation_q = msg.pose.pose.orientation
        orientation_list = [orientation_q.x,
                            orientation_q.y,
                            orientation_q.z,
                            orientation_q.w]
        (self.roll, self.pitch, self.yaw) = self.euler_from_quaternion(orientation_list)

    def scan_callback(self, msg):
        self.get_logger().info("Scan CallBack")
        self.laser_msg = msg

    def get_front_laser(self):
        return self.laser_msg.ranges[360]

    def get_yaw(self):
        return self.yaw

    def euler_from_quaternion(self, quaternion):
        """
        쿼터니언을 to 오일러 각 roll, pitch, yaw
        quaternion = [x, y, z, w]
        나중에 tf 패키지를 사용할 경우, 해당 패키지에서 제공하는 함수를 사용하면 된다.
        """
        x = quaternion[0]
        y = quaternion[1]
        z = quaternion[2]
        w = quaternion[3]

        sinr_cosp = 2 * (w * x + y * z)
        cosr_cosp = 1 - 2 * (x * x + y * y)
        roll = np.arctan2(sinr_cosp, cosr_cosp)

        sinp = 2 * (w * y - z * x)
        pitch = np.arcsin(sinp)

        siny_cosp = 2 * (w * z + x * y)
        cosy_cosp = 1 - 2 * (y * y + z * z)
        yaw = np.arctan2(siny_cosp, cosy_cosp)

        return roll, pitch, yaw

    def stop_robot(self):
        self.cmd.linear.x = 0.0
        self.cmd.angular.z = 0.0
        self.vel_pub.publish(self.cmd)

    def move_straight(self):
        self.cmd.linear.x = 0.10
        self.cmd.angular.z = 0.0
        self.vel_pub.publish(self.cmd)

    def rotate(self):
        self.cmd.angular.z = -0.2
        self.cmd.linear.x = 0.0
        self.vel_pub.publish(self.cmd)

        self.get_logger().info(f'Rotating for {self._seconds_sleeping} seconds')
        for i in range(self._seconds_sleeping):
            self.get_logger().info(f'SLEEPING == {i} seconds')
            time.sleep(1)

        self.stop_robot()

    def timer_callback(self):
        self.get_logger().info("Timer CallBack")
        try:
            self.get_logger().warning(f'>>>>> RANGES Value = {self.laser_msg.ranges[359]}')
            if not self.laser_msg.ranges[359] < 0.5:
                self.get_logger().info("MOVE STRAIGHT")
                self.move_straight()
            else:
                self.get_logger().info("STOP and ROTATE")
                self.stop_robot()
                self.rotate()
        except:
            pass


def main(args=None):
    rclpy.init(args=args)
    control_node = ControlClass()

    executor = MultiThreadedExecutor(num_threads=4)
    executor.add_node(control_node)

    try:
        executor.spin()
    finally:
        executor.shutdown()
        control_node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

 

 

실행 결과, 회전 도중에도 계속 odom, scan callbacks가 들어오는 것을 확인할 수 있습니다.

 

executor = MultiThreadedExecutor(num_threads=4)

에서 num_threads로 넣어줄 수 있는 최댓값은 glance(sudo apt-get install glances로 설치)나 파이썬에서 바로 확인할 수 있습니다.

 

 

 

MultiThreadedExecutor와 multiple Callback Group에 대해 좀 더 설명을 하자면...

예를 들어 공장에 컨베이어 벨트가 있고, 그 벨트에서 일해야 할 사람이 있는 상황을 가정해보겠습니다. 이때, 각 컨베이어 벨트는 Callback Groups고, 그 컨베이어로 들어오는 물건들이 Callbacks입니다.

이렇게 들어오는 물건들을 처리할 사람들이 Thread입니다. Callback_Groups가 3개이고 num_threads = 3이면, 각각의 Callback_Groups에 사람이 하나씩 붙어있는 것입니다.

 

 

3. Callback Group 더 알아보기

이전 예제에서는 MutuallyExclusiveCallbackGroup을 사용했습니다. ROS2에서는 디폴트로 이 타입을 사용합니다. 또다른 타입으로는 ReentrantCallbackGroup이 있는데, 둘의 차이점으로는...

 

- ReentrantCallbackGroup : 충분한 Threads가 있는 한, 이 그룹에 있는 모든 callbacks는 병렬로 실행될 수 있습니다. 예를 들어, 여분의 Threads가 2개인데 하나의 ReentrantCallbackGroup에 3개의 Callbacks이 들어오면 2개의 Threads를 사용하여 이 Callbacks을 처리합니다.

- MutuallyExclusiveCallbackGroup : 이 그룹에 있는 모든 Callbacks은 Threads의 여분이 몇 개가 있든 한 번에 하나씩 처리됩니다.

 

 

 

다음 예제에서는 1개의 service server와 하나의 timer callback이 있는 경우에 대해 진행해보겠습니다. 

 

1. callback_groups_examples.py 파일을 만듭니다.

callback_groups_examples.py

from pickle import TRUE
from std_srvs.srv import SetBool
import rclpy
from rclpy.node import Node
import time

from rclpy.callback_groups import ReentrantCallbackGroup, MutuallyExclusiveCallbackGroup
from rclpy.executors import MultiThreadedExecutor, SingleThreadedExecutor
from rclpy.qos import ReliabilityPolicy, QoSProfile

import argparse


class DummyServer(Node):

    def __init__(self, args, callback_group_type="reentrant"):

        self.timer_flag = True

        super().__init__('service_start_turn')

        parser = argparse.ArgumentParser(
            description='Dummy Server to Learn about Callback Groups and Threads')

        # 서비스 호출 시 대기시간
        parser.add_argument('-service_wait_time',
                            type=float,
                            help='Time the service will be waiting',
                            required=True)

        # timer callback 주기
        parser.add_argument('-timer_period',
                            type=float,
                            nargs=1,
                            metavar='TIMEOUT',
                            default=1.0,
                            help="Time period of the Callback for the timer")

        # callback group 타입
        parser.add_argument('-callback_group_type',
                            type=str,
                            default="reentrant",
                            help="Type of Callback Groups REENTRANT of EXCLUSIVE")

        # thread 개수
        parser.add_argument('-threads',
                            type=int,
                            default=1,
                            help="Number of threads to use in the executor")

        self.args = parser.parse_args(args[1:])

        parser.print_help()
        print("## DEFAULT Node Callback Group=" + str(self.default_callback_group))

        self.get_logger().warning(f'Setting {self.args.callback_group_type} Groups')
        if self.args.callback_group_type == "reentrant":
            self.group1 = ReentrantCallbackGroup()
            self.get_logger().warning("ReentrantCallbackGroup Set")
            # ReentrantCallback이므로, service와 timer를 같은 그룹에 넣습니다
            self.srv = self.create_service(
                SetBool, '/dummy_server_srv', self.SetBool_callback, callback_group=self.group1)
            self.timer = self.create_timer(
                self.args.timer_period[0], self.timer_callback, callback_group=self.group1)

        elif self.args.callback_group_type == "exclusive":
            self.group1 = MutuallyExclusiveCallbackGroup()
            self.group2 = MutuallyExclusiveCallbackGroup()
            self.get_logger().warning("MutuallyExclusiveCallbackGroup Set")
            # MutuallyExclusiveCallback이므로, service와 timer를 다른 그룹에 넣습니다
            self.srv = self.create_service(
                SetBool, '/dummy_server_srv', self.SetBool_callback, callback_group=self.group1)
            self.timer = self.create_timer(
                self.args.timer_period[0], self.timer_callback, callback_group=self.group2)

        else:
            # callback group이 없는 경우, 디폴트로 실행합니다
            self.get_logger().error("NO GROUPS SET Set")
            self.srv = self.create_service(
                SetBool, '/dummy_server_srv', self.SetBool_callback)
            self.timer = self.create_timer(
                self.args.timer_period[0], self.timer_callback)

    def get_threads(self):
        return self.args.threads

    def SetBool_callback(self, request, response):
        self.get_logger().warning("Processing Server Message...")
        self.wait_for_sec(self.args.service_wait_time)
        self.get_logger().warning("Processing Server Message...DONE")
        response.message = 'TURNING'
        return response

    def wait_for_sec(self, wait_sec, delta=1.0):
        i = 0
        while i < wait_sec:
            self.get_logger().info(f'... {i} [WAITING...]')
            time.sleep(delta)
            i += delta

    def timer_callback(self):
        self.print_dummy_msgs()

    def print_dummy_msgs(self):
        if self.timer_flag:
            self.get_logger().info("TICK")
            self.timer_flag = False
        else:
            self.get_logger().info("TACK")
            self.timer_flag = True


def main(args=None):
    # ros2 run unit5_pkg callback_groups_examples -service_wait_time 5.0 -timer_period 1.0
    rclpy.init(args=args)
    print(f'args=== + {args}')
    # Format the arguments given through ROS to use the arguments
    args_without_ros = rclpy.utilities.remove_ros_args(args)
    print(f'clean ROS args=== {args_without_ros}')
    start_stop_service_node = DummyServer(args_without_ros)

    num_threads = start_stop_service_node.get_threads()
    start_stop_service_node.get_logger().info(
        f'DummyServer Started with threads = {num_threads}')

    executor = MultiThreadedExecutor(num_threads=num_threads)
    executor.add_node(start_stop_service_node)

    try:
        executor.spin()
    finally:
        executor.shutdown()
        start_stop_service_node.destroy_node()

    rclpy.shutdown()


if __name__ == '__main__':
    main()

 

 

2. setup.py 파일을 수정합니다

setup.py

 

from setuptools import setup
import os
from glob import glob

package_name = 'unit5_pkg'

setup(
    name=package_name,
    version='0.0.0',
    packages=[package_name],
    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        (os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py'))
    ],
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='somebody very awesome',
    maintainer_email='user@user.com',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
        'console_scripts': [
            'exercise51 = unit5_pkg.exercise51:main',
            'exercise52 = unit5_pkg.exercise52:main',
            'exercise53 = unit5_pkg.exercise53:main',
            'callback_groups_examples = unit5_pkg.callback_groups_examples:main',
        ],
    },
)

 

 

3. 빌드 후, 다음 명령으로 실행해보면서 결과가 어떻게 달라지는지 확인해보세요.

threads, callback_group_type를 바꿔보면서 결과를 확인해보세요

$ ros2 run unit5_pkg callback_groups_examples -service_wait_time 5.0 -timer_period 1.0 -callback_group_type exclusive -threads 2
$ ros2 run unit5_pkg callback_groups_examples -service_wait_time 5.0 -timer_period 1.0 -callback_group_type reentrant -threads 2
$ ros2 run unit5_pkg callback_groups_examples -service_wait_time 5.0 -timer_period 1.0 -callback_group_type reentrant -threads 1

 

위 명령을 실행 후, 아래 명령으로 서비스를 보내면 됩니다. 보내는 값은 true든 false든 상관없습니다

$ ros2 service call /dummy_server_srv std_srvs/srv/SetBool data:\ false\