Skip to main content

그리퍼 제어

OnRobot 그리퍼를 설정하고 제어하는 방법을 설명합니다.


1. Launch에서 그리퍼 활성화

gripper 파라미터로 그리퍼 타입을 지정합니다:

ros2 launch neuromeka_robot_driver plem_launch.py gripper:=rg6

그리퍼가 활성화되면 다음 인터페이스가 추가됩니다:

인터페이스경로
액션/{robot_id}/gripper_action_controller/gripper_cmd
상태 토픽/{robot_id}/gripper_status

2. 액션 인터페이스

  • 액션 서버: /{robot_id}/gripper_action_controller/gripper_cmd
  • 타입: control_msgs/action/GripperCommand

GripperCommand 필드

필드타입설명
command.positionfloat그리퍼 위치 (0.0 = 완전히 닫힘, 1.0 = 완전히 열림)
command.max_effortfloat최대 힘 (N). 0.0이면 기본값 사용

3. CLI 예제

그리퍼 열기

ros2 action send_goal \
/indy/gripper_action_controller/gripper_cmd \
control_msgs/action/GripperCommand \
"{command: {position: 1.0, max_effort: 0.0}}"

그리퍼 닫기

ros2 action send_goal \
/indy/gripper_action_controller/gripper_cmd \
control_msgs/action/GripperCommand \
"{command: {position: 0.0, max_effort: 0.0}}"

중간 위치로 이동

ros2 action send_goal \
/indy/gripper_action_controller/gripper_cmd \
control_msgs/action/GripperCommand \
"{command: {position: 0.5, max_effort: 0.0}}"

4. Python 예제

#!/usr/bin/env python3
"""그리퍼 제어 예제."""

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from action_msgs.msg import GoalStatus
from control_msgs.action import GripperCommand


class GripperController(Node):
"""그리퍼를 제어하는 노드."""

def __init__(self, robot_id: str = "indy"):
super().__init__("gripper_controller")
self._client = ActionClient(
self,
GripperCommand,
f"/{robot_id}/gripper_action_controller/gripper_cmd",
)

def move(self, position: float, max_effort: float = 0.0) -> bool:
"""그리퍼를 지정 위치로 이동한다.

Args:
position: 0.0(닫힘) ~ 1.0(열림)
max_effort: 최대 힘(N). 0.0이면 기본값.
"""
if not self._client.wait_for_server(timeout_sec=5.0):
self.get_logger().error("GripperCommand 액션 서버 연결 실패")
return False

goal = GripperCommand.Goal()
goal.command.position = position
goal.command.max_effort = max_effort

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"그리퍼 이동 완료: position={position}")
return True


def main():
rclpy.init()
node = GripperController(robot_id="indy")

try:
# 그리퍼 열기
node.move(position=1.0)

# 그리퍼 닫기
node.move(position=0.0)
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == "__main__":
main()

5. 상태 확인

그리퍼의 현재 상태를 토픽으로 확인할 수 있습니다:

ros2 topic echo /indy/gripper_status --once

다음 단계

Multi-Robot 운용으로 이동하여 여러 로봇을 동시에 제어하는 방법을 확인하세요.