新建工作空间
bash
mkdir -p ~/catkin_ws/src
cd catkin_ws_ur5/src
git clone -b melodic-devel https://github.com/ros-industrial/universal_robot.git
cd ..
rosdep update
rosdep install --rosdistro melodic --ignore-src --from-paths src
catkin_make
source ~/catkin_ws/devel/setup.bash
测试
bash
roslaunch ur_description view_ur5.launch
添加夹爪
view_ur5_gripper.launch文件(修改rviz配置)
包含 load_ur5_gripper.launch
xml
<?xml version="1.0"?>
<launch>
<!-- change -->
<!-- <include file="$(find ur_description)/launch/load_ur5.launch"/> -->
<include file="$(find ur_description)/launch/load_ur5_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_ur5_gripper.launch文件
包含load_ur_gripper.launch
xml
<?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" />
<arg name="robot_model" value="ur5" />
<!-- use common launch file and pass all arguments to it -->
<!-- change -->
<include file="$(find ur_description)/launch/load_ur_gripper.launch" pass_all_args="true"/>
<!-- <include file="$(find ur_description)/launch/load_ur.launch" pass_all_args="true"/> -->
</launch>
load_ur_gripper.launch
robot_description command设置为'$(find ur_description)/urdf/ur5_gripper.xacro'
xml
<?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" />
<!-- 固定写法-->
<!-- change -->
<!-- <param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur.xacro' -->
<!-- <param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur_gripper.xacro' -->
<!-- 直接ur5_gripper.xacro更方便-->
<param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur5_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>
ur5_gripper.xacro (设置prefix值)
包含ur5_macro_gripper.xacro
xml
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur5_robot">
<!--
This is a convenience top-level xacro which loads the macro for the UR5e
which defines the default values for the various "parameters files"
parameters for a UR5e.
This file is only useful when loading a stand-alone, completely isolated
robot with only default values for all parameters such as the kinematics,
visual and physical parameters and joint limits.
This file is not intended to be integrated into a larger scene or other
composite xacro.
Instead, xacro:include 'inc/ur5e_macro.xacro' and override the defaults
for the arguments to that macro.
Refer to 'inc/ur_macro.xacro' for more information.
-->
<!-- change -->
<!-- <xacro:include filename="$(find ur_description)/urdf/inc/ur5_macro.xacro"/> -->
<xacro:include filename="$(find ur_description)/urdf/inc/ur5_macro_gripper.xacro"/>
<xacro:ur5_robot prefix="" />
</robot>
ur5_macro_gripper.xacro (模型参数设置 夹爪添加)
xml
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="ur5_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur5/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur5/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur5/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur5/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<!-- change -->
<!-- <xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.xacro"/> -->
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro_gripper.xacro"/>
<xacro:ur_robot
prefix="${prefix}"
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}"
transmission_hw_interface="${transmission_hw_interface}"
safety_limits="${safety_limits}"
safety_pos_margin="${safety_pos_margin}"
safety_k_position="${safety_k_position}"
/>
<!-- base_link - world joint -->
<link name="world" />
<joint name="world_joint" type="fixed">
<parent link="world" />
<child link = "${prefix}base_link" />
<origin xyz="0.0 0.0 0" rpy="0.0 0.0 0.0" />
</joint>
<!--gripper-->
<xacro:include filename="$(find robotiq_2f_85_gripper_visualization)/urdf/robotiq_arg2f_85_model_macro.xacro" />
<xacro:include filename="$(find robotiq_85_description)/urdf/robotiq_85_gripper.urdf.xacro" />
<xacro:robotiq_85_gripper prefix="" parent="${prefix}tool0" >
<origin xyz="0 0 0" rpy="0 ${-pi/2} 0"/>
</xacro:robotiq_85_gripper>
<!--camera-->
<xacro:include filename="$(find realsense2_description)/urdf/_d415.urdf.xacro" />
<xacro:sensor_d415 parent="${prefix}base_link" use_nominal_extrinsics="false" add_plug="false" use_mesh="true">
<origin xyz="0 0 1" rpy="0 0 0"/>
</xacro:sensor_d415>
</xacro:macro>
</robot>
ur_macro_gripper.xacro(定义joint 和 link 添加ee_link )
xml
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<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="
prefix
joint_limits_parameters_file
kinematics_parameters_file
physical_parameters_file
visual_parameters_file
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<!-- 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}"/>
<!-- Add URDF transmission elements (for ros_control) -->
<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />
<!-- links: main serial chain -->
<link name="${prefix}base_link"/>
<link name="${prefix}base_link_inertia">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="${base_visual_mesh}"/>
</geometry>
<material name="${base_visual_material_name}">
<color rgba="${base_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="${base_collision_mesh}"/>
</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="${prefix}shoulder_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="${shoulder_visual_mesh}"/>
</geometry>
<material name="${shoulder_visual_material_name}">
<color rgba="${shoulder_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="${shoulder_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${shoulder_inertia_radius}" length="${shoulder_inertia_length}" mass="${shoulder_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${prefix}upper_arm_link">
<visual>
<origin xyz="0 0 ${shoulder_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<mesh filename="${upper_arm_visual_mesh}"/>
</geometry>
<material name="${upper_arm_visual_material_name}">
<color rgba="${upper_arm_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${shoulder_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<mesh filename="${upper_arm_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${upperarm_inertia_radius}" length="${upperarm_inertia_length}" mass="${upper_arm_mass}">
<origin xyz="${-0.5 * upperarm_inertia_length} 0.0 ${upper_arm_inertia_offset}" rpy="0 ${pi/2} 0" />
</xacro:cylinder_inertial>
</link>
<link name="${prefix}forearm_link">
<visual>
<origin xyz="0 0 ${elbow_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<mesh filename="${forearm_visual_mesh}"/>
</geometry>
<material name="${forearm_visual_material_name}">
<color rgba="${forearm_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${elbow_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<mesh filename="${forearm_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${forearm_inertia_radius}" length="${forearm_inertia_length}" mass="${forearm_mass}">
<origin xyz="${-0.5 * forearm_inertia_length} 0.0 ${elbow_offset}" rpy="0 ${pi/2} 0" />
</xacro:cylinder_inertial>
</link>
<link name="${prefix}wrist_1_link">
<visual>
<!-- TODO: Move this to a parameter -->
<origin xyz="0 0 ${wrist_1_visual_offset}" rpy="${pi/2} 0 0"/>
<geometry>
<mesh filename="${wrist_1_visual_mesh}"/>
</geometry>
<material name="${wrist_1_visual_material_name}">
<color rgba="${wrist_1_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${wrist_1_visual_offset}" rpy="${pi/2} 0 0"/>
<geometry>
<mesh filename="${wrist_1_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_1_inertia_radius}" length="${wrist_1_inertia_length}" mass="${wrist_1_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${prefix}wrist_2_link">
<visual>
<origin xyz="0 0 ${wrist_2_visual_offset}" rpy="0 0 0"/>
<geometry>
<mesh filename="${wrist_2_visual_mesh}"/>
</geometry>
<material name="${wrist_2_visual_material_name}">
<color rgba="${wrist_2_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${wrist_2_visual_offset}" rpy="0 0 0"/>
<geometry>
<mesh filename="${wrist_2_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_2_inertia_radius}" length="${wrist_2_inertia_length}" mass="${wrist_2_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${prefix}wrist_3_link">
<visual>
<origin xyz="0 0 ${wrist_3_visual_offset}" rpy="${pi/2} 0 0"/>
<geometry>
<mesh filename="${wrist_3_visual_mesh}"/>
</geometry>
<material name="${wrist_3_visual_material_name}">
<color rgba="${wrist_3_visual_material_color}"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${wrist_3_visual_offset}" rpy="${pi/2} 0 0"/>
<geometry>
<mesh filename="${wrist_3_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_3_inertia_radius}" length="${wrist_3_inertia_length}" mass="${wrist_3_mass}">
<origin xyz="0.0 0.0 ${-0.5 * wrist_3_inertia_length}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<!-- joints: main serial chain -->
<!-- base_link-base_link_inertia -->
<joint name="${prefix}base_link-base_link_inertia" type="fixed">
<parent link="${prefix}base_link" />
<child link="${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>
<!-- shoulder_pan_joint -->
<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link_inertia" />
<child link="${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>
<!-- shoulder_lift_joint -->
<joint name="${prefix}shoulder_lift_joint" type="revolute">
<parent link="${prefix}shoulder_link" />
<child link="${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>
<!-- elbow_joint -->
<joint name="${prefix}elbow_joint" type="revolute">
<parent link="${prefix}upper_arm_link" />
<child link="${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>
<!-- wrist_1_joint -->
<joint name="${prefix}wrist_1_joint" type="revolute">
<parent link="${prefix}forearm_link" />
<child link="${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>
<!-- wrist_2_joint -->
<joint name="${prefix}wrist_2_joint" type="revolute">
<parent link="${prefix}wrist_1_link" />
<child link="${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>
<!-- wrist_3_joint -->
<joint name="${prefix}wrist_3_joint" type="revolute">
<parent link="${prefix}wrist_2_link" />
<child link="${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" />
<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>
<dynamics damping="0" friction="0"/>
</joint>
<!-- 添加ee_link -->
<!-- ee_link -->
<joint name="${prefix}ee_fixed_joint" type="fixed">
<parent link="${prefix}wrist_3_link" />
<child link = "${prefix}ee_link" />
<!--origin xyz="0.0 ${wrist_3_length+0.155} 0.0" rpy="0.0 0.0 ${pi/2.0}" /-->
<origin xyz="0.0 0.0 ${wrist_3_y+0.142}" rpy="0 0 0" />
</joint>
<!--link name="${prefix}ee_link">
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.01 0 0"/>
</collision>
</link-->
<link name="${prefix}ee_link"/>
<!-- ROS-Industrial 'base' frame: base_link to UR 'Base' Coordinates transform -->
<link name="${prefix}base"/>
<joint name="${prefix}base_link-base_fixed_joint" type="fixed">
<!-- Note the rotation over Z of pi radians: as base_link is REP-103
aligned (ie: 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="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
<!-- ROS-Industrial 'flange' frame: attachment point for EEF models -->
<link name="${prefix}flange" />
<joint name="${prefix}wrist_3-flange" type="fixed">
<parent link="${prefix}wrist_3_link" />
<child link="${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="${prefix}tool0"/>
<joint name="${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="${prefix}flange"/>
<child link="${prefix}tool0"/>
</joint>
</xacro:macro>
</robot>
其他
ur_gripper.xacro (ur5_gripper.xacro 更方便)
包含ur_macro_gripper.xacro
xml
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg robot_model)_robot">
<!-- import main macro -->
<!-- change -->
<!-- <xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.xacro"/> -->
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro_gripper.xacro"/>
<!-- parameters -->
<xacro:arg name="joint_limit_params" default=""/>
<xacro:arg name="kinematics_params" default=""/>
<xacro:arg name="physical_params" default=""/>
<xacro:arg name="visual_params" default=""/>
<!-- legal values:
- hardware_interface/PositionJointInterface
- hardware_interface/VelocityJointInterface
- hardware_interface/EffortJointInterface
-->
<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>
<xacro:arg name="safety_limits" default="false"/>
<xacro:arg name="safety_pos_margin" default="0.15"/>
<xacro:arg name="safety_k_position" default="20"/>
<!-- arm -->
<xacro:ur_robot
prefix=""
joint_limits_parameters_file="$(arg joint_limit_params)"
kinematics_parameters_file="$(arg kinematics_params)"
physical_parameters_file="$(arg physical_params)"
visual_parameters_file="$(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)"/>
</robot>
base
base_link
base_link_inertia
flange
forearm_link
shoulder_link
tool0
upper_arm_link
wrist_1_link
wrist_2_link
wrist_3_link
夹爪功能包下载
试运行
roslaunch ur_description view_ur5_gripper.launch