본문으로 건너뛰기

빠른 시작: 첫 로봇 프로그램

실제 Neuromeka Indy7 로봇에 연결하고 PLEM으로 첫 번째 하드웨어 제어 프로그램을 실행합니다.

전제조건:

  • PLEM이 설치된 W-RC
  • Neuromeka Indy7 로봇 전원 ON
  • EtherCAT 케이블이 제어 PC와 로봇 베이스에 연결됨

예상 시간: 15분


안전 주의사항

산업용 manipulator를 다루는 것은 엄격한 안전 protocol이 필요합니다.

필수 안전 요구사항
  1. 비상정지 버튼: 팔이 닿는 범위 내에 비상정지 버튼을 배치하고 작동을 확인합니다.
  2. 작업공간 정리: 로봇의 작업공간에서 모든 장애물과 인원을 제거합니다.
  3. 저속 테스트: 처음 실행 시 낮은 속도 제한(10-20%)을 사용합니다.
  4. 방치 금지: 작동 중 항상 작업자가 로봇을 모니터링해야 합니다.

작동 전 체크리스트

  • 비상정지 버튼이 손이 닿는 곳에 있고 작동함
  • 작업공간에 장애물과 인원이 없음
  • 로봇 전원 케이블과 EtherCAT 케이블이 올바르게 연결됨
  • 첫 실행을 위한 낮은 속도 설정 준비됨
경고

안전에 대해 확실하지 않은 경우, 진행하기 전에 인증된 로봇 통합자에게 문의하세요.


1단계: 프로젝트 생성

프로젝트 구조

quickstart_hardware/
├── CMakeLists.txt
├── package.xml
└── src/
└── main.cpp

워크스페이스 준비

사용자 패키지를 빌드하려면 colcon 워크스페이스가 필요합니다. 워크스페이스는 src/ 디렉토리에 소스 패키지를 배치하고, 루트에서 colcon build를 실행하는 ROS2 표준 구조입니다.

# 워크스페이스 생성 (이름은 자유롭게 변경 가능)
mkdir -p ~/robot_ws/src
정보

PLEM 라이브러리 스택(plem_core, plem_robot 등)이 이미 W-RC에 설치되어 있어야 합니다. 설치 확인은 설치 가이드를 참조하세요.

패키지 생성

cd ~/robot_ws/src
ros2 pkg create quickstart_hardware --build-type ament_cmake --dependencies plem_robot plem_core
cd quickstart_hardware

CMakeLists.txt

파일: CMakeLists.txt

cmake_minimum_required(VERSION 3.25)
project(quickstart_hardware)

# C++20 필수
set(CMAKE_CXX_STANDARD 20)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

# 의존성 찾기
find_package(ament_cmake REQUIRED)
find_package(plem_core REQUIRED)
find_package(plem_robot REQUIRED)

# 실행 파일
add_executable(quickstart_hardware_node src/main.cpp)

# 라이브러리 링크
target_link_libraries(quickstart_hardware_node
plem_core::plem_core
plem_robot::plem_robot
)

# 설치
install(TARGETS quickstart_hardware_node
DESTINATION lib/${PROJECT_NAME}
)

ament_package()

package.xml

파일: package.xml

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>quickstart_hardware</name>
<version>0.1.0</version>
<description>PLEM hardware quickstart example</description>
<maintainer email="you@example.com">Your Name</maintainer>
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<depend>plem_core</depend>
<depend>plem_robot</depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>

2단계: 코드 작성

파일: src/main.cpp

#include <chrono>
#include <csignal>
#include <iostream>
#include <memory>
#include <thread>

#include <plem/core/logging/logger.hpp>
#include <plem/robot/models/indy7.hpp>
#include <plem/robot/robot_builder.hpp>

// 시그널 핸들러를 위한 전역 로봇 포인터
std::unique_ptr<plem::robot::IRobot> g_robot;

void signal_handler(int signal) {
if (signal == SIGINT) {
plem::core::logger.info("Caught SIGINT, shutting down...");
if (g_robot) {
g_robot->stop();
}
}
}

int main(int argc, char* argv[]) {
using namespace plem;

// 명령줄 인수 파싱
std::string interface = "eth0"; // W-RC 기본 EtherCAT 네트워크 인터페이스
if (argc > 1) {
interface = argv[1];
}

// 로깅 초기화
core::logger.set_level(spdlog::level::info);
core::logger.info("=== PLEM 하드웨어 빠른 시작 ===");
core::logger.info("Using network interface: {}", interface);

// 로봇 빌드
core::logger.info("Creating robot...");
auto result = robot::Robot::builder<robot::models::Indy7>()
.with_network_interface(interface)
.build();

if (!result) {
core::logger.error("Failed to create robot: {}", result.message());
core::logger.error("WHAT: Robot initialization failed");
core::logger.error("WHY: {}", result.message());
core::logger.error("HOW: Check network interface name and EtherCAT cable");
return 1;
}
g_robot = std::move(result).value();
core::logger.info("Robot created successfully");

// 시그널 핸들러 등록
std::signal(SIGINT, signal_handler);

// RT 스레드 시작
core::logger.info("Starting robot...");
auto rc = g_robot->start();
if (rc != 0) {
core::logger.error("Failed to start robot (code: {})", rc);
core::logger.error("WHAT: RT thread initialization failed");
core::logger.error("WHY: Possible permission issue or EtherCAT master busy");
core::logger.error("HOW: Check 'ethercat' group membership and /dev/EtherCAT0");
return 1;
}
core::logger.info("RT threads started");

// 서보 초기화 대기
core::logger.info("Waiting for servo drives to initialize (2 seconds)...");
std::this_thread::sleep_for(std::chrono::seconds(2));

// 브레이크 해제 카운트다운
core::logger.warn("=== 3초 후 브레이크 해제 ===");
core::logger.warn("작업공간이 안전하지 않으면 지금 Ctrl+C를 누르세요!");
std::this_thread::sleep_for(std::chrono::seconds(3));

// 브레이크 해제
core::logger.info("Releasing brakes...");
g_robot->release_brake();

// 서보 활성화 완료 대기
std::this_thread::sleep_for(std::chrono::seconds(2));

core::logger.info("Brakes released. Robot is now active.");
core::logger.info("Robot mode: {}", static_cast<int>(g_robot->mode()));

// 사용자 대기
core::logger.info("Robot is running. Press Enter to shutdown...");
std::cin.get();

// 종료 전 브레이크 체결
core::logger.info("Engaging brakes...");
g_robot->engage_brake();
std::this_thread::sleep_for(std::chrono::seconds(1));

// 정지
core::logger.info("Stopping robot...");
g_robot->stop();
g_robot.reset();

core::logger.info("Shutdown complete");
return 0;
}

코드 설명

Robot::builder 패턴

auto result = robot::Robot::builder<robot::models::Indy7>()
.with_network_interface(interface)
.build();
  • Robot::builder<T>(): 타입 안전한 builder 패턴
  • with_network_interface(): EtherCAT이 연결된 물리 NIC 이름 설정 (예: "enp2s0")
  • with_robot_id(): 다중 로봇 환경에서 IPC/ROS2 namespace 격리용 고유 ID (선택사항)
  • build(): Result<std::unique_ptr<IRobot>> 반환
중요

network_interfaceEtherCAT이 연결된 물리 네트워크 interface 이름입니다. EtherCAT은 Layer 2 (raw Ethernet) 통신이므로 IP 주소 설정이 필요하지 않습니다.

일반적인 interface 이름: eth0, enp2s0, eno1

네트워크 인터페이스 확인

EtherCAT 케이블이 연결된 interface를 찾으려면:

ip link show
# 예제 출력:
# 2: eth0: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 ...

또는 EtherCAT slave 확인:

sudo ethercat slaves
# 예상 출력:
# 0 0:0 PREOP + Neuromeka Indy7 Joint0
# 1 0:1 PREOP + Neuromeka Indy7 Joint1
# ...

시그널 핸들러

SIGINT (Ctrl+C) 처리로 정상적인 종료 보장:

void signal_handler(int signal) {
if (signal == SIGINT) {
if (g_robot) {
g_robot->stop(); // RT 스레드 종료
}
}
}

브레이크 제어

g_robot->release_brake();  // 서보 활성화 (CiA 402 상태 전환)
g_robot->engage_brake(); // 서보 비활성화

브레이크 해제 시 CiA 402 상태 머신이 다음 순서로 전환됩니다:

SWITCH_ON_DISABLED → READY_TO_SWITCH_ON → SWITCHED_ON → OPERATION_ENABLED
Production 실행 파일

이 예제는 최소 동작 확인용입니다. ROS2 topic 모니터링(/rt_raw, /joint_states)이 포함된 production 실행 파일 작성법은 로봇 통합 가이드를 참조하세요.


3단계: 빌드 및 실행

빌드

cd ~/robot_ws
colcon build --packages-select quickstart_hardware
source install/setup.bash

실행

# 인터페이스 이름을 인수로 전달
ros2 run quickstart_hardware quickstart_hardware_node eth0

또는 기본값 사용 (코드에서 "eth0"):

ros2 run quickstart_hardware quickstart_hardware_node

다음 단계

로봇 통합 가이드로 이동하여 내 로봇을 PLEM에 통합하는 방법을 알아보세요.

이미 통합된 로봇을 사용 중이라면:

안전 알림

복잡한 motion을 실행하기 전에 항상 먼저 simulation에서 테스트하고, 하드웨어에서는 낮은 속도로 시작하세요.


요약

배운 내용:

  • PLEM으로 최소 하드웨어 제어 프로그램 작성
  • Robot::builder 패턴으로 로봇 instance 생성
  • 브레이크 해제 sequence를 안전하게 실행
  • 일반적인 EtherCAT 문제 해결

핵심 요점:

  • network_interface는 EtherCAT이 연결된 물리 NIC 이름 (IP 설정 불필요)
  • EtherCAT은 Layer 2 통신 (raw Ethernet)
  • 브레이크 해제는 CiA 402 상태 전환을 거침 (1-2초 소요)
  • 종료 전에 항상 브레이크 체결