첫 번째 실행
설치를 완료했다면 로봇을 구동합니다.
1. 실시간 스케줄링 권한 설정
PLEM 드라이버는 1 kHz 실시간 제어 루프를 실행합니다. ros2_control_node에 실시간 스케줄링 권한을 부여해야 합니다:
sudo setcap cap_sys_nice+ep $(which ros2_control_node)
경고
이 명령을 실행하지 않으면 RT 스레드가 높은 우선순위를 획득하지 못해 제어 성능이 저하됩니다.
2. Launch 실행
ros2 launch neuromeka_robot_driver plem_launch.py
기본값은 robot_type:=indy7_v2, robot_id:=indy입니다.
Launch 파라미터
| 파라미터 | 기본값 | 설명 |
|---|---|---|
robot_type | indy7_v2 | 로봇 타입 (indy7_v2, indy12_v2) |
robot_id | indy | ROS2 네임스페이스 |
gripper | none | 그리퍼 타입 (none, rg6) |
camera | none | 카메라 타입 (none, zedxm) |
record | true | rosbag2 녹화 활성화 |
구성 예시
# Indy12 + OnRobot RG6 그리퍼
ros2 launch neuromeka_robot_driver plem_launch.py \
robot_type:=indy12_v2 gripper:=rg6
# Indy7 + ZED X Mini 카메라 + 녹화 비활성화
ros2 launch neuromeka_robot_driver plem_launch.py \
robot_type:=indy7_v2 camera:=zedxm record:=false
# Indy12 + 그리퍼 + 카메라 전체 구성
ros2 launch neuromeka_robot_driver plem_launch.py \
robot_type:=indy12_v2 gripper:=rg6 camera:=zedxm
3. 정상 구동 확인
토픽 확인
ros2 topic list
다음 토픽이 표시되어야 합니다:
/indy/joint_states
/indy/joint_trajectory_controller/follow_joint_trajectory/_action/status
/indy/wim_rt_driver/set_mode/_action/status
노드 확인
ros2 node list
다음 노드가 표시되어야 합니다:
/indy/controller_manager
/indy/joint_state_broadcaster
/indy/joint_trajectory_controller
/indy/wim_rt_driver
Joint 상태 확인
현재 로봇의 관절 위치를 확인합니다:
ros2 topic echo /indy/joint_states --once
6개 관절(joint0 ~ joint5)의 position, velocity, effort가 출력됩니다.
문제 해결
ros2_control_node가 시작되지 않음
EtherCAT 마스터 연결을 확인하세요. 마스터 인덱스가 기본값(0)과 다르면 master_index 파라미터를 지정합니다:
ros2 launch neuromeka_robot_driver plem_launch.py master_index:=1
권한 오류 (Operation not permitted)
cap_sys_nice 권한이 설정되었는지 확인합니다:
getcap $(which ros2_control_node)
# 출력: /opt/ros/humble/.../ros2_control_node cap_sys_nice=ep
출력이 비어 있으면 1단계를 다시 실행하세요.
다음 단계
첫 궤적 전송으로 이동하여 로봇에 모션 명령을 보내 보세요.