navigationros2tutorialamrcpppythonlaunch

ROS 2 từ A đến Z (P3): Parameters, Launch, Lifecycle

Cấu hình node linh hoạt bằng Parameters, khởi động cả hệ thống bằng Launch files, và quản lý vòng đời node với Lifecycle — đầy đủ ví dụ C++ và Python (Jazzy, 6/2026).

Nguyễn Anh Tuấn6 tháng 2, 20267 phút đọcCập nhật: 14 thg 6, 2026
ROS 2 từ A đến Z (P3): Parameters, Launch, Lifecycle

Phần 2, bạn đã nắm Topics, Services và Actions — cách các node nói chuyện với nhau. Nhưng một hệ thống robot thật có hàng chục node, mỗi node cần cấu hình (tốc độ tối đa, cổng serial, tần số…), cần được khởi động cùng lúc theo đúng thứ tự, và đôi khi cần bật/tắt có kiểm soát. Đó là ba công cụ của bài này: Parameters, Launch files, và Lifecycle nodes.

Phiên bản (6/2026): Dùng ROS 2 Jazzy (Ubuntu 24.04). Mọi ví dụ có cả C++ (rclcpp)Python (rclpy). Trên Humble đổi jazzyhumble.

Cấu hình và khởi động hệ thống ROS 2
Cấu hình và khởi động hệ thống ROS 2

1. Parameters — cấu hình node mà không sửa code

Hãy tưởng tượng node điều khiển motor của bạn có tốc độ tối đa max_speed = 0.5. Nếu hard-code số này, mỗi lần đổi robot bạn phải sửa code và build lại. Parameters cho phép đặt giá trị này từ ngoài — qua dòng lệnh, file YAML, hoặc lúc runtime.

Khai báo và đọc parameter

Python (rclpy):

# minimal_param.py
import rclpy
from rclpy.node import Node


class ParamDemo(Node):
    def __init__(self):
        super().__init__('param_demo')

        # Khai báo parameter với giá trị mặc định
        self.declare_parameter('max_speed', 0.5)
        self.declare_parameter('robot_name', 'turtle')

        # Đọc giá trị
        speed = self.get_parameter('max_speed').value
        name = self.get_parameter('robot_name').value
        self.get_logger().info(f'{name} chạy tối đa {speed} m/s')


def main():
    rclpy.init()
    rclpy.spin(ParamDemo())
    rclpy.shutdown()

C++ (rclcpp):

// minimal_param.cpp
#include "rclcpp/rclcpp.hpp"

class ParamDemo : public rclcpp::Node
{
public:
  ParamDemo() : Node("param_demo")
  {
    // Khai báo parameter với giá trị mặc định
    this->declare_parameter<double>("max_speed", 0.5);
    this->declare_parameter<std::string>("robot_name", "turtle");

    double speed = this->get_parameter("max_speed").as_double();
    std::string name = this->get_parameter("robot_name").as_string();
    RCLCPP_INFO(this->get_logger(), "%s chạy tối đa %.2f m/s",
                name.c_str(), speed);
  }
};

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<ParamDemo>());
  rclcpp::shutdown();
}

Đặt parameter từ ngoài

# Đặt trực tiếp khi chạy node
ros2 run my_pkg param_demo --ros-args -p max_speed:=1.2 -p robot_name:=amr_01

# Xem tất cả parameter của một node
ros2 param list /param_demo

# Đọc/ghi runtime
ros2 param get /param_demo max_speed
ros2 param set /param_demo max_speed 0.8

File parameter YAML

Với nhiều parameter, dùng file YAML gọn hơn:

# config/robot_params.yaml
param_demo:
  ros__parameters:
    max_speed: 1.0
    robot_name: "amr_warehouse"
    pid:
      kp: 1.2
      ki: 0.05
      kd: 0.1
ros2 run my_pkg param_demo --ros-args --params-file config/robot_params.yaml

Parameter callback — phản ứng khi giá trị đổi

Điều mạnh nhất: node tự cập nhật khi parameter thay đổi runtime (không cần restart).

Python:

from rcl_interfaces.msg import SetParametersResult

class ParamDemo(Node):
    def __init__(self):
        super().__init__('param_demo')
        self.declare_parameter('max_speed', 0.5)
        self.max_speed = self.get_parameter('max_speed').value
        # Đăng ký callback
        self.add_on_set_parameters_callback(self.on_param_change)

    def on_param_change(self, params):
        for p in params:
            if p.name == 'max_speed' and p.value > 0:
                self.max_speed = p.value
                self.get_logger().info(f'max_speed cập nhật: {p.value}')
        return SetParametersResult(successful=True)

Mẹo thực tế: Luôn validate trong callback (vd max_speed > 0). Nếu trả successful=False, ROS 2 từ chối giá trị xấu — robot không bị set tốc độ âm do gõ nhầm.

2. Launch files — khởi động cả hệ thống bằng một lệnh

Một AMR cần chạy: driver LiDAR, node odometry, robot_state_publisher, node điều khiển… Gõ ros2 run từng cái rất mệt. Launch file khởi động tất cả cùng lúc, truyền parameter, và remap topic — chỉ bằng một lệnh.

ROS 2 dùng launch file viết bằng Python (linh hoạt hơn XML của ROS 1).

# launch/robot_bringup.launch.py
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory


def generate_launch_description():
    pkg = get_package_share_directory('my_pkg')
    params_file = os.path.join(pkg, 'config', 'robot_params.yaml')

    # Tham số dòng lệnh: ros2 launch ... use_sim_time:=true
    use_sim_time = LaunchConfiguration('use_sim_time')

    return LaunchDescription([
        DeclareLaunchArgument('use_sim_time', default_value='false'),

        # Node điều khiển motor — nạp param từ YAML
        Node(
            package='my_pkg',
            executable='param_demo',
            name='param_demo',
            parameters=[params_file, {'use_sim_time': use_sim_time}],
            output='screen',
        ),

        # Node sensor — remap topic /scan → /lidar/scan
        Node(
            package='my_pkg',
            executable='lidar_node',
            remappings=[('/scan', '/lidar/scan')],
        ),
    ])
# Chạy cả hệ thống
ros2 launch my_pkg robot_bringup.launch.py use_sim_time:=true

Include launch khác

Tái sử dụng launch file của package khác (vd Nav2) bằng IncludeLaunchDescription:

from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

nav2 = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(
        os.path.join(get_package_share_directory('nav2_bringup'),
                     'launch', 'navigation_launch.py')),
    launch_arguments={'use_sim_time': 'true'}.items(),
)

Đây chính là cách ta sẽ ghép Nav2 vào robot ở Phần 6.

3. Lifecycle nodes — node có vòng đời quản lý được

Node thường (rclcpp::Node) khởi động là chạy ngay. Nhưng với phần cứng quan trọng (driver LiDAR, motor), bạn muốn kiểm soát: cấu hình trước, kích hoạt sau, tắt an toàn. Đó là Lifecycle node (managed node).

Một lifecycle node có 4 trạng thái chính, chuyển đổi qua các transition:

   ┌──────────────┐  configure   ┌──────────┐  activate   ┌────────┐
   │ Unconfigured │ ───────────► │ Inactive │ ──────────► │ Active │
   └──────────────┘              └──────────┘ ◄────────── └────────┘
          ▲                           │       deactivate
          └───────────────────────────┘
                  cleanup
  • Unconfigured: vừa tạo, chưa làm gì.
  • Inactive: đã cấu hình (mở file, cấp phát buffer) nhưng chưa xử lý dữ liệu.
  • Active: đang chạy thật — publish, đọc sensor.
  • Finalized: đã shutdown.

Vì sao hữu ích: với một fleet robot, bạn có thể configure tất cả driver, kiểm tra mọi thứ OK, rồi mới activate đồng loạt — tránh tình trạng node A chạy trước khi node B sẵn sàng.

Python (rclpy lifecycle):

import rclpy
from rclpy.lifecycle import Node, State, TransitionCallbackReturn


class LidarDriver(Node):
    def __init__(self):
        super().__init__('lidar_driver')

    def on_configure(self, state: State) -> TransitionCallbackReturn:
        # Mở cổng serial, cấp phát buffer — CHƯA publish
        self.get_logger().info('Configuring: mở /dev/ttyUSB0')
        self._pub = self.create_lifecycle_publisher(...)  # ví dụ
        return TransitionCallbackReturn.SUCCESS

    def on_activate(self, state: State) -> TransitionCallbackReturn:
        self.get_logger().info('Activating: bắt đầu đọc LiDAR')
        return super().on_activate(state)

    def on_deactivate(self, state: State) -> TransitionCallbackReturn:
        self.get_logger().info('Deactivating: tạm dừng')
        return super().on_deactivate(state)

    def on_cleanup(self, state: State) -> TransitionCallbackReturn:
        self.get_logger().info('Cleanup: đóng serial')
        return TransitionCallbackReturn.SUCCESS

C++ (rclcpp_lifecycle):

#include "rclcpp_lifecycle/lifecycle_node.hpp"
using CallbackReturn =
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class LidarDriver : public rclcpp_lifecycle::LifecycleNode
{
public:
  LidarDriver() : rclcpp_lifecycle::LifecycleNode("lidar_driver") {}

  CallbackReturn on_configure(const rclcpp_lifecycle::State &) override
  {
    RCLCPP_INFO(get_logger(), "Configuring: mở serial");
    return CallbackReturn::SUCCESS;
  }
  CallbackReturn on_activate(const rclcpp_lifecycle::State & s) override
  {
    LifecycleNode::on_activate(s);  // kích hoạt publisher
    RCLCPP_INFO(get_logger(), "Activating");
    return CallbackReturn::SUCCESS;
  }
  CallbackReturn on_deactivate(const rclcpp_lifecycle::State & s) override
  {
    LifecycleNode::on_deactivate(s);
    return CallbackReturn::SUCCESS;
  }
};

Điều khiển transition từ CLI:

# Xem trạng thái hiện tại
ros2 lifecycle get /lidar_driver

# Chuyển trạng thái
ros2 lifecycle set /lidar_driver configure
ros2 lifecycle set /lidar_driver activate

Khi nào KHÔNG cần lifecycle: node logic đơn giản (một bộ lọc, một bộ chuyển đổi) thì node thường là đủ. Lifecycle đáng dùng cho driver phần cứng và các node mà thứ tự khởi động quan trọng.

Pitfalls thường gặp

  1. Quên declare_parameter trước khi get — ROS 2 sẽ báo ParameterNotDeclaredException. Luôn declare trước.
  2. Launch file không thấy node — chưa colcon build lại sau khi sửa setup.py/CMakeLists.txt, hoặc chưa source install/setup.bash.
  3. Param YAML sai tên node — key trong YAML phải khớp name của node (hoặc dùng /** wildcard để áp cho mọi node).
  4. Lifecycle publisher không ra dữ liệu — quên gọi super().on_activate(); publisher của lifecycle node chỉ phát khi ở trạng thái Active.

Tổng kết

Bài này cho bạn 3 công cụ vận hành hệ thống ROS 2 thực tế:

  • Parameters — cấu hình node từ ngoài, đổi runtime, có validation.
  • Launch files — khởi động cả hệ thống, truyền param, remap, include launch khác.
  • Lifecycle nodes — quản lý vòng đời node phần cứng có kiểm soát.

Phần 4, ta sẽ mô tả hình dạng robot bằng URDF, theo dõi quan hệ toạ độ giữa các bộ phận bằng TF2, và nhìn tất cả trong RViz2.


Bài viết liên quan

NT

Nguyễn Anh Tuấn

Robotics & AI Engineer. Building VnRobo — sharing knowledge about robot learning, VLA models, and automation.

Khám phá VnRobo

Bài viết liên quan

ROS 2 từ A đến Z (P4): TF2, URDF và RViz2
navigation

ROS 2 từ A đến Z (P4): TF2, URDF và RViz2

20/2/20267 phút đọc
NT
ROS 2 từ A đến Z (P6): Nav2 — Robot tự hành
navigation

ROS 2 từ A đến Z (P6): Nav2 — Robot tự hành

20/3/202611 phút đọc
NT
ROS 2 từ A đến Z (Phần 2): Topics, Services và Actions
navigation

ROS 2 từ A đến Z (Phần 2): Topics, Services và Actions

21/1/202610 phút đọc
NT