ur3+robotiq ft sensor+robotiq 2f 140配置rviz仿真环境

ur3+robotiq ft sensor+robotiq 2f 140配置rviz仿真环境

搭建环境:

ubuntu: 20.04
ros: Nonetic
sensor: robotiq_ft300
gripper: robotiq_2f_140_gripper
UR: UR3

在安装sensor和gripper之前,先简单配置一下UR机械臂的仿真环境,可参考这篇博客进行配置,配置完了之后下面正式开始安装力传感器和夹爪

1. 下载sensor和gripper工具包

进入之前安装UR机械臂仿真环境创建的工作空间,克隆仓库到src文件夹中

cd ~/catkin_ws/src
git clone https://github.com/jr-robotics/robotiq.git

为什么不直接克隆robotiq官方的仓库呢?因为官方仓库中没有noetic版本, 所以采用了上图中的git仓库

2. 编译工作环境
cd ~/catkin_ws
sudo apt update -qq
rosdep update
rosdep install --from-paths src --ignore-src -y
catkin_make
source devel/setup.bash
3. 在UR3末端安装力传感器

我是直接在universal_robotrobotiq工具包中进行修改安装的,不过建议将需要修改的文件复制出来放在新建的一个包中,可以避免直接修改原仓库,提高代移植性

  • 复制universal_robot/ur_description/urdf中的ur3.xacro,并命名为ur3_ft_gripper.xacro(复制放在同一目录下)

  • 查看ur3的末端link是什么

找到universal_robot/ur_description/urdf/inc中的ur_macro.xacro文件,文件最后几行中暴露了ur机械臂的末端link为tool0

20230220161059

剩下的就是将力传感器接在ur3末端中,根据robotiq/robotiq_ft_sensor/urdf中的robotiq_ft300.urdf.xacro文件中的使用例子

20230220163231

ur3_ft_gripper.xacro文件中分别添加下面的代码

<xacro:include filename="$(find robotiq_ft_sensor)/urdf/robotiq_ft300.urdf.xacro"/> 
<!--robotiq_ft_sensor-->
<xacro:robotiq_ft300 prefix="" parent="tool0">
    <origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:robotiq_ft300>

将官方提供的例子中parent参数改成机械臂末端link的名称,即将robot_flange_link改成tool0

此时完整的ur3_ft_gripper.xacro文件代码如下:

<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur3_robot_ft_gripper">
  <xacro:include filename="$(find ur_description)/urdf/inc/ur3_macro.xacro"/>
  <xacro:ur3_robot prefix="" />
  
  <xacro:include filename="$(find robotiq_ft_sensor)/urdf/robotiq_ft300.urdf.xacro"/> 

  <!--robotiq_ft_sensor-->
  <xacro:robotiq_ft300 prefix="" parent="tool0">
      <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:robotiq_ft300>

</robot>

  • 修改三个launch文件

复制universal_robot/ur_description/launch文件夹下中的view_ur3.launchload_ur3.launchload_ur.launch文件,分别命名为view_ur3_ft_gripper.launchload_ur3_ft_gripper.launchload_ur_ft_gripper.launch文件

修改view_ur3_ft_gripper.launch文件,将include标签中的load_ur3.launch改成load_ur3_ft_gripper.launch,整个文件如下

<?xml version="1.0"?>
<launch>
  <include file="$(find ur_description)/launch/load_ur3_ft_gripper.launch"/>

  <node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
  <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>

修改load_ur3_ft_gripper.launch文件,将include标签中的load_ur.launch改成load_ur_ft_gripper.launch,整个文件如下

<?xml version="1.0"?>
<launch>
  <!--ur3 parameters files -->
  <arg name="joint_limit_params" default="$(find ur_description)/config/ur3/joint_limits.yaml"/>
  <arg name="kinematics_params" default="$(find ur_description)/config/ur3/default_kinematics.yaml"/>
  <arg name="physical_params" default="$(find ur_description)/config/ur3/physical_parameters.yaml"/>
  <arg name="visual_params" default="$(find ur_description)/config/ur3/visual_parameters.yaml"/>
  <!--common parameters -->
  <arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
  <arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
  <arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
  <arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />

  <arg name="robot_model" value="ur3" />

  <!-- use common launch file and pass all arguments to it -->
  <include file="$(find ur_description)/launch/load_ur_ft_gripper.launch" pass_all_args="true"/>
</launch>

修改load_ur_ft_gripper.launch文件,将param标签中command第二个路径中的ur.xacro改成刚刚一开始修改的xacro文件ur3_ft_gripper.xacro,整个文件如下

<?xml version="1.0"?>
<launch>
  <!--ur parameters files -->
  <arg name="joint_limit_params" doc="YAML file containing the joint limit values"/>
  <arg name="kinematics_params" doc="YAML file containing the robot's kinematic parameters. These will be different for each robot as they contain the robot's calibration."/>
  <arg name="physical_params" doc="YAML file containing the phycical parameters of the robots"/>
  <arg name="visual_params" doc="YAML file containing the visual model of the robots"/>
  <!--common parameters  -->
  <arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
  <arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
  <arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
  <arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />

  <arg name="robot_model" />

  <param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur3_ft_gripper.xacro'
    robot_model:=$(arg robot_model)
    joint_limit_params:=$(arg joint_limit_params)
    kinematics_params:=$(arg kinematics_params)
    physical_params:=$(arg physical_params)
    visual_params:=$(arg visual_params)
    transmission_hw_interface:=$(arg transmission_hw_interface)
    safety_limits:=$(arg safety_limits)
    safety_pos_margin:=$(arg safety_pos_margin)
    safety_k_position:=$(arg safety_k_position)"
    />
</launch>
  • 查看效果
    运行命令
cd ~/catkin_ws
source devel/setup.bash
roslaunch ur_description view_ur3_ft_gripper.launch

20230220171354

可以看到多出来一截,就是力传感器

4. 在力传感器末端安装夹爪
  • 查看力传感器末端link是什么

找到robotiq/robotiq_ft_sensor/urdf中的robotiq_ft300.urdf.xacro文件,文件最后几行中暴露了力传感器的末端link为robotiq_ft_frame_id

20230220161709

  • 再来看看夹爪末端的link是什么

找到robotiq/robotiq_2f_140_gripper_visualization/urdf中的robotiq_arg2f_140_macro.xacro文件,文件最后几段就是在将夹爪拼接起来,其中看到robotiq_arg2f_base_link拼接到base_link上,说明夹爪的末端link就是robotiq_arg2f_base_link

20230220172147

将框中的这几行注释掉,因为不能让他再和base_link连接起来,而是将它连接到力传感器上

  • 修改universal_robot/ur_description/urdf/ur3_ft_gripper.xacro文件

添加下面代码,将夹爪包含进来

<xacro:include filename="$(find robotiq_2f_140_gripper_visualization)/urdf/robotiq_arg2f_140.xacro" />
<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>

添加一个joint是为了将力传感器末端link和夹爪末端link连接起来

该文件完整代码如下:

<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur3_robot_ft_gripper">
  <xacro:include filename="$(find ur_description)/urdf/inc/ur3_macro.xacro"/>
  <xacro:ur3_robot prefix="" />
  
  <xacro:include filename="$(find robotiq_ft_sensor)/urdf/robotiq_ft300.urdf.xacro"/> 
  <xacro:include filename="$(find robotiq_2f_140_gripper_visualization)/urdf/robotiq_arg2f_140.xacro" />

  <!--robotiq_ft_sensor-->
  <xacro:robotiq_ft300 prefix="" parent="tool0">
      <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:robotiq_ft300>

  <!--robotiq_arg2f_140.xacro已经调用了robotiq_arg2f_140宏定义,这里只需要把gripper和sensor用joint连接起来即可-->

  <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>
  • 本来也需要修改三个launch文件,但是上面安装力传感器已经修改了,所以不用再修改了

  • 查看效果
    运行命令

cd ~/catkin_ws
source devel/setup.bash
roslaunch ur_description view_ur3_ft_gripper.launch

20230220173028

可以看到多出来一个夹爪

评论 5
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值