본문으로 건너뛰기

커스텀 URDF 사용

plem 플랫폼의 기본 URDF 대신 사용자가 직접 작성한 URDF를 사용할 수 있다. description_package 파라미터를 통해 외부 URDF 패키지를 연결한다.

기본 사용법

ros2 launch neuromeka_robot_driver plem_launch.py description_package:=my_robot_description

커스텀 URDF 요구사항

커스텀 URDF 패키지가 plem 플랫폼과 호환되려면 다음 요구사항을 충족해야 한다.

1. ${prefix} 파라미터 지원

모든 link와 joint 이름에 ${prefix}를 적용해야 한다. 이는 멀티 로봇 환경에서 이름 충돌을 방지한다.

<link name="${prefix}base_link"/>
<joint name="${prefix}joint_1" type="revolute">
<!-- ... -->
</joint>

2. ros2_control 태그 포함

hardware interface 플러그인을 지정하는 ros2_control 태그가 필요하다.

<ros2_control name="${prefix}robot_hardware" type="system">
<hardware>
<plugin>neuromeka_robot_driver/IndyHardwareInterface</plugin>
</hardware>
<joint name="${prefix}joint_1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<!-- 나머지 joint도 동일하게 정의 -->
</ros2_control>

3. ${prefix}flange 엔드이펙터 부착점

엔드이펙터(그리퍼, 카메라 등)의 부착점으로 사용되는 flange fixed joint와 link를 정의해야 한다.

<joint name="${prefix}flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}flange_link"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
<link name="${prefix}flange_link"/>

최소 URDF 구조 예시

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="my_robot">
<xacro:macro name="my_robot" params="prefix">

<!-- Base link -->
<link name="${prefix}base_link">
<visual>
<geometry><mesh filename="package://my_robot_description/meshes/base.stl"/></geometry>
</visual>
<collision>
<geometry><mesh filename="package://my_robot_description/meshes/base_collision.stl"/></geometry>
</collision>
</link>

<!-- Joint 1 -->
<joint name="${prefix}joint_1" type="revolute">
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="-3.14159" upper="3.14159" velocity="1.0" effort="100.0"/>
</joint>
<link name="${prefix}link_1">
<!-- visual/collision/inertial -->
</link>

<!-- ... 나머지 joint/link ... -->

<!-- Flange (엔드이펙터 부착점) -->
<joint name="${prefix}flange" type="fixed">
<parent link="${prefix}link_N"/>
<child link="${prefix}flange_link"/>
</joint>
<link name="${prefix}flange_link"/>

<!-- ros2_control -->
<ros2_control name="${prefix}robot_hardware" type="system">
<hardware>
<plugin>neuromeka_robot_driver/IndyHardwareInterface</plugin>
</hardware>
<joint name="${prefix}joint_1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<!-- 나머지 joint도 동일하게 정의 -->
</ros2_control>

</xacro:macro>
</robot>

특정 URDF 파일 직접 지정

패키지 내 기본 파일이 아닌 특정 xacro 파일을 사용하려면 urdf_file 파라미터를 함께 지정한다:

ros2 launch neuromeka_robot_driver plem_launch.py \
description_package:=my_robot urdf_file:=urdf/my_robot.urdf.xacro

주의사항

  • ros2_control 태그의 hardware interface 플러그인은 neuromeka_robot_driver/IndyHardwareInterface를 참조해야 한다. 이 플러그인이 plem 플랫폼의 EtherCAT 통신과 실시간 제어 루프를 담당한다.
  • 모든 joint의 limit 값(position, velocity, effort)을 실제 로봇 사양에 맞게 정확히 설정해야 한다. 잘못된 limit은 안전 문제를 일으킬 수 있다.
  • 메쉬 파일 경로는 package:// URI를 사용한다.