RRrobot.xacro
<?xml version="1.0"?>
<robot name="moonknight" xmlns:xaro="http://www.ros.org/wiki/xacro">
<!--Base part-->
<link name="baselink">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.1" length="0.08"/>
</geometry>
</visual>
</link>
<joint name="baselink_link1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="0.3"/>
<origin rpy = "0 0 0" xyz="0 0 0"/>
<parent link="baselink"/>
<child link="link1"/>
</joint>
<!--Arm part-->
<link name="link1">
<visual>
<origin rpy="0 0 0" xyz="0 0.4 0.08"/>
<geometry>
<box size="0.06 0.8 0.06"/>
</geometry>
</visual>
</link>
<joint name="link1_link2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-3.14" upper="3.14" velocity="0.5"/>
<origin rpy = "0 0 1.57" xyz="0 0.8 0"/>
<parent link="link1"/>
<child link="link2"/>
</joint>
<link name="link2">
<visual>
<origin rpy="0 0 0" xyz="0 0.4 0.08"/>
<geometry>
<box size="0.06 0.8 0.06"/>
</geometry>
</visual>
</link>
<!--End effector part-->
<joint name="link2_link3" type="prismatic">
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-0.1" upper="0.1" velocity="0.3"/>
<origin rpy = "0 0 0" xyz="0 0.8 0"/>
<parent link="link2"/>
<child link="link3"/>
</joint>
<link name="link3">
<visual>
<origin rpy="0 0 0" xyz="0 0 0.08"/>
<geometry>
<box size="0.06 0.06 0.2"/>
</geometry>
</visual>
</link>
</robot>
rviz.launch
<launch>
<!-- 定义了一个叫"robot_description"的parameter存放在param server
且这个parameter是后面commond的执行结果形成的string
这个commond的意思是找到xacro包并执行xacro程序把如下地址的xacro转成urdf文件-->
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find RRrobot_description)/urdf/RRrobot.xacro"/>
<!-- 定义了一个节点叫"robot_state_publisher",这个节点执行"robot_state_publisher"包里的
"state_publisher"程序,作用是发布robot状态信息-->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"/>
<!-- 定义了一个节点叫"rviz",这个节点执行"riz"包里的"rviz"程序,作用是显示机器人模型-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find RRrobot_description)/config/config.rviz"/>
<!-- 定义了一个节点叫"joint_state_publisher",这个节点执行"joint_state_publisher"包里的"joint_state_publisher"程序,作用是发布关节信息。并且定义了值为True的局部变量use_gui-->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="True"/>
</node>
</launch>