로봇 통합
새 로봇을 PLEM에 통합하는 방법을 외부 사용자 관점에서 설명합니다.
빠른 개요
통합 흐름도
Builder 패턴 사용 (C++ API)
C++ 애플리케이션에서 직접 로봇을 생성할 때:
#include <plem/robot/robot_builder.hpp>
#include "plem/robot/models/your_robot.hpp" // 사용자 정의 로봇 Config
// 1. Config 준비
YourRobot config;
config.network_interface = "eth0";
config.cycle_time = std::chrono::microseconds(1000); // 1kHz
config.rt_priority = 98;
// joint_offsets: 엔코더 오프셋 (int32_t 배열, 로봇별 캘리브레이션 값)
// 실제 값은 RobotProfile에서 로드하거나 캘리브레이션 과정에서 결정됨
config.joint_offsets = {0, 0, 0, 0, 0, 0};
// 2. Builder로 로봇 생성
auto result = Robot::builder<YourRobot>(config).build();
if (!result) {
std::cerr << "Failed to create robot: " << result.message() << std::endl;
return -1;
}
std::unique_ptr<IRobot> robot = std::move(result.value());
// 3. 시작
robot->start();
// 4. 플래너와 실행기 주입
robot->set_planner(std::make_shared<PilzPlanner>(node));
robot->set_executor(std::make_shared<TrajectoryExecutor>(node, "joint_trajectory_controller"));
// 5. 모션 명령
auto traj = robot->move_j({0.0, 0.5, -0.5, 0.0, 1.0, 0.0}, 0.3);
if (traj) {
robot->execute(traj.value());
}
set_planner()/set_executor() 없이 free function을 직접 사용할 수도 있습니다.
plem::robot::move_j(planner, dof, joint_names, planning_group, target, speed) — 자세한 내용은 <plem/robot/motion_functions.hpp>를 참조하세요.
다중 로봇 (동일 호스트)
한 호스트에서 여러 로봇을 실행할 때, with_robot_id()로 IPC와 ROS2 네임스페이스를 자동 격리합니다:
// 각 로봇에 고유 ID와 별도의 EtherCAT 마스터를 지정
config_a.network_interface = "eth0";
config_a.master_index = 0;
auto robot_a = Robot::builder<YourRobot>(config_a)
.with_robot_id("arm_left")
.build().value();
config_b.network_interface = "eth1";
config_b.master_index = 1;
auto robot_b = Robot::builder<YourRobot>(config_b)
.with_robot_id("arm_right")
.build().value();
// IPC: /arm_left_joint_actual_values, /arm_right_joint_actual_values
// ROS2: /arm_left/rt_raw, /arm_right/rt_raw
robot_id를 생략하면 기존 단일 로봇과 동일하게 동작합니다.
프로덕션 실행 파일 (main.cpp)
위의 Builder 예제는 핵심 API만 보여줍니다. 실제 production 환경에서는 ROS2 Bridge, 모니터링, 시그널 처리가 필요합니다.
다음은 완전한 main.cpp 템플릿입니다:
#include <memory>
#include <string>
#include <rclcpp/rclcpp.hpp>
#include <plem/core/logging/logger.hpp>
#include <plem/monitoring.hpp>
#include <plem/robot/robot_builder.hpp>
#include <plem/ros2_adapter/bridge.hpp>
#include "your_robot_package/your_factory.hpp" // RobotFactory 특수화 포함
using plem::core::logger;
int main(int argc, char* argv[]) {
// 1. ROS2 초기화 (Bridge.start() 전에 필수)
rclcpp::init(argc, argv);
// 2. 로봇 Config 준비 + Builder로 생성
your_ns::YourRobotConfig config;
config.network_interface = "eth0";
config.rt_priority = 98;
config.joint_offsets = {0, 0, 0, 0, 0, 0};
auto result = plem::robot::Robot::builder(config)
.with_robot_id("my_robot") // IPC/ROS2 네임스페이스 격리
.build();
if (!result) {
logger.error("Failed to create robot: {}", result.message());
rclcpp::shutdown();
return EXIT_FAILURE;
}
auto robot = std::move(result).value();
// 3. ROS2 Bridge 생성 (모니터링, 모드 제어, 상태 퍼블리싱)
plem::ros2_adapter::Bridge bridge(*robot);
// 4. RT 스레드 시작 → Bridge 시작
int rc = robot->start();
if (rc != 0) {
logger.error("Failed to start robot");
rclcpp::shutdown();
return EXIT_FAILURE;
}
bridge.start();
// 5. Ctrl+C까지 대기 (시그널 처리는 PLEM 내부에서 자동)
logger.info("Robot running. Press Ctrl+C to stop.");
robot->wait_for_shutdown();
// 6. 정리 (Bridge 소멸자가 자동으로 stop() 호출)
plem::monitoring::shutdown();
rclcpp::shutdown();
return EXIT_SUCCESS;
}
실행 순서 요약:
| 단계 | 호출 | 역할 |
|---|---|---|
rclcpp::init() | ROS2 런타임 초기화 | Bridge가 ROS2 노드를 생성하기 위해 필요 |
Robot::builder().build() | 로봇 인스턴스 생성 | Config 검증, Factory 호출, 리소스 할당 |
Bridge bridge(*robot) | ROS2 adapter 생성 | 모니터링/모드제어/상태 publisher 노드 준비 |
robot->start() | RT 스레드 시작 | EtherCAT 통신, 토크 계산, IPC bridge |
bridge.start() | ROS2 노드 스레드 시작 | /rt_raw, /set_mode, /robot_status 토픽 활성화 |
wait_for_shutdown() | 종료 신호 대기 | Ctrl+C (SIGINT) 수신 시 반환 |
monitoring::shutdown() | 모니터링 큐 정리 | RT 큐 드레인 |
rclcpp::shutdown() | ROS2 런타임 정리 | 노드 종료 |
create_robot scaffold가 생성하는 main.cpp는 최소 뼈대(robot->run())만 포함합니다.
ROS2 토픽 모니터링이 필요하면 위 패턴으로 확장하세요.
Launch 아키텍처
PLEM은 composable launch 구조를 제공합니다.
개별 컴포넌트 Launch 파일
| Launch 파일 | 역할 | 주요 인수 |
|---|---|---|
rt_driver.launch.py | RT driver 실행 | eth_interface, description_package, robot_type |
ros2_control.launch.py | ros2_control stack 시작 | description_package, robot_type |
moveit.launch.py | MoveIt motion planning 시작 | description_package, robot_type |
moveit_only_launch.py | 단일 로봇 MoveIt + namespace 격리 | name, robot_type |
multi_robot.launch.py | 다중 로봇 동시 실행 | robots (comma-separated names) |
통합 Launch 파일 (내부 개발/빠른 테스트용)
plem_launch.py는 모든 컴포넌트를 조율하여 순차적으로 실행합니다:
# 통합 실행 (빠른 테스트, 모든 컴포넌트 시작)
ros2 launch plem_bringup plem_launch.py description_package:=my_robot_description
# 또는 내장 로봇 타입 사용
ros2 launch plem_bringup plem_launch.py robot_type:=indy7_v2
용도: 프로토타이핑, 전체 기능 테스트, 내부 개발
특징: RT driver, ROS2 Control, MoveIt, Python Bridge (plem_ai_server) 모두 자동 실행
Scaffold Launch 파일 (외부 사용자 권장)
외부 로봇 통합 시 scaffold 도구로 생성된 launcher 사용:
# 1. Description package 생성 (launch 파일은 기본 생성됨)
ros2 run plem_bringup create_description --name my_robot --dof 6
# 2. 생성된 bringup.launch.py 편집하여 필요한 컴포넌트만 활성화
# 3. 커스텀 launcher 실행
ros2 launch my_robot_description bringup.launch.py
용도: Production 배포, 리소스 최적화
특징: 필요한 컴포넌트만 선택 가능, 로봇별 커스터마이징
자세한 내용은 ROS2 Launch 시스템 가이드를 참조하세요.
Convention-Based 발견
description_package 인수 제공 시, PLEM은 다음 규약으로 파일을 자동 발견합니다:
| 파일 유형 | 경로 규약 | 용도 |
|---|---|---|
| URDF | urdf/<robot_name>.urdf.xacro | 로봇 기구학, ros2_control 태그 |
| SRDF | srdf/<robot_name>.srdf.xacro | MoveIt 설정 (planning groups, poses) |
| Joint Limits | config/joint_limits.yaml | 위치/속도/가속도/저크 제한 |
| Controllers | config/controllers.yaml | ros2_control controller 설정 |
| Initial Positions | config/initial_positions.yaml | 로봇 시작 자세 (선택) |
로봇 이름 감지: Package 이름에서 _description 접미사를 제거하여 자동 추출합니다 (ur5e_description → ur5e).
자세한 protocol 명세는 Description Protocol 문서를 참조하세요.
Scaffold 도구
새 description package를 빠르게 생성:
ros2 run plem_bringup create_description \
--name my_robot \
--dof 6 \
--manufacturer "Vendor"
생성된 구조:
my_robot_description/
├── CMakeLists.txt # ament_cmake 빌드 설정
├── package.xml # ROS2 패키지 메타데이터
├── PLEM_COMPAT_VERSION # 호환성 버전 파일
├── README.md # 사용 가이드
├── config/
│ └── joint_limits.yaml # 조인트 제한값 (SSoT)
├── launch/
│ └── bringup.launch.py # Scaffold launcher
└── urdf/
├── my_robot.urdf.xacro # 로봇 URDF (joint limits는 YAML에서 자동 로드)
└── my_robot.ros2_control.xacro # ros2_control 하드웨어 interface
URDF의 조인트 제한값은 joint_limits.yaml에서 xacro.load_yaml로 자동 로드됩니다. URDF에 제한값을 하드코딩할 필요가 없습니다.
다음 단계: 생성된 템플릿을 로봇의 실제 parameter로 편집합니다.
검증 절차
실제 하드웨어 테스트
# 1. EtherCAT 설정 확인
sudo systemctl status ethercat
ethercat slaves # 서보가 감지되는지 확인
# 2. Launch 파일로 시스템 시작
ros2 launch my_robot_description bringup.launch.py
# 3. 상태 모니터링
ros2 topic echo /joint_states
ros2 topic echo /rt_raw # RT 성능 메트릭
Troubleshooting
| 증상 | 원인 | 해결 |
|---|---|---|
/dev/EtherCAT0 없음 | 서비스 미시작 | sudo systemctl restart ethercat |
No network interface | ethercat.conf 미설정 | MASTER0_DEVICE="eth0" 설정 |
| 권한 오류 | 그룹 미설정 | sudo groupadd -g 1001 ethercat + udev 규칙 |
| WKC mismatch | 슬레이브 미응답 | 케이블 확인, ethercat slaves 명령으로 상태 점검 |
통합 체크리스트
Description Package 생성
-
패키지 생성
ros2 run plem_bringup create_description -
URDF 편집 — geometry, mesh, joint 구조 정의
-
조인트 제한값 설정 (
config/joint_limits.yaml)- Full precision 값 사용 (예:
3.14159265358979— 반올림 금지) max_effort필드 필수 포함- 템플릿: Description Protocol 참조
- Full precision 값 사용 (예:
-
빌드
colcon build --packages-select <name>_description -
검증
colcon test --packages-select <name>_description -
실행
ros2 launch <name>_description bringup.launch.py -
Optional: 커스텀 MoveIt Config (SRDF 편집, planning group 설정)
C++ Robot Extension 생성
create_robot으로 생성하는 애플리케이션은 PLEM 내장 RT driver를 완전히 대체합니다.
create_robot이 생성하는 main.cpp가 EtherCAT 통신, 토크 계산, 안전 모니터링을 사용자의 로봇 설정으로 직접 수행합니다.
-
패키지 생성
ros2 run plem_bringup create_robot -
Config 편집 —
kInertial,kURDFKinematics(기구학/동역학 데이터)URDF 자동 파싱URDF가 준비된 경우,
parse_urdf_to_config.py로 자동 추출할 수 있습니다:ros2 run plem_bringup parse_urdf_to_config my_robot.urdf.xacro출력된 C++ constexpr 배열을 config header에 복사하면 됩니다.
-
교차 검증 — YAML ↔ C++ 제한값 자동 비교
colcon build --packages-select <name>_description
colcon test --packages-select <name>_robot -
빌드
colcon build --packages-select <name>_robot -
시스템 실행 (RT driver + ROS2 stack 자동 시퀀싱)
ros2 launch <name>_robot bringup.launch.py
Post-Integration
-
/rt_raw토픽으로 RT 지터 확인 (< 50µs 양호) -
/joint_states토픽으로 조인트 상태 확인 - 비상 정지 테스트
새 제조사 로봇 지원
PLEM은 두 가지 통합 경로를 제공합니다:
경로 A: Description Package (ROS2 통합만)
시뮬레이션, MoveIt Planning, 또는 기존 지원 로봇 사용 시:
ros2 run plem_bringup create_description --name my_robot --dof 6
대부분의 사용자는 이 방법으로 충분합니다.
경로 B: C++ Robot Extension (하드웨어 제어)
새 제조사 로봇을 실제 하드웨어와 연동하려면:
ros2 run plem_bringup create_robot
Interactive 마법사가 완전한 C++ 확장 패키지를 생성합니다:
| 파일 | 용도 |
|---|---|
<model>_config.hpp | Config 구조체 + RobotTraits 특수화 |
<manufacturer>_factory.hpp | RobotFactory 특수화 |
<model>_robot.hpp/.cpp | PImpl 위임 클래스 (EtherCAT 선택 시) |
main.cpp | 진입점 (static_assert 검증) |
test_<model>_config.cpp | Concept 검증 + YAML 교차 검증 테스트 |
CMakeLists.txt | 빌드 설정 |
package.xml | ROS2 패키지 메타데이터 |
특징:
- PLEM 소스 코드 수정 불필요
- C++20 Concepts로 컴파일 타임 타입 안전성
- 다양한 DOF (4, 5, 6, 7, 12) 및 필드버스 지원
필드버스별 자동 생성 범위:
| 필드버스 | Config | Factory | PImpl | 비고 |
|---|---|---|---|---|
| EtherCAT CiA402 | 전체 | 전체 | 전체 (EtherCATRobotBase) | 권장 |
| EtherCAT Custom | 전체 | 전체 | 전체 | 커스텀 PDO 매핑 필요 |
| Modbus (실험적) | skeleton | stub | 없음 | IRobot 직접 구현 필요 |
Description과 Driver를 함께 생성하려면 통합 래퍼를 사용할 수 있습니다:
ros2 run plem_bringup create_robot_package # 대화형: 범위 선택
ros2 run plem_bringup create_robot_package --scope=both # 둘 다 한 번에
각 도구(create_description, create_robot)는 여전히 독립 실행이 가능합니다.
다음 단계
- Description Protocol - Convention-based 파일 규약
- ROS2 Launch 시스템 - Composable Launch 구조
- 안전 모드 API - SafetyMode, RobotMode 이해