Skip to content

Commit

Permalink
Merge pull request #562 from fmauch/convenience_macros
Browse files Browse the repository at this point in the history
Add convenience macros for description files
  • Loading branch information
gavanderhoorn authored Sep 28, 2021
2 parents d111eb0 + dbc9e15 commit 81a542b
Show file tree
Hide file tree
Showing 17 changed files with 485 additions and 2 deletions.
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur10_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR10.
This file can be used when composing a more complex scene with one or more
UR10 robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur10_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur10/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur10/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur10/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur10/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur10e_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR10e.
This file can be used when composing a more complex scene with one or more
UR10e robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur10e_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur10e/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur10e/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur10e/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur10e/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur16e_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR16e.
This file can be used when composing a more complex scene with one or more
UR16e robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur16e_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur16e/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur16e/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur16e/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur16e/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur3_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR3.
This file can be used when composing a more complex scene with one or more
UR3 robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur3_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur3/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur3/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur3/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur3/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur3e_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR3e.
This file can be used when composing a more complex scene with one or more
UR3e robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur3e_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur3e/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur3e/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur3e/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur3e/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur5_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR5.
This file can be used when composing a more complex scene with one or more
UR5 robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<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"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
47 changes: 47 additions & 0 deletions ur_description/urdf/inc/ur5e_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Convenience wrapper for the 'ur_robot' macro which provides default values
for the various "parameters files" parameters for a UR5e.
This file can be used when composing a more complex scene with one or more
UR5e robots.
While the generic 'ur_robot' macro could also be used, it would require
the user to provide values for all parameters, as that macro does not set
any model-specific defaults (not even for the generic parameters, such as
the visual and physical parameters and joint limits).
Refer to the main 'ur_macro.xacro' in this package for information about
use, contributors and limitations.
NOTE: users will most likely want to override *at least* the
'kinematics_parameters_file' parameter. Otherwise, a default kinematic
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur5e_robot" params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur5e/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur5e/default_kinematics.yaml'
physical_parameters_file:='$(find ur_description)/config/ur5e/physical_parameters.yaml'
visual_parameters_file:='$(find ur_description)/config/ur5e/visual_parameters.yaml'
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.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}"
/>
</xacro:macro>
</robot>
File renamed without changes.
2 changes: 1 addition & 1 deletion ur_description/urdf/ur.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur">

<!-- import main macro -->
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.xacro"/>

<!-- parameters -->
<xacro:arg name="joint_limit_params" default=""/>
Expand Down
22 changes: 22 additions & 0 deletions ur_description/urdf/ur10.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur10_robot">
<!--
This is a convenience top-level xacro which loads the macro for the UR10
which defines the default values for the various "parameters files"
parameters for a UR10.
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/ur10_macro.xacro' and override the defaults
for the arguments to that macro.
Refer to 'inc/ur_macro.xacro' for more information.
-->
<xacro:include filename="$(find ur_description)/urdf/inc/ur10_macro.xacro"/>
<xacro:ur10_robot prefix="" />
</robot>
22 changes: 22 additions & 0 deletions ur_description/urdf/ur10e.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur10e_robot">
<!--
This is a convenience top-level xacro which loads the macro for the UR10e
which defines the default values for the various "parameters files"
parameters for a UR10e.
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/ur10e_macro.xacro' and override the defaults
for the arguments to that macro.
Refer to 'inc/ur_macro.xacro' for more information.
-->
<xacro:include filename="$(find ur_description)/urdf/inc/ur10e_macro.xacro"/>
<xacro:ur10e_robot prefix="" />
</robot>
Loading

0 comments on commit 81a542b

Please sign in to comment.