0. 准备工作
0.1 查看现在的 UR3 机器人模样
安装 robotiq_ft300.urdf前的 UR3 机器人是这样的(注意末端的样子):
roslaunch ur_description view_ur3.launch
0.2 robotiq下载链接
https://github.com/ros-industrial/robotiq
0.3 文件路径
各个文件的路径见效果图的上面部分。
1. 末端安装 robotiq_ft300.urdf
1.1 查看传感器应该安装的位置
UR3 最后一个 link 的名称为 tool0:
1.2 新建文件ur3_ft_robot.urdf.xacro复制ur3_robot.urdf.xacro的内容,修改后如下:
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro"
name="ur3" >
<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>
<!-- common stuff -->
<xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" />
<!-- ur3 -->
<xacro:include filename="$(find ur_description)/urdf/ur3.urdf.xacro" />
<!-- arm -->
<xacro:ur3_robot prefix="" joint_limited="false"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>
<link name="world" />
<joint name="world_joint" type="fixed">
<parent link="world" />
<child link = "base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
<!-- Add robotiq_ft300-->
<xacro:include filename="$(find robotiq_ft_sensor)/urdf/robotiq_ft300.urdf.xacro" />
<xacro:robotiq_ft300 parent="tool0" prefix="">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:robotiq_ft300>
</robot>
修改后效果如下:
1.3 新建文件view_ur3_ft.launch复制view_ur3.launch的内容,修改后如下:
<?xml version="1.0"?>
<launch>
<include file="$(find ur_description)/launch/ur3_ft_upload.launch"/>
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" >
<param name="use_gui" value="true"/>
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find ur_description)/cfg/view_robot.rviz" required="true" />
</launch>
修改后效果如下:
1.4 新建ur3_ft_upload.launch文件复制ur3_upload.launch的内容,修改后如下:
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_ft_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
</launch>
修改后效果如下:
1.5 查看添加后的效果
roslaunch ur_description view_ur3_ft.launch
2. 安装2.1 查看手爪应该安装的位置ft300 的最后一个 link 名称如下:
gripper140 的第一个 link 名称如下:
- 所以需要添加一个 joint 来连接两个 link。
2.2 新建文件ur3_ft_gripper140_robot.urdf.xacro
- 复制
ur3_ft_robot.urdf.xacro
的内容,添加的内容如下面的最后一段: -
<?xml version="1.0"?> <robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur3" > <xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/> <!-- common stuff --> <xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" /> <!-- ur3 --> <xacro:include filename="$(find ur_description)/urdf/ur3.urdf.xacro" /> <!-- arm --> <xacro:ur3_robot prefix="" joint_limited="false" transmission_hw_interface="$(arg transmission_hw_interface)" /> <link name="world" /> <joint name="world_joint" type="fixed"> <parent link="world" /> <child link = "base_link" /> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> </joint> <!-- Add robotiq_ft300--> <xacro:include filename="$(find robotiq_ft_sensor)/urdf/robotiq_ft300.urdf.xacro" /> <xacro:robotiq_ft300 parent="tool0" prefix=""> <origin xyz="0 0 0" rpy="0 0 0"/> </xacro:robotiq_ft300> <!-- Add robotiq arg2f140--> <!-- Copy from robotiq_arg2f_140_model.xacro --> <xacro:include filename="$(find robotiq_2f_140_gripper_visualization)/urdf/robotiq_arg2f_140_model_macro.xacro" /> <xacro:robotiq_arg2f_140 prefix=""/> <!-- Link to the end of ft300 --> <joint name="ft_gripper_joint" type="fixed"> <parent link="robotiq_ft_frame_id"/> <child link="robotiq_arg2f_base_link"/> <origin xyz="0 0 0" rpy="0 0 0"/> </joint> </robot>
- 修改后效果如下:
- 2.3 新建文件ur3_ft_gripper140_upload.launch流程和上面添加 ft300 的一样:
-
<?xml version="1.0"?> <launch> <arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." /> <arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" /> <param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_ft_gripper140_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" /> <param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" /> </launch>
- 修改后效果如下:
- 2.4 新建文件view_ur3_ft_gripper140.launch流程和上面添加 ft300 的一样:
-
<?xml version="1.0"?> <launch> <include file="$(find ur_description)/launch/ur3_ft_gripper140_upload.launch"/> <node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" > <param name="use_gui" value="true"/> </node> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find ur_description)/cfg/view_robot.rviz" required="true" /> </launch>
- 修改后效果如下:
- 2.5 查看添加后的效果
-
roslaunch ur_description view_ur3_ft_gripper140.launch
-
3. 参考链接
评论(0)
您还未登录,请登录后发表或查看评论