Skip to content

Commit

Permalink
Simplified ur_description and ur_gazebo by using model argument
Browse files Browse the repository at this point in the history
Model specific xacro and launch files replaced by generic ones.
Default arguments and parameters only defined once in lowest level files by replacing empty strings.
Omit properties same as default.
Still all properties can be overridden in upper level files.
Less redefining of arguments and parameters by pass_all_args in launch and using upper level parameters in xacro files.
transmission_hw_interface only needs to contain parts of position, velocity or effort in lower or upper case.
Names of properties, files and directory structure simplified.
Macro for individual transmission and fixed joint added.
Fractions and squares cylinder_inertial macro.
initial_joint_positions, full world_pose and unpause argument at spawning added to control.launch, as by moveit_setup_assistant.
robot_model changed to model for easier calling for example: roslaunch ur_gazebo bringup.launch model:=ur5
  • Loading branch information
BobbyCephy committed Nov 16, 2022
1 parent 40e21b1 commit a053318
Show file tree
Hide file tree
Showing 98 changed files with 537 additions and 1,950 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ Don't forget to source the correct setup shell files and use a new terminal for

To bring up the simulated robot in Gazebo, run:

```roslaunch ur_gazebo ur5_bringup.launch```
```roslaunch ur_gazebo bringup.launch model:=ur5```


___MoveIt! with a simulated robot___
Expand Down
4 changes: 2 additions & 2 deletions ur10_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur10.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur10
SRDF:
relative_path: config/ur10.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur10_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur10.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur10"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur10_moveit_config)/config/ur10.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur10e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur10e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur10e
SRDF:
relative_path: config/ur10e.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur10e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur10e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur10e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur10e_moveit_config)/config/ur10e.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur16e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur16e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur16e
SRDF:
relative_path: config/ur16e.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur16e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur16e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur16e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur16e_moveit_config)/config/ur16e.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur3_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur3.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur3
SRDF:
relative_path: config/ur3.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur3_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur3.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur3"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur3_moveit_config)/config/ur3.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur3e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur3e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur3e
SRDF:
relative_path: config/ur3e.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur3e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur3e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur3e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur3e_moveit_config)/config/ur3e.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur5_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur5.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur5
SRDF:
relative_path: config/ur5.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur5_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur5.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur3"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur5_moveit_config)/config/ur5.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur5e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur5e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur5e
SRDF:
relative_path: config/ur5e.srdf
CONFIG:
Expand Down
2 changes: 1 addition & 1 deletion ur5e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur5e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur5e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur5e_moveit_config)/config/ur5e.srdf" />
Expand Down
14 changes: 4 additions & 10 deletions ur_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,20 +1,14 @@
cmake_minimum_required(VERSION 3.0.2)
project(ur_description)

find_package(catkin REQUIRED)

catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(tests/roslaunch_test_ur10e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur10.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur16e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur3e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur3.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur5e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur5.xml)
foreach(model ur3 ur3e ur5 ur5e ur10 ur10e ur16e)
roslaunch_add_file_check(launch/test.launch model=${model})
endforeach()
endif()

install(DIRECTORY cfg config launch meshes urdf
install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
47 changes: 47 additions & 0 deletions ur_description/launch/load.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<launch>
<arg name="model" doc="Type/series of used UR robot (ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e)"/>
<arg name="prefix" default="" doc="Prefix of robot name"/>

<!-- Parameter files -->
<arg name="joint_limit_params" default="" doc="YAML file containing the joint limit values"/>
<arg name="kinematics_params" default="" 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" default="" doc="YAML file containing the phycical parameters of the robots"/>
<arg name="visual_params" default="" doc="YAML file containing the visual model of the robots"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="" doc="The hardware_interface to expose for each joint in the simulated robot: position, velocity or effort"/>
<arg name="safety_limits" default="" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="" doc="The lower/upper limits in the safety controller"/>
<arg name="safety_k_position" default="" doc="Used to set k position in the safety controller"/>

<!-- Load the top-level (ie: stand-alone and complete) xacro for the UR
variant defined by the set of yaml parameter files (so to load a UR5
onto the ROS parameter server, provide paths to the .yaml files which
contain the limits, kinematics, physical and visual parameters which
together describe a UR5 robot.
NOTE: users will typically want to use use one of the other .launch files
in this directory (ie: 'load.launch'), as those already contain
appropriate default values for the required arguments for the various
supported robots.
NOTE2: if you have a custom robot configuration, or your robot is
integrated into a work cell, do NOT change this file or add all of the
work cell objects to the ur.xacro file. Create a new top-level xacro and
include the macro.xacro file into it. Then write a new .launch file
to load it onto the parameter server.
-->
<param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur.xacro'
model:=$(arg model)
prefix:=$(arg prefix)
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>
44 changes: 0 additions & 44 deletions ur_description/launch/load_ur.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur10.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur10e.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur16e.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur3.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur3e.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur5.launch

This file was deleted.

18 changes: 0 additions & 18 deletions ur_description/launch/load_ur5e.launch

This file was deleted.

Loading

0 comments on commit a053318

Please sign in to comment.