모드 제어
로봇 동작 모드를 전환하고 안전 상태를 확인하는 방법을 설명합니다.
상태 다이어그램
모드 설명
| 모드 | 값 | 설명 |
|---|---|---|
| BRAKED | 0 | 브레이크 잠금. Launch 직후 기본 상태 |
| TRAJECTORY | 2 | 궤적 실행 가능. FollowJointTrajectory 액션이 동작함 |
| FREEDRIVE | 3 | 수동 조작 가능. 사용자가 손으로 로봇을 움직일 수 있음 |
warning
TRAJECTORY나 FREEDRIVE 모드에서는 로봇이 움직일 수 있습니다. 전환 전 로봇 주변 안전을 확인하세요.
액션 인터페이스
- 액션 서버:
/{robot_id}/wim_rt_driver/set_mode - 타입:
neuromeka_msgs/action/SetMode
CLI 전환 명령어
BRAKED → TRAJECTORY
ros2 action send_goal /indy/wim_rt_driver/set_mode \
neuromeka_msgs/action/SetMode \
"{target_robot_mode: {mode: 2}}"
BRAKED → FREEDRIVE
ros2 action send_goal /indy/wim_rt_driver/set_mode \
neuromeka_msgs/action/SetMode \
"{target_robot_mode: {mode: 3}}"
TRAJECTORY/FREEDRIVE → BRAKED
ros2 action send_goal /indy/wim_rt_driver/set_mode \
neuromeka_msgs/action/SetMode \
"{target_robot_mode: {mode: 0}}"
Python 예제
#!/usr/bin/env python3
"""로봇 모드 전환 예제."""
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from action_msgs.msg import GoalStatus
from neuromeka_msgs.action import SetMode
class ModeController(Node):
"""로봇 모드를 전환하는 노드."""
def __init__(self, robot_id: str = "indy"):
super().__init__("mode_controller")
self._client = ActionClient(
self,
SetMode,
f"/{robot_id}/wim_rt_driver/set_mode",
)
def set_mode(self, mode: int) -> bool:
"""모드를 전환하고 완료까지 대기한다."""
if not self._client.wait_for_server(timeout_sec=5.0):
self.get_logger().error("SetMode 액션 서버 연결 실패")
return False
goal = SetMode.Goal()
goal.target_robot_mode.mode = mode
future = self._client.send_goal(goal)
if future.status != GoalStatus.STATUS_SUCCEEDED:
self.get_logger().error(f"모드 전환 실패: status={future.status}")
return False
self.get_logger().info(f"모드 전환 완료: {mode}")
return True
def main():
rclpy.init()
node = ModeController(robot_id="indy")
try:
# TRAJECTORY 모드로 전환
node.set_mode(2)
# ... 작업 수행 ...
# BRAKED 모드로 복귀
node.set_mode(0)
finally:
node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()
SafetyMode (읽기 전용)
안전 상태는 토픽으로 발행되며, 사용자가 직접 변경할 수 없습니다.
- 토픽:
/{robot_id}/wim_rt_driver/safety_mode
| SafetyMode | 설명 |
|---|---|
| NORMAL | 정상 운영 상태 |
| P_STOP | 보호 정지. 외부 안전 입력에 의해 발생 |
| HW_FAULT | 하드웨어 이상. 드라이버 과부하, 통신 오류 등 |
# 현재 SafetyMode 확인
ros2 topic echo /indy/wim_rt_driver/safety_mode --once
danger
P_STOP 또는 HW_FAULT 상태에서는 모드 전환이 거부됩니다. 원인을 해결한 후 다시 시도하세요.
다음 단계
MoveIt 연동으로 이동하여 MoveIt을 통한 모션 계획을 확인하세요.