ubuntu20.04 进行机械臂抓取仿真(1)

本文档详细介绍了如何在ROS环境中为Universal Robots的UR机械臂添加夹爪。首先从官方和第三方源下载必要的软件包,包括UR机械臂驱动、夹爪插件和相关依赖。然后,针对gazebo版本不匹配的问题,替换夹爪文件中的旧版API,并修改夹爪和机械臂的urdf配置文件。接着,更新launch文件以包含夹爪控制器,并进行编译。最后,运行启动文件时可能会遇到警告,但不影响最终功能。
摘要由CSDN通过智能技术生成

这一部分为后面的部分做准备:

在这里我使用的是官方提供的ur机械臂;废话不多说,进入正题;

1、从官网上下载ur机械臂

在终端中进入工作空间下的src目录输入下面几串代码

git clone https://github.com/UniversalRobots/Universal_Robots_ROS_Driver.git src/Universal_Robots_ROS_Driver
git clone -b calibration_devel https://github.com/fmauch/universal_robot.git src/fmauch_universal_robot
git clone https://github.com/ros-industrial/ur_msgs.git src/ur_msgs
rosdep install --from-paths src --ignore-src -y
catkin_make

2、给ur机械臂添加夹爪

(1)从官网上下载的ur机械臂是没有夹爪的,我们需要自己添加夹爪。

在终端中进入工作空间输入代码下载夹爪

git clone https://github.com/DH-Robotics/dh_gripper_ros.git src/dh_gripper_ros

夹爪下载完之后再进行编译,这时候会报错,因为咱们下载的夹爪文件中程序调用的时Gazebo7中的 API,而在gazebo9时函数已经被改写,有的函数已经不存在。所以我们需要将部分文件替换成gazebo11的版本(因为我用的是gazebo11版本的)。

https://github.com/roboticsgroup/roboticsgroup_gazebo_plugins.git

打开网址并下载,然后将里面的文件复制并粘贴到你刚刚下载的夹爪文件下dh_robotics_ag95_gripper/dh_robotics_ag95_simulation/roboticsgroup_gazebo_plugins (将里面的文件删掉)。然后进行编译。

(2)在刚刚下载好的夹爪文件操作

打开dh_robotics_ag95_gripper/dh_robotics_ag95_description/urdf/dh_robotics_ag95_gripper.xacro,然后将下面几段代码注释掉并保存。

<gazebo>
        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> 
            <robotNamespace>/</robotNamespace>
            <legacyModeNS>true</legacyModeNS>
        </plugin> 
    </gazebo>

 <link name="world"/>
    <joint name="world_fixed" type="fixed">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="world"/>
        <child link="gripper_root_link"/>
    </joint>

    <link name="gripper_root_link">
        <visual>
            <origin xyz="0 0 0.5" rpy="0 0 0"/>
            <geometry>
                <box size="0.1 0.1 1.0"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0.5" rpy="0 0 0"/>
            <geometry>
                <box size="0.1 0.1 1.0"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="1e2" />
            <origin xyz="0.0 0.0 0.0" />
            <inertia ixx = "0.000001" ixy = "0.000000" ixz = "0.000000"
                     iyx = "0.000000" iyy = "0.000001" iyz = "0.000000"
                     izx = "0.000000" izy = "0.000000" izz = "0.000001" />
        </inertial>
    </link>
    
    <xacro:dh_robotics_ag95_gripper prefix="" parent="gripper_root_link" >
        <origin xyz="0.05 0 0.85" rpy="${pi/2}  0 ${pi/2}"/>
    </xacro:dh_robotics_ag95_gripper>

然后打开机械臂文件:打开fmauch_universal_robot/ur_description/urdf,复制ur5.xacro文件并重命名;并且添加下面几行代码:

<xacro:include filename="$(find dh_robotics_ag95_description)/urdf/dh_robotics_ag95_gripper.xacro" />

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

打开fmauch_universal_robot/ur_description/launch,复制load_ur5.launch并且重命名,将下面代码替代原来的代码

<?xml version="1.0"?>
<launch>
  <!--ur5 parameters files -->
  <arg name="joint_limit_params" default="$(find ur_description)/config/ur5/joint_limits.yaml"/>
  <arg name="kinematics_params" default="$(find ur_description)/config/ur5/default_kinematics.yaml"/>
  <arg name="physical_params" default="$(find ur_description)/config/ur5/physical_parameters.yaml"/>
  <arg name="visual_params" default="$(find ur_description)/config/ur5/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" />


  <param name="robot_description" command="$(find xacro)/xacro $(find ur_description)/urdf/ur5_dh.xacro transmission_hw_interface:=$(arg transmission_hw_interface)" />
  
  
  <!-- use common launch file and pass all arguments to it -->
  <!-- <include file="$(find ur_description)/launch/load_ur.launch" pass_all_args="true"/> -->
</launch>

继续在这一个launch文件夹下复制view_ur5.launch,并且重命名;修改其中的部分内容。

<?xml version="1.0"?>
<launch>
  <include file="$(find ur_description)/launch/load_ur5_dh.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>

然后找到ur_gazebo/launch,复制ur5_bringup.launch并且重命名;修改其中的部分内容。

<?xml version="1.0"?>
<launch>
<include file="$(find ur_description)/launch/load_ur5_dh.launch"/>
<rosparam file="$(find dh_robotics_ag95_gazebo)/controller/gripper_controller_dh_robotics.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller gripper" respawn="false" output="screen"/>
<node name="gui_controller" pkg="rqt_joint_trajectory_controller" type="rqt_joint_trajectory_controller" />

  <!--Robot description and related parameter files -->
  <arg name="robot_description_file" default="$(dirname)/inc/load_ur5.launch.xml" doc="Launch file which populates the 'robot_description' parameter."/>
  <arg name="joint_limit_params" default="$(find ur_description)/config/ur5/joint_limits.yaml"/>
  <arg name="kinematics_params" default="$(find ur_description)/config/ur5/default_kinematics.yaml"/>
  <arg name="physical_params" default="$(find ur_description)/config/ur5/physical_parameters.yaml"/>
  <arg name="visual_params" default="$(find ur_description)/config/ur5/visual_parameters.yaml"/>

  <!-- Controller configuration -->
  <arg name="controller_config_file" default="$(find ur_gazebo)/config/ur5_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
  <arg name="controllers" default="joint_state_controller pos_joint_traj_controller" doc="Controllers that are activated by default."/>
  <arg name="stopped_controllers" default="joint_group_pos_controller" doc="Controllers that are initally loaded, but not started."/>

  <!-- robot_state_publisher configuration -->
  <arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
  <arg name="tf_pub_rate" default="125" doc="Rate at which robot_state_publisher should publish transforms."/>

  <!-- Gazebo parameters -->
  <arg name="paused" default="false" doc="Starts Gazebo in paused mode" />
  <arg name="gui" default="true" doc="Starts Gazebo gui" />

  <!-- Load urdf on the parameter server -->
  <include file="$(arg robot_description_file)">
    <arg name="joint_limit_params" value="$(arg joint_limit_params)"/>
    <arg name="kinematics_params" value="$(arg kinematics_params)"/>
    <arg name="physical_params" value="$(arg physical_params)"/>
    <arg name="visual_params" value="$(arg visual_params)"/>
  </include>

  <!-- Robot state publisher -->
  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
    <param name="publish_frequency" type="double" value="$(arg tf_pub_rate)" />
    <param name="tf_prefix" value="$(arg tf_prefix)" />
  </node>

  <!-- Start the 'driver' (ie: Gazebo in this case) -->
  <include file="$(dirname)/inc/ur_control.launch.xml">
    <arg name="controller_config_file" value="$(arg controller_config_file)"/>
    <arg name="controllers" value="$(arg controllers)"/>
    <arg name="gui" value="$(arg gui)"/>
    <arg name="paused" value="$(arg paused)"/>
    <arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
  </include>
</launch>

最后进行编译一下,运行 roslaunch ur_description view_ur5_dh.launch 

 警告:

运行的时候会出现如下警告:

 这个不影响(因为yaml更新,导致的)。

  • 10
    点赞
  • 77
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 10
    评论
评论 10
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

没入&浅出

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值