ubuntu系统下使用ros控制UR真实机械臂,逻辑清晰,亲测有效

本文详细介绍了如何在Ubuntu18.04系统中使用ROSMelodic控制UR5e机械臂,包括安装ROS系统、下载Universal_Robots_ROS_Driver驱动、安装URCap、设置UR机械臂和电脑的IP,以及启动ROS驱动和moveit进行机械臂运动规划。过程中强调了URCap的安装和IP配置对通讯的重要性。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

一、背景

UR机械臂作为目前论文中的“常青树”,被广泛使用,不得不说其质感确实是国产臂不能比的,也不是说国产臂不好,只是发展时间较短,正迎头赶超,毕竟优傲从2005年创立以来,一直深耕UR机械臂的研发。

因此,本博客梳理一下在ubuntu系统使用ros控制UR真实机械臂的思路,逻辑清晰,亲测有效,并记录踩过的坑。从0开始,使用ros控制真实UR机械臂。

环境:ubuntu18.04
ros版本:melodic
机械臂型号:UR5e
工作空间:UR_ws

获得UR机械臂末端相对于基座的方法:

rosrun tf tf_echo base tool0

二、:安装ubuntu18.04系统+ROS melodic

这个教程太多了,也可以参考我前面写的CSDN,这篇博客假设你已经成功安装ubuntu18.04系统+ROS melodic,这里不再赘述。

三、:下载Universal_Robots_ROS_Driver驱动

说明&写在前面:下载Universal_Robots_ROS_Driver驱动的过程中,已经下载了universal_robot的相关包,不要再单独重复下载,不然后期编译工作空间的时候会报错。
虽然不用单独下载universal_robot包,但还是贴一下该包的官方网址,里面主要包括urdf等描述文件和官方配置好的moveit。
网址:https://github.com/ros-industrial/universal_robot

a:Universal_Robots_ROS_Driver驱动下载地址:
https://github.com/UniversalRobots/Universal_Robots_ROS_Driver
按照README里的步骤安装即可。
这里贴一下安装流程:

# source global ros
source /opt/ros/<your_ros_version>/setup.bash

# create a catkin workspace
mkdir -p catkin_ws/src && cd catkin_ws

# clone the driver
git clone https://github.com/UniversalRobots/Universal_Robots_ROS_Driver.git src/Universal_Robots_ROS_Driver

# clone the description. Currently, it is necessary to use the melodic-devel branch.
git clone -b melodic-devel https://github.com/ros-industrial/universal_robot.git src/universal_robot

# install dependencies
sudo apt update -qq
rosdep update
rosdep install --from-paths src --ignore-src -y

# build the workspace
catkin_make

# activate the workspace (ie: source it)
source devel/setup.bash

#号前面的是解释

驱动安装完成后,在工作空间的src文件夹下会有universal_robot和Universal_Robots_ROS_Driver两个文件,universal_robot就是前面提到的ur机械臂描述文件和moveit包,Universal_Robots_ROS_Driver就是ur机械臂和ros连接的驱动程序

四、在实体UR机器人安装URCap

URCap相当于UR机械臂可以被外部设备控制的一个插件,如果不安装的话,应该只能使用示教器控制机械臂。
a:下载URCap网址:
https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/blob/master/ur_robot_driver/doc/install_urcap_cb3.md

b:根据文档提示For using the ur_robot_driver with a real robot you need to install the externalcontrol-x.x.x.urcap which can be found here,点击here
下载最新版本的URCap,我这里下载的是externalcontrol-1.0.5.urcap

c:将下载好的externalcontrol-1.0.5.urcap拷贝到U盘,然后U盘插入到UR的控制柜

d:打开UR5e机械臂,我们示教器面板的界面和官方文档不一样,我这里选择—右上角的三个横线—设置—系统----URCap—下面的+号—添加U盘的externalcontrol-1.0.5.urcap—打开该文件—重启机械臂

e:重启后,选择最上面的程序—URCap—External Control—我这里显示
Host IP:192.168.0.102
Custrom port:50002
依据此IP设置电脑ubuntu系统下的IP,端口为50002不用动。

特别注意,修改URCap—External Control的Host IP和Custrom port方法:
UR面板最上方安装设置—URCap—External Control
在这里插入图片描述

五、UR机械臂和电脑IP设置

a:UR机械臂示教器IP设置
示教器右上角的三个横线—设置—系统—网络
网络:选择静态地址
ur机械臂IP地址 : 192.168.0.101
ur机械臂子网掩码: 255.255.255.0
默认网关:0.0.0.0
首选DNS服务器:0.0.0.0
备用DNS服务器:0.0.0.0
然后应用即可

b:电脑ubuntu系统下IP设置:
右上角设置–Network–Wired设置按钮—IPv4
手动设置manual
Address:192.168.0.102
Netmask: 255.255.255.0

如何电脑的IPv4设置不了,则先点击下图Details中红色的Remove Connection Profile,然后再在IPv4中设置Address和Netmask。
在这里插入图片描述

此时UR机械臂和电脑IP均设置完毕,检测机械臂实体和电脑是否通讯:
首先使用网线将电脑和机械臂控制柜连接,断开电脑的wifi
打开终端,执行以下命令:

ping 192.168.0.101

这里ping的是机械臂IP,根据大家实际情况而定,若提示如下,则说明机械臂和电脑IP配置成功。
在这里插入图片描述

六、ubuntu系统下使用ros驱动UR5e机械臂

依旧参考官方文档:https://github.com/UniversalRobots/Universal_Robots_ROS_Driver
a:提取标定信息。

cd UR_ws/
catkin_make
source devel/setup.bash
roslaunch ur_calibration calibration_correction.launch robot_ip:=<robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml"

这里的<robot_ip> 填写机械臂的IP

b:步骤一:终端1启动机器人驱动程序

cd UR_ws
source devel/setup.bash
roslaunch ur_robot_driver ur5e_bringup.launch robot_ip:=192.168.0.101

提示:
UR_ws是我的工作空间名字,根据你们情况修改,一般为catkin_ws;
ur5e是我们的机械臂型号,如果你的是ur3,则改为ur3;
robot_ip:=后面是自己的机械臂IP,根据实际情况修改。

c:步骤二:在机器人示教器上,点击【程序】,选择【URCaps】,然后【External Control】,teach-panent最下面三角号运行程序。之后可以看到运行驱动的终端显示:

在这里插入图片描述

d:步骤三:终端2启动moveit:

roslaunch ur5e_moveit_config moveit_planning_execution.launch limited:=true

e:步骤四:终端3启动rviz:

roslaunch ur5e_moveit_config moveit_rviz.launch config:=true

f:步骤五:rviz界面配置
Fixed Frame:base
Add:添加RobotModel,添加机械臂模型
ADD:添加MotionPlanning,添加规划界面,拖动小球可以plan机械臂的轨迹,excute机械臂执行运动。

切忌,实体机械臂执行运动时,手一定要放在示教器上的急停按钮,防止机械臂打到人或损坏机械臂。

在这里插入图片描述
在这里插入图片描述

完结~~~

### 使用ROS控制实际硬件机械 为了实现通过ROS控制系统中的真实机械,通常需要遵循一系列配置和编程流程。这不仅涉及软件环境的搭建,还包括特定于所使用机械型号的驱动程序安装以及MoveIt!框架的应用。 #### 安装必要的依赖项 确保已正确设置ROS环境并安装了`ros-desktop-full`包,其中`<distro>`代表当前使用ROS版本名称(如melodic, noetic)。对于具体品牌的机械支持,则需额外下载对应的ROS兼容驱动: ```bash sudo apt-get install ros-melodic-desktop-full ``` #### 配置机械模型与接口 针对不同品牌和类型的机械设备,制造商一般会提供官方推荐的ROS集成方案。这些资源往往包含了详细的启动文件、URDF描述文档以及其他辅助工具来简化开发过程[^1]。 #### 初始化MoveIt! 完成上述准备工作之后,可以利用MoveIt!进一步增强对机械的操作能力。首先应当获取适用于目标平台的预设参数集,并将其加载到规划场景当中去。此步骤可通过执行如下命令自动完成: ```bash roslaunch ur_moveit_config demo.launch ``` 这里假设使用的是Universal Robots系列之一作为实例对象;其他厂商的产品可能具有不同的命名约定,请参照各自的技术手册调整指令细节[^2]。 #### 编写Python脚本调用API 下面给出了一段简单的Python代码片段用于演示如何借助`moveit_commander`库发送运动请求给连接着的真实物理装置: ```python import sys import copy import rospy import moveit_commander import moveit_msgs.msg import geometry_msgs.msg def main(): # Initialize the moveit commander and node. moveit_commander.roscpp_initialize(sys.argv) rospy.init_node('move_group_python_interface_tutorial', anonymous=True) robot = moveit_commander.RobotCommander() scene = moveit_commander.PlanningSceneInterface() group_name = "manipulator" move_group = moveit_commander.MoveGroupCommander(group_name) display_trajectory_publisher = rospy.Publisher( '/move_group/display_planned_path', moveit_msgs.msg.DisplayTrajectory, queue_size=20) planning_frame = move_group.get_planning_frame() print("============ Planning frame: %s" % planning_frame) eef_link = move_group.get_end_effector_link() print("============ End effector link: %s" % eef_link) group_names = robot.get_group_names() print("============ Available Planning Groups:", robot.get_group_names()) joint_goal = move_group.get_current_joint_values() joint_goal[0] = 0 joint_goal[1] = -2 * math.pi / 8 joint_goal[2] = 0 joint_goal[3] = -2 * math.pi / 4 joint_goal[4] = 0 joint_goal[5] = 2 * math.pi / 6 move_group.go(joint_goal, wait=True) move_group.stop() if __name__ == '__main__': try: main() except rospy.ROSInterruptException: pass ``` 这段代码展示了怎样初始化MoveIt!控制器并与指定关节位置同步的过程。值得注意的是,在实际部署前还需考虑更多因素比如安全边界设定、碰撞检机制等以保障操作的安全性和可靠性。
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值