패키지 생성
$ catkin_create_pkg swing_robot roscpp tf geometry_msgs urdf rviz xacro
디렉토리 이동
$ roscd swing_robot
xacro 파일을 사용하면, 변수를 만들어 유지보수를 쉽게 만들 수 있습니다.
아직은 사용하지 않지만 차후를 위해서 xacro 파일을 작성합니다.
swing_robot.xacro
파일을 생성하고, 다음과 같이 코드를 작성합니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
name="swing_robot">
<link name="base_link">
<visual>
<origin rpy="1.570796 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://swing_robot/meshes/frames.stl"/>
</geometry>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<origin rpy="1.570796 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://swing_robot/meshes/frames.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<mass value="3.314"/>
<inertia ixx="463814.860" ixy="323.087" ixz="0.0"
iyy="223494.895" iyz="0.0" izz="457336.445"/>
</inertial>
</link>
<joint name="swing joint" type="revolute">
<parent link="base_link"/>
<child link="swing_link"/>
<origin xyz="0 0 0.599704"/>
<axis xyz="1 0 0" />
<limit effort="300" velocity="0.1" lower="-3.14" upper="3.14"/>
<dynamics damping="50" friction="1"/>
</joint>
<link name="swing_link">
<visual>
<geometry>
<mesh filename="package://swing_robot/meshes/swing.stl"/>
</geometry>
<origin rpy="1.570796 0 0" xyz="0 0 0"/>
<material name="red">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://swing_robot/meshes/swing.stl"/>
</geometry>
<origin rpy="1.570796 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<origin xyz="0.0 0.0 0" rpy="1.570796 0 0"/>
<mass value="4.443"/>
<inertia ixx="22383.593" ixy="5442.330" ixz="-438.500"
iyy="3976.186" iyz="764.536" izz="26027.494"/>
</inertial>
</link>
</robot>
여기서 아래와 같이 stl파일이 존재하는 경로를 mesh 태크를 이용하여 각 링크마다 mesh를 설정할 수 있습니다.
<mesh filename="package://swing_robot/meshes/frames.stl"/>
다음과 같이 launch, meshes, urdf 폴더 생성 후 stl 파일과 launch 파일 urdf 파일을 작업폴더 안에 생성하여 줍니다.
├── CMakeLists.txt
├── include
│ └── swing_robot
├── launch
│ └── swing_robot.launch
├── meshes
│ ├── frames.stl
│ └── swing.stl
├── package.xml
├── src
└── urdf
├── swing_robot.urdf
└── swing_robot.xacro
xacro를 이용한 urdf 파일 생성
$ rosrun xacro xacro --inorder swing_robot.xacro > swing_robot.urdf
<launch>
<param name="robot_description"
command="$(find xacro)/xacro.py $(find swing_robot)/urdf/swing_robot.xacro"/>
<node pkg="robot_state_publisher"
type="state_publisher"
name="robot_state_publisher" />
<node pkg="joint_state_publisher"
type="joint_state_publisher"
name="joint_state_publisher">
<param name="use_gui" value="1" />
</node>
<!-- Launch visualization in rviz -->
<node name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find swing_robot)/urdf.rviz"
required="True" />
</launch>
$ roslaunch swing_robot swing_robot.launch