Skip to main content

ROS2 인터페이스

PLEM 제어 시스템이 제공하는 ROS2 토픽, 액션, 서비스, 컨트롤러를 정리합니다.

모든 인터페이스는 /{robot_id}/ 네임스페이스 아래에 위치합니다. 예를 들어 robot_idindy7이면 joint states 토픽은 /indy7/joint_states가 됩니다.


토픽

토픽메시지 타입주기설명
/{robot_id}/joint_statessensor_msgs/JointState1 kHz관절 위치·속도·토크
/{robot_id}/tftf2_msgs/TFMessage1 kHzTF 트리 broadcast
/{robot_id}/rt_rawneuromeka_msgs/RtRaw1 kHzRT 루프 타이밍 원시 데이터
/{robot_id}/status_broadcaster/robot_modeneuromeka_msgs/RobotMode50 Hz로봇 동작 모드
/{robot_id}/status_broadcaster/safety_modeneuromeka_msgs/SafetyMode50 Hz안전 모드 상태
/{robot_id}/rt_eventsneuromeka_msgs/RtEventon-eventRT 이벤트 (에러, 경고 등)
/{robot_id}/rt_monitor_statsneuromeka_msgs/RtMonitorStats10 HzRT 모니터링 통계
/{robot_id}/gripper_status_publisher/gripper_statusneuromeka_msgs/GripperStatus그리퍼 상태 (그리퍼 사용 시)

액션

액션메시지 타입설명
/{robot_id}/joint_trajectory_controller/follow_joint_trajectorycontrol_msgs/FollowJointTrajectory궤적 실행 (핵심 인터페이스). 로봇을 움직이려면 이 액션을 사용합니다.
/{robot_id}/wim_rt_driver/set_modeneuromeka_msgs/SetMode로봇 모드 전환 (idle, position 등)
/{robot_id}/gripper_action_controller/gripper_cmdcontrol_msgs/GripperCommand그리퍼 열기/닫기 (그리퍼 사용 시)

follow_joint_trajectory는 MoveIt2, 사용자 애플리케이션 등 모든 궤적 실행의 진입점입니다. Getting Started의 궤적 전송 가이드를 참고하세요.

note

wim_rt_driver는 레거시 노드명입니다. 향후 버전에서 변경될 예정이므로, 직접 의존하기보다는 launch 파라미터를 통해 접근하세요.


서비스

서비스메시지 타입설명
/{robot_id}/control_commandneuromeka_msgs/SetControlCommand에러 리셋 등 제어 명령 전송

컨트롤러

ros2_control 프레임워크 기반 컨트롤러입니다. ros2 control list_controllers 명령으로 상태를 확인할 수 있습니다.

컨트롤러기본 상태용도
joint_state_broadcasteractive관절 상태 broadcast (joint_states, tf)
joint_trajectory_controllerinactive궤적 추종 제어. 사용 전 activate 필요
free_drive_controllerinactive프리드라이브(직접 교시) 모드. 사용 전 activate 필요

joint_trajectory_controllerfree_drive_controller는 동시에 active 상태가 될 수 없습니다. 하나를 activate하면 다른 하나는 deactivate해야 합니다.

# 컨트롤러 상태 확인
ros2 control list_controllers --controller-manager /{robot_id}/controller_manager

# joint_trajectory_controller 활성화
ros2 control switch_controllers \
--activate joint_trajectory_controller \
--deactivate free_drive_controller \
--controller-manager /{robot_id}/controller_manager

Multi-Robot 네임스페이스

여러 대의 로봇을 동시에 제어할 때, 각 로봇은 고유한 robot_id 네임스페이스로 구분됩니다.

/indy7_left/joint_states
/indy7_left/joint_trajectory_controller/follow_joint_trajectory

/indy7_right/joint_states
/indy7_right/joint_trajectory_controller/follow_joint_trajectory

robot_id는 launch 파라미터로 설정합니다:

ros2 launch neuromeka_robot_driver neuromeka.launch.py robot_id:=indy7_left robot_type:=indy7_v2 ...
ros2 launch neuromeka_robot_driver neuromeka.launch.py robot_id:=indy7_right robot_type:=indy7_v2 ...