系统:Ubuntu22.04 + ROS2-humble
官方仓库:https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/tree/humble
目录
- 1.官方仓库概述
-
- [1.1 基本概述](#1.1 基本概述)
- [1.2 仓库中的软件包](#1.2 仓库中的软件包)
- [1.3 系统要求](#1.3 系统要求)
- [1.4 入门指南](#1.4 入门指南)
-
- [1.4.1 安装驱动](#1.4.1 安装驱动)
- [1.4.2 启动并设置机器人](#1.4.2 启动并设置机器人)
- [1.4.3 启动驱动](#1.4.3 启动驱动)
- [1.5 MoveIt支持](#1.5 MoveIt支持)
- [2.本地部署运行UR ROS2(真机)](#2.本地部署运行UR ROS2(真机))
-
- [2.1 PC和真机通讯](#2.1 PC和真机通讯)
- [2.2 示教器端](#2.2 示教器端)
- [2.3 PC端](#2.3 PC端)
- 3.使用自定义的仿真环境进行moveit规划
-
- [3.1 官方示例代码分析](#3.1 官方示例代码分析)
- [3.2 使用自定义的urdf文件](#3.2 使用自定义的urdf文件)
1.官方仓库概述
1.1 基本概述
-
此驱动基于 Universal_Robots_Client_Library 开发,支持一些关键的协作机器人功能,例如:紧急停止时暂停、安全防护停止、自动速度缩放以避免违反安全设置以及通过示教器进行手动速度缩放。此外,externalControl URCap 使得在机器人程序中纳入 ROS2 行为成为可能。
该驱动兼容全系列的 UR 机器人 ------ 从 3 千克负载到 30 千克负载,包括所有配备 PolyScope X、PolyScope 5 或 CB3 控制器的机器人。
-
关于一些moveit UR的演示视频(基于障碍物避障规划、示教器可以实时改变规划运行的速度、急停后也可以恢复轨迹继续运动)
https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/humble/ur_robot_driver/doc/resources/README.md


1.2 仓库中的软件包
ur- 提供已发布软件包单点安装的元软件包。ur_calibration- 用于从真实机器人提取校准信息的工具。ur_controllers- 适用于 UR 机器人的特定控制器实现。ur_dashboard_msgs- 定义仪表板节点使用的消息的软件包。ur_moveit_config- UR 机器人的示例 MoveIt 配置。ur_robot_driver- 用于与 UR 机器人通信的驱动程序 / 硬件接口。
1.3 系统要求
参阅 Universal_Robots_Client_Library 的要求,因为此驱动基于 Universal_Robots_Client_Library 构建。
- Polyscope(运行于机器人控制器上的软件)版本需为3.14.3(适用于CB3系列)、5.9.4(适用于e系列)或10.7.0(适用于PolyScope X)及以上版本。若使用旧版Polyscope,建议升级您的机器人。若因特殊原因(请在问题反馈中说明原因)无法升级机器人,请参阅版本兼容性表获取适配标签。
- 该库需要POSIX线程的实现,例如pthread库。
1.4 入门指南
1.4.1 安装驱动
bash
sudo apt-get install ros-humble-ur
更多详细的信息参考文档:https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/installation/installation.html
提供两种方式,二进制安装和源码编译安装,这里选择直接二进制包安装。
1.4.2 启动并设置机器人
安装驱动程序后,设置机器人并创建用于外部控制的程序。(IP设置、示教器安装URCap等)
-
a.https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/installation/robot_setup.html
通过示教器给机器人设置固定IP,
本地PC端设置IP和机器人同一频段,
设置好了之后PC端ping一下机器人的IP地址,确认连通。
-
本节将说明如何从示教器安装并启动 URCap 程序。该程序支持 ROS 对机器人进行外部控制。通常的操作流程是:先通过 ROS 启动驱动,再从示教器启动 URCap 程序。
若要在真实机器人上使用 ur_robot_driver,需安装 externalcontrol URCap (外部控制插件)。最新版本可从其专属仓库下载。(https://github.com/UniversalRobots/Universal_Robots_ExternalControl_URCap/releases)

注意:安装此 URCap 需满足最低 PolyScope 版本要求 ------CB3 系列机器人需为 3.7 及以上版本 ,e 系列机器人需为 5.1 及以上版本。 (这里我的示教器上位机版本是5.15.1)
关于必要 URCap 的安装及程序创建,请参考对应教程:
CB3 系列机器人配置URCap教程------https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/installation/install_urcap_cb3.html#install-urcap-cb3
e 系列机器人配置URCap教程------https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/installation/install_urcap_e_series.html#install-urcap-e-series

若需在
e 系列机器人上配置工具通信功能,请参阅工具通信配置指南------https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/setup_tool_communication.html#setup-tool-communication
请谨慎执行此步骤,并按照此处说明提取校准数据 。否则,TCP 在ROS生态系统中的姿态将不准确。https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/installation/robot_setup.html#extract-calibration-information
若无需使用实体机器人,可采用仿真机器人,其行为几乎与真实机器人无异。
https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/usage.html#usage-with-official-ur-simulator
1.4.3 启动驱动
-
有关详细信息,请参阅使用文档:https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/usage.html
-
将
ur_robot_driver拷贝到之前编译好了的moveit_ws/src中,重新编译

-
给机械臂上电
bash
# Replace ur5e with one of ur3, ur5, ur10, ur3e, ur5e, ur7e, ur10e, ur12e, ur16e, ur8long, ur15, ur18, ur20, ur30
# Replace the IP address with the IP address of your actual robot / URSim
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.1.103

运行后可以看到,rviz2中的机器人位姿和实际机器人的一致

- 4.除非在无头模式下启动:按示教器上的play运行external_control程序。
https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/ROS_INTERFACE.html#headless-mode
headless-mode:以无头模式启动机器人。这不需要在机器人上运行"外部控制"URCap,但这将直接向机器人发送URScript。在e-Series机器人上,这要求机器人在"远程控制"模式下运行。
1.5 MoveIt支持
该视频显示了使用Rviz2的MoveIt2 MotionPlanning小部件围绕建模碰撞场景对象进行自由空间轨迹规划。
-
https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/usage.html#using-moveit
-
https://docs.ros.org/en/ros2_packages/humble/api/ur_robot_driver/doc/usage.html
2.本地部署运行UR ROS2(真机)
2.1 PC和真机通讯
- 1.机械臂通过示教器上位机设置固定IP为 192.168.1.103
- 2.将机械臂控制柜的网线和PC端连接,设置PC端固定IP为 192.168.1.165
- 3.PC端通过ping指令确认两者通讯可达

2.2 示教器端
-
1.确认当前的机械臂型号和示教器上位机版本
我当前使用的 UR5e,示教器上位机版本
5.15.1 -
2.下载 ExternalControl_URCap (https://github.com/UniversalRobots/Universal_Robots_ExternalControl_URCap/releases)
这里选择 v1.0.5版本, 下载
externalcontrol-1.0.5.urcap将下载好的
externalcontrol-1.0.5.urcap拷贝到U盘中,插到示教器的USB口上 -
3.示教器界面点击右上角设置------系统------URCaps ,点击 + 号,选择U盘中的
externalcontrol-1.0.5.urcap,点击加载,此时会提醒你重启机器人,点击重启。

-
4.重启后点击安装节点中的 URCaps 节点,这里需要设置远程PC端的IP地址,我设置 192.168.1.165
-
5.程序节点,添加一个External Control的节点到程序树中,如果需要moveit运行控制机械臂,这个程序需要一直在运行中

2.3 PC端
-
1.克隆 https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git 仓库,切换到
humble分支 -
2.安装UR的ros2驱动
bash
sudo apt-get install ros-humble-ur
- 3.将 Universal_Robots_ROS2_Driver 仓库中的
ur、ur_calibration、ur_dashboard_msgs、ur_robot_driver、ur_bringup、ur_controllers、ur_moveit_config都拷贝到/moveit_ws/src中(这里为防止用到别的库,我一次性全拷贝过去了)
切换到/moveit_ws目录下,编译
bash
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --executor sequential
先启动 ur_robot_driver
bash
source install/setup.bash
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.1.103
看下当前rviz2中的机器人位姿和实际机器人的是否一致,如果一致则 ok
再另起终端启动 ur_moveit_config
bash
source install/setup.bash
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true

- 4.拖动黄色的目标pose机械臂,点击 MotionPlanning 的 Plan 和 Execute看下真实机器人是否可以移动到位。
UR5e 真实机器人的
scaled_joint_trajectory_controller(moveit)需要满足如下前提才会进入运行状态:(PC端先运行 ur_robot_driver、示教器端再运行External Control程序,此时ur_robot_driver终端会有输出,最后将示教器改为远程模式。)
- 1.示教器需运行程序 External Control;
- 2.机器人处于远程控制模式;
- 3.驱动节点的controller_manager已加载并激活该控制器;(需要启动ur_robot_driver节点)
- 4.机器人未处于急停 / 保护停止状态(硬件安全机制)。
3.使用自定义的仿真环境进行moveit规划
需求:目前在做抓取任务,由于周围环境有一些障碍物,需求进行避障的路径规划,将周围环境通过URDF建模显示到环境中。
关于URDF建模参考:https://blog.csdn.net/qq_45445740/article/details/155353989?spm=1001.2014.3001.5501
3.1 官方示例代码分析
ur_robot_driver
之前我们是通过如下指令启动该节点:
bash
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.1.103
- 分析
ur_control.launch.py


终端中输入参数是机械臂类型和机器人的IP,会根据这个类型去加载相应的机器人的urdf文件,但是在src文件夹中并没有相关机械臂的urdf文件,有点好奇是从哪儿加载的,在源代码中加了打印获取真实的urdf文件路径。
python
# 解析实际的包名和文件名
desc_pkg_name = context.perform_substitution(description_package)
desc_file_name = context.perform_substitution(description_file)
# 查找包的实际路径
pkg_share_path = FindPackageShare(desc_pkg_name).perform(context)
# 构建完整的URDF文件路径
full_urdf_path = os.path.join(pkg_share_path, "urdf", desc_file_name)
# 打印详细信息
print("\n" + "-"*50)
print("解析后的URDF文件详细信息:")
print(f"描述包实际路径: {pkg_share_path}")
print(f"URDF文件名称: {desc_file_name}")
print(f"URDF文件完整路径: {full_urdf_path}")
print(f"文件是否存在: {os.path.exists(full_urdf_path)}")

经过打印后可以发现原来之前通过apt指令安装的ros-humble-ur会将相应的UR ROS2文件下载到本机系统目录下:

加载的是/opt/ros/humble/share/ur_description目录下的文件
Universal_Robots_ROS2_Description :https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/tree/humble
如果通过 sudo apt-get install ros-humble-ur 安装后,可以在本地 /opt/ros/humble/share/ur_description 目录下看到
- 通过
ur_control.launch.py文件会加载/opt/ros/humble/share/ur_description/urdf/ur.urdf.xacro,然后再加载/opt/ros/humble/share/ur_description/urdf/ur_macro.xacro文件。


ur_moveit_config
ur_moveit.launch.py中加载的urdf逻辑和ur_robot_driver一致- 如果ur_moveit_config启动节点后不会给机械臂做规划和运行,可通过
ros2 control list_controllers查看
bash
$ ros2 control list_controllers
[INFO] [1764913635.990601027] [_ros2cli_105632]: waiting for service /controller_manager/list_controllers to become available...
joint_state_broadcaster joint_state_broadcaster/JointStateBroadcaster active
joint_trajectory_controller joint_trajectory_controller/JointTrajectoryController inactive
io_and_status_controller ur_controllers/GPIOController active
forward_velocity_controller velocity_controllers/JointGroupVelocityController inactive
speed_scaling_state_broadcaster ur_controllers/SpeedScalingStateBroadcaster active
forward_position_controller position_controllers/JointGroupPositionController inactive
forward_effort_controller effort_controllers/JointGroupEffortController inactive
force_torque_sensor_broadcaster force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster active
force_mode_controller ur_controllers/ForceModeController inactive
tcp_pose_broadcaster pose_broadcaster/PoseBroadcaster active
passthrough_trajectory_controller ur_controllers/PassthroughTrajectoryController inactive
freedrive_mode_controller ur_controllers/FreedriveModeController inactive
ur_configuration_controller ur_controllers/URConfigurationController active
tool_contact_controller ur_controllers/ToolContactController inactive
scaled_joint_trajectory_controller ur_controllers/ScaledJointTrajectoryController active
3.2 使用自定义的urdf文件
由于UR官方是通过
xacro文件生成urdf来进行加载,现在我有一个自定义环境的urdf,考虑到重写xacro有点繁琐,可以将外部的urdf参数直接修改到默认加载的xacro文件中,


前一部分是机械臂的urdf,由于原有机械臂并未做任何修改,只是在其基础上增加外设,从此往下开始添加。
ur_macro.xacro
xml
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Base UR robot series xacro macro.
NOTE this is NOT a URDF. It cannot directly be loaded by consumers
expecting a flattened '.urdf' file. See the top-level '.xacro' for that
(but note that .xacro must still be processed by the xacro command).
This file models the base kinematic chain of a UR robot, which then gets
parameterised by various configuration files to convert it into a UR3(e),
UR5(e), UR10(e) or UR16e, etc.
NOTE the default kinematic parameters (i.e., link lengths, frame locations,
offsets, etc) do not correspond to any particular robot. They are defaults
only. There WILL be non-zero offsets between the Forward Kinematics results
in TF (i.e., robot_state_publisher) and the values reported by the Teach
Pendant.
For accurate (and robot-specific) transforms, the 'kinematics_parameters_file'
parameter MUST point to a .yaml file containing the appropriate values for
the targeted robot.
If using the UniversalRobots/Universal_Robots_ROS_Driver, follow the steps
described in the readme of that repository to extract the kinematic
calibration from the controller and generate the required .yaml file.
Main author of the migration to yaml configs Ludovic Delval.
Contributors to previous versions (in no particular order)
- Denis Stogl
- Lovro Ivanov
- Felix Messmer
- Kelsey Hawkins
- Wim Meeussen
- Shaun Edwards
- Nadia Hammoudeh Garcia
- Dave Hershberger
- G. vd. Hoorn
- Philip Long
- Dave Coleman
- Miguel Prada
- Mathias Luedtke
- Marcel Schnirring
- Felix von Drigalski
- Felix Exner
- Jimmy Da Silva
- Ajit Krisshna N L
- Muhammad Asif Rana
-->
<xacro:include filename="$(find ur_description)/urdf/inc/ur_transmissions.xacro" />
<xacro:include filename="$(find ur_description)/urdf/inc/ur_common.xacro" />
<xacro:macro name="ur_robot" params="
name
tf_prefix
parent
*origin
joint_limits_parameters_file
kinematics_parameters_file
physical_parameters_file
visual_parameters_file
generate_ros2_control_tag:=true
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20
use_fake_hardware:=false
fake_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
headless_mode:=false
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
use_tool_communication:=false
tool_voltage:=0
tool_parity:=0
tool_baud_rate:=115200
tool_stop_bits:=1
tool_rx_idle_chars:=1.5
tool_tx_idle_chars:=3.5
tool_device_name:=/tmp/ttyUR
tool_tcp_port:=54321
robot_ip:=0.0.0.0
script_filename:=to_be_filled_by_ur_robot_driver
output_recipe_filename:=to_be_filled_by_ur_robot_driver
input_recipe_filename:=to_be_filled_by_ur_robot_driver
reverse_port:=50001
script_sender_port:=50002
reverse_ip:=0.0.0.0
script_command_port:=50004
trajectory_port:=50003
non_blocking_read:=true
keep_alive_count:=2"
>
<!-- Load configuration data from the provided .yaml files -->
<xacro:read_model_data
joint_limits_parameters_file="${joint_limits_parameters_file}"
kinematics_parameters_file="${kinematics_parameters_file}"
physical_parameters_file="${physical_parameters_file}"
visual_parameters_file="${visual_parameters_file}"
force_abs_paths="${sim_gazebo or sim_ignition}"/>
<xacro:if value="${generate_ros2_control_tag}">
<!-- ros2 control include -->
<xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="${name}"
use_fake_hardware="${use_fake_hardware}"
initial_positions="${initial_positions}"
fake_sensor_commands="${fake_sensor_commands}"
headless_mode="${headless_mode}"
sim_gazebo="${sim_gazebo}"
sim_ignition="${sim_ignition}"
script_filename="${script_filename}"
output_recipe_filename="${output_recipe_filename}"
input_recipe_filename="${input_recipe_filename}"
tf_prefix="${tf_prefix}"
hash_kinematics="${kinematics_hash}"
robot_ip="${robot_ip}"
use_tool_communication="${use_tool_communication}"
tool_voltage="${tool_voltage}"
tool_parity="${tool_parity}"
tool_baud_rate="${tool_baud_rate}"
tool_stop_bits="${tool_stop_bits}"
tool_rx_idle_chars="${tool_rx_idle_chars}"
tool_tx_idle_chars="${tool_tx_idle_chars}"
tool_device_name="${tool_device_name}"
tool_tcp_port="${tool_tcp_port}"
reverse_port="${reverse_port}"
script_sender_port="${script_sender_port}"
reverse_ip="${reverse_ip}"
script_command_port="${script_command_port}"
trajectory_port="${trajectory_port}"
non_blocking_read="${non_blocking_read}"
keep_alive_count="${keep_alive_count}"
/>
</xacro:if>
<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
<!-- Placeholder for ros2_control transmission which don't yet exist -->
<!-- links - main serial chain -->
<link name="${tf_prefix}base_link"/>
<link name="${tf_prefix}base_link_inertia">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="base" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="base" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${base_inertia_radius}" length="${base_inertia_length}" mass="${base_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}shoulder_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="shoulder" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="shoulder" type="collision"/>
</geometry>
</collision>
<inertial>
<mass value="${shoulder_mass}"/>
<origin rpy="${shoulder_inertia_rotation}" xyz="${shoulder_cog}"/>
<inertia
ixx="${shoulder_inertia_ixx}"
ixy="${shoulder_inertia_ixy}"
ixz="${shoulder_inertia_ixz}"
iyy="${shoulder_inertia_iyy}"
iyz="${shoulder_inertia_iyz}"
izz="${shoulder_inertia_izz}"
/>
</inertial> </link>
<link name="${tf_prefix}upper_arm_link">
<visual>
<origin xyz="0 0 ${shoulder_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="upper_arm" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${shoulder_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="upper_arm" type="collision"/>
</geometry>
</collision>
<inertial>
<mass value="${upper_arm_mass}"/>
<origin rpy="${upper_arm_inertia_rotation}" xyz="${upper_arm_cog}"/>
<inertia
ixx="${upper_arm_inertia_ixx}"
ixy="${upper_arm_inertia_ixy}"
ixz="${upper_arm_inertia_ixz}"
iyy="${upper_arm_inertia_iyy}"
iyz="${upper_arm_inertia_iyz}"
izz="${upper_arm_inertia_izz}"
/>
</inertial>
</link>
<link name="${tf_prefix}forearm_link">
<visual>
<origin xyz="0 0 ${elbow_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="forearm" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${elbow_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="forearm" type="collision"/>
</geometry>
</collision>
<inertial>
<mass value="${forearm_mass}"/>
<origin rpy="${forearm_inertia_rotation}" xyz="${forearm_cog}"/>
<inertia
ixx="${forearm_inertia_ixx}"
ixy="${forearm_inertia_ixy}"
ixz="${forearm_inertia_ixz}"
iyy="${forearm_inertia_iyy}"
iyz="${forearm_inertia_iyz}"
izz="${forearm_inertia_izz}"
/>
</inertial>
</link>
<link name="${tf_prefix}wrist_1_link">
<xacro:get_visual_params name="wrist_1" type="visual_offset"/>
<visual>
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_1" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_1" type="collision"/>
</geometry>
</collision>
<inertial>
<mass value="${wrist_1_mass}"/>
<origin rpy="${wrist_1_inertia_rotation}" xyz="${wrist_1_cog}"/>
<inertia
ixx="${wrist_1_inertia_ixx}"
ixy="${wrist_1_inertia_ixy}"
ixz="${wrist_1_inertia_ixz}"
iyy="${wrist_1_inertia_iyy}"
iyz="${wrist_1_inertia_iyz}"
izz="${wrist_1_inertia_izz}"
/>
</inertial>
</link>
<link name="${tf_prefix}wrist_2_link">
<xacro:get_visual_params name="wrist_2" type="visual_offset"/>
<visual>
<origin xyz="0 0 ${visual_params}" rpy="0 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_2" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${visual_params}" rpy="0 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_2" type="collision"/>
</geometry>
</collision>
<inertial>
<mass value="${wrist_2_mass}"/>
<origin rpy="${wrist_2_inertia_rotation}" xyz="${wrist_2_cog}"/>
<inertia
ixx="${wrist_2_inertia_ixx}"
ixy="${wrist_2_inertia_ixy}"
ixz="${wrist_2_inertia_ixz}"
iyy="${wrist_2_inertia_iyy}"
iyz="${wrist_2_inertia_iyz}"
izz="${wrist_2_inertia_izz}"
/>
</inertial>
</link>
<link name="${tf_prefix}wrist_3_link">
<!-- TODO: remove this once all wrist_3 meshes have the visual_offset_xyz tag -->
<xacro:get_visual_params name="wrist_3" type="visual_offset_xyz"/>
<xacro:property name="mesh_offset" value="${visual_params}" scope="parent"/>
<xacro:if value="${visual_params == ''}">
<xacro:get_visual_params name="wrist_3" type="visual_offset"/>
<xacro:property name="mesh_offset" value="0 0 ${visual_params}" scope="parent"/>
</xacro:if>
<visual>
<origin xyz="${mesh_offset}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_3" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="${mesh_offset}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_3" type="collision"/>
</geometry>
</collision>
<inertial>
<mass value="${wrist_3_mass}"/>
<origin rpy="${wrist_3_inertia_rotation}" xyz="${wrist_3_cog}"/>
<inertia
ixx="${wrist_3_inertia_ixx}"
ixy="${wrist_3_inertia_ixy}"
ixz="${wrist_3_inertia_ixz}"
iyy="${wrist_3_inertia_iyy}"
iyz="${wrist_3_inertia_iyz}"
izz="${wrist_3_inertia_izz}"
/>
</inertial>
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="${tf_prefix}base_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${tf_prefix}base_link" />
</joint>
<!-- joints - main serial chain -->
<joint name="${tf_prefix}base_link-base_link_inertia" type="fixed">
<parent link="${tf_prefix}base_link" />
<child link="${tf_prefix}base_link_inertia" />
<!-- 'base_link' is REP-103 aligned (so X+ forward), while the internal
frames of the robot/controller have X+ pointing backwards.
Use the joint between 'base_link' and 'base_link_inertia' (a dummy
link/frame) to introduce the necessary rotation over Z (of pi rad).
-->
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
</joint>
<joint name="${tf_prefix}shoulder_pan_joint" type="revolute">
<parent link="${tf_prefix}base_link_inertia" />
<child link="${tf_prefix}shoulder_link" />
<origin xyz="${shoulder_x} ${shoulder_y} ${shoulder_z}" rpy="${shoulder_roll} ${shoulder_pitch} ${shoulder_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}"
effort="${shoulder_pan_effort_limit}" velocity="${shoulder_pan_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_pan_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_pan_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}shoulder_lift_joint" type="revolute">
<parent link="${tf_prefix}shoulder_link" />
<child link="${tf_prefix}upper_arm_link" />
<origin xyz="${upper_arm_x} ${upper_arm_y} ${upper_arm_z}" rpy="${upper_arm_roll} ${upper_arm_pitch} ${upper_arm_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}"
effort="${shoulder_lift_effort_limit}" velocity="${shoulder_lift_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_lift_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_lift_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}elbow_joint" type="revolute">
<parent link="${tf_prefix}upper_arm_link" />
<child link="${tf_prefix}forearm_link" />
<origin xyz="${forearm_x} ${forearm_y} ${forearm_z}" rpy="${forearm_roll} ${forearm_pitch} ${forearm_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}"
effort="${elbow_joint_effort_limit}" velocity="${elbow_joint_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${elbow_joint_lower_limit + safety_pos_margin}" soft_upper_limit="${elbow_joint_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_1_joint" type="revolute">
<parent link="${tf_prefix}forearm_link" />
<child link="${tf_prefix}wrist_1_link" />
<origin xyz="${wrist_1_x} ${wrist_1_y} ${wrist_1_z}" rpy="${wrist_1_roll} ${wrist_1_pitch} ${wrist_1_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}"
effort="${wrist_1_effort_limit}" velocity="${wrist_1_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_1_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_1_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_2_joint" type="revolute">
<parent link="${tf_prefix}wrist_1_link" />
<child link="${tf_prefix}wrist_2_link" />
<origin xyz="${wrist_2_x} ${wrist_2_y} ${wrist_2_z}" rpy="${wrist_2_roll} ${wrist_2_pitch} ${wrist_2_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}"
effort="${wrist_2_effort_limit}" velocity="${wrist_2_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_2_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_2_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_3_joint" type="${wrist_3_joint_type}">
<parent link="${tf_prefix}wrist_2_link" />
<child link="${tf_prefix}wrist_3_link" />
<origin xyz="${wrist_3_x} ${wrist_3_y} ${wrist_3_z}" rpy="${wrist_3_roll} ${wrist_3_pitch} ${wrist_3_yaw}" />
<axis xyz="0 0 1" />
<xacro:if value="${wrist_3_joint_type != 'continuous'}">
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}"
effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_3_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_3_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:if>
<xacro:unless value="${wrist_3_joint_type != 'continuous'}">
<limit effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<dynamics damping="0" friction="0"/>
</joint>
<link name="${tf_prefix}ft_frame"/>
<joint name="${tf_prefix}wrist_3_link-ft_frame" type="fixed">
<parent link="${tf_prefix}wrist_3_link"/>
<child link="${tf_prefix}ft_frame"/>
<origin xyz="0 0 0" rpy="${pi} 0 0"/>
</joint>
<!-- ROS-Industrial 'base' frame - base_link to UR 'Base' Coordinates transform -->
<link name="${tf_prefix}base"/>
<joint name="${tf_prefix}base_link-base_fixed_joint" type="fixed">
<!-- Note the rotation over Z of pi radians - as base_link is REP-103
aligned (i.e., has X+ forward, Y+ left and Z+ up), this is needed
to correctly align 'base' with the 'Base' coordinate system of
the UR controller.
-->
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<parent link="${tf_prefix}base_link"/>
<child link="${tf_prefix}base"/>
</joint>
<!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
<link name="${tf_prefix}flange" />
<joint name="${tf_prefix}wrist_3-flange" type="fixed">
<parent link="${tf_prefix}wrist_3_link" />
<child link="${tf_prefix}flange" />
<origin xyz="0 0 0" rpy="0 ${-pi/2.0} ${-pi/2.0}" />
</joint>
<!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
<link name="${tf_prefix}tool0"/>
<joint name="${tf_prefix}flange-tool0" type="fixed">
<!-- default toolframe - X+ left, Y+ up, Z+ front -->
<origin xyz="0 0 0" rpy="${pi/2.0} 0 ${pi/2.0}"/>
<parent link="${tf_prefix}flange"/>
<child link="${tf_prefix}tool0"/>
</joint>
<!-- ##################### 新增内容:末端快换连接器 ##################### -->
<link name="${tf_prefix}quick_change_disc_connector">
<visual>
<origin rpy="0 0 0" xyz="-0.04485 -0.04247 0.00334"/>
<geometry>
<mesh filename="package://ur_description/meshes/tool_quick_change/quick_change_disc.STL" scale="1.0 1.0 1.0"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.04485 -0.04247 0.00334"/>
<geometry>
<mesh filename="package://ur_description/meshes/tool_quick_change/quick_change_disc.STL" scale="1.0 1.0 1.0"/>
</geometry>
</collision>
<inertial>
<mass value="0.3"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0"
iyy="1e-5" iyz="0.0" izz="1e-5"/>
</inertial>
</link>
<joint name="${tf_prefix}tool0_to_quick_tool" type="fixed">
<parent link="${tf_prefix}tool0"/>
<child link="${tf_prefix}quick_change_disc_connector"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<!-- ##################### 新增内容:夹爪(CTAG2F120) ##################### -->
<link name="${tf_prefix}gripper_connector">
<visual>
<origin rpy="0 0 0" xyz="-0.0155 0 0.02"/>
<geometry>
<mesh filename="package://ur_description/meshes/tool_quick_change/gripper.STL" scale="1.0 1.0 1.0"/>
</geometry>
<material name="MatteBlackPlastic">
<color rgba="0.12 0.12 0.12 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.0155 0 0.02"/>
<geometry>
<mesh filename="package://ur_description/meshes/tool_quick_change/gripper.STL" scale="1.0 1.0 1.0"/>
</geometry>
</collision>
<inertial>
<mass value="3.0"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0"
iyy="1e-5" iyz="0.0" izz="1e-5"/>
</inertial>
</link>
<joint name="${tf_prefix}tool0_to_suction" type="fixed">
<parent link="${tf_prefix}tool0"/>
<child link="${tf_prefix}gripper_connector"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<!-- ##################### 新增内容:机器人工作台 ##################### -->
<link name="${tf_prefix}workspace_stable">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/bin_picking/robbie_table.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="Aluminum_Warm">
<color rgba="0.85 0.86 0.87 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/bin_picking/robbie_table.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<mass value="50.0"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0"
iyy="1e-5" iyz="0.0" izz="1e-5"/>
</inertial>
</link>
<joint name="${tf_prefix}base_to_stable" type="fixed">
<parent link="${tf_prefix}base"/>
<child link="${tf_prefix}workspace_stable"/>
<origin rpy="0 0 -1.57" xyz="0 -0.6 0"/>
</joint>
<!-- ##################### 新增内容:蓝色塑料放置框 ##################### -->
<link name="${tf_prefix}storage_box">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/bin_picking/storage_box.STL" scale="1.0 1.0 1.0"/>
</geometry>
<material name="BluePlastic">
<color rgba="0.3 0.6 0.9 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/bin_picking/storage_box.STL" scale="1.0 1.0 1.0"/>
</geometry>
</collision>
<inertial>
<mass value="10.0"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0"
iyy="1e-5" iyz="0.0" izz="1e-5"/>
</inertial>
</link>
<joint name="${tf_prefix}base_to_storage_box" type="fixed">
<parent link="${tf_prefix}base"/>
<child link="${tf_prefix}storage_box"/>
<origin rpy="0 0 0" xyz="-0.3 0.4 -0.4"/>
</joint>
<!-- ##################### 新增内容:D455相机 ##################### -->
<link name="${tf_prefix}camera">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/bin_picking/d455.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="aluminum">
<color rgba="0.85 0.86 0.87 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/bin_picking/d455.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<mass value="0.072"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0"
iyy="1e-5" iyz="0.0" izz="1e-5"/>
</inertial>
</link>
<joint name="${tf_prefix}base_to_camera" type="fixed">
<parent link="${tf_prefix}base"/>
<child link="${tf_prefix}camera"/>
<origin rpy="0 0 0" xyz="-0.000679524 0.80945 0.957394"/>
</joint>
</xacro:macro>
</robot>
- 效果如下:

