UR3双臂配合Kinect V2深度相机、云台实现轨迹规划、避障等功能。
UR3机械臂两个、Kinect v2、云台、底座
系统:Ubuntu16.04 虚拟机(由于虚拟机跑Kinect存在串口bug,之后更换Ubuntu双系统)、ROS-Kinetic
ros包:UR机械臂驱动包—ur_modern_driver
ros包:UR机械臂moveit包—universal_robot
universal_robot包通过以太网连接与硬件进行通信,当建立连接的时候ROS-Industrial上传由URScript编写的程序,URScript是类似python的UR机器人自己的脚本语言。这段程序负责监听ROS-Industrial的 simple_messages 包发送的消息信息,并将这些消息解释成硬件指令。
打开机械臂示教器,松开急停按钮,加载安装设置,打开机械臂,进入机械臂设置。设置界面选择网络,配置静态地址,输入IP地址、子网掩码,完成配置。
由于使用的机械臂固件为3.9.1,相对应的机械臂驱动包为ur_modern_driver。使用时编译报错,修改驱动包中的ur_hardware_interface.cpp文件。检索文件中的hardware_interface,替换为type。
机械臂驱动包ur_modern_driver使用原包中的ur_description模型。按照驱动包的README.md文件说明,在ur3.urdf.xacro文件ur3_robot macro内,添加代码:
控制机械臂之前,首先ping一下机械臂网址。例如我的机械臂IP为192.168.33.33,在终端内输入命令:
ping 192.168.33.33
打开终端,输入命令:
roslaunch ur_modern_driver ur3_bringup.launch robot_ip:=192.168.33.33 [reverse_port:=REVERSE_PORT] #替换robot_ip为自己的机械臂IP
打开新终端,运行UR3自带的机械臂demo运动程序:
rosrun ur_driver test_move.py #时刻注意机械臂位置,随时准备按急停按钮
终止test_move.py脚本,运行MoveIT文件。打开新终端,输入命令:
roslaunch ur3_moveit_config ur5_moveit_planning_execution.launch
打开新终端,运行带路径规划器的rviz,输入命令:
roslaunch ur3_moveit_config moveit_rviz.launch config:=true
UR包自带一份带关节约束的文件,每个关节约束在[-PI/2,PI/2],若想运行带关节约束的文件,在终端运行命令:
roslaunch ur_modern_driver ur3_bringup.launch limited:=true robot_ip:=192.168.33.33 [reverse_port:=REVERSE_PORT]
roslaunch ur3_moveit_config ur5_moveit_planning_execution.launch limited:=true
roslaunch ur3_moveit_config moveit_rviz.launch config:=true
在运行moveIT文件时,时常会碰到moveIT报错问题。报错如下
[ERROR] [1515404258.018207679]: Ignoring transform for child_frame_id "tool0_controller" from authority "unknown_publisher" because of a nan value in the transform (0.000000 26815622274503241629349378993175553962225540122973894056168551426931042827562994218784229639762337459109057520690886188494020583679371347120178163255083008.000000 26815622274206272770731577112262473438093890782345820683584369763133472687942565341004009969841415624372630858128332080466218773763999513725165301565227008.000000) (-nan -nan -nan -nan)
报错原因参考:GitHub Issues
主要是因为loosing the connection to the realtime port,导致TF信息丢失,在重连之后,随机发布末端效应器位置姿态,导致moveIT无法运行。
解决办法:在重连成功之后,清空buffer,修改源文件。
#ur_modern_driver/src/ur_realtime_communication.cpp line185,添加下列代码
bzero(buf, 2048);
FD_ZERO(&readfds);
FD_SET(sockfd_, &readfds);
#ur_modern_driver/src/ur_communication.cpp line173,添加下列代码
bzero(buf, 2048);
FD_ZERO(&readfds);
FD_SET(sec_sockfd_, &readfds);
重新编译,运行,拔掉网线,重新连接之后,moveIT不再报错。
建立新的bringup包,新建launch文件,命名为ur3_man_bringup.launch。文件启动左右机械臂的两个ROS节点,分别赋予不同的名称。
#单个机械臂的驱动节点,因为安装状态问题,以左右臂加以区分
运行新写的launch文件,终端发生binding socket错误,在源代码中搜索报错内容,定位到代码段ur_modern_driver/src/ur_driver.cpp line54。
报错大致原因是左右双臂在运行驱动时,分别申请了一个监听端口用以监听所有通信,因为没有设置reverse_port值,所以驱动运行时左右双臂均申请了同一端口50001,所以运行时发生错误。解决办法:在驱动节点运行时增加新的参数用以区分双臂的reverse_port。
#新增代码,置于某一驱动结点内部
更改launch文件之后,驱动运行正常。
moveIT配置 。运行setup_assistant.launch文件,按照常规方法配置moveIT文件,注意,在planing_group环节增加一个move_group组,用于同时控制左右双臂。group_name填写mvoe_group,之后增加subgroups,选择左右双臂对应的group。
生成moveit_config包之后,按照常规方式更改文件用与控制机械臂实体。