Skip to content

Commit

Permalink
Fix/exercise 3.1 ur repository update (#357)
Browse files Browse the repository at this point in the history
* updated workcell.urdf.xacro to use recent universal repositories

* updated instructions for exercise 3.1

* simplify ex3.1 xacro and launch

Co-authored-by: Jeremy Zoss <jzoss@swri.org>
  • Loading branch information
jrgnicho and JeremyZoss committed Oct 6, 2021
1 parent 060b782 commit 2b4d33b
Show file tree
Hide file tree
Showing 3 changed files with 78 additions and 99 deletions.
31 changes: 4 additions & 27 deletions exercises/3.1/ros2/src/myworkcell_support/launch/urdf.launch.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
import os
import yaml
import launch
import launch_ros
import xacro

from ament_index_python import get_package_share_directory

def get_package_file(package, file_path):
Expand All @@ -10,41 +11,17 @@ def get_package_file(package, file_path):
absolute_file_path = os.path.join(package_path, file_path)
return absolute_file_path

def load_file(file_path):
"""Load the contents of a file into a string"""
try:
with open(file_path, 'r') as file:
return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None

def load_yaml(file_path):
"""Load a yaml file into a dictionary"""
try:
with open(file_path, 'r') as file:
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None

def run_xacro(xacro_file):
"""Run xacro and output a file in the same directory with the same name, w/o a .xacro suffix"""
urdf_file, ext = os.path.splitext(xacro_file)
if ext != '.xacro':
raise RuntimeError(f'Input file to xacro must have a .xacro extension, got {xacro_file}')
os.system(f'xacro {xacro_file} -o {urdf_file}')
return urdf_file

def generate_launch_description():
xacro_file = get_package_file('myworkcell_support', 'urdf/workcell.urdf.xacro')
urdf_file = run_xacro(xacro_file)
urdf = xacro.process_file(xacro_file).toprettyxml(indent=' ')

return launch.LaunchDescription([
launch_ros.actions.Node(
name='robot_state_publisher',
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
arguments=[urdf_file],
parameters=[{'robot_description': urdf}],
),
launch_ros.actions.Node(
name='joint_state_publisher_gui',
Expand Down
16 changes: 14 additions & 2 deletions exercises/3.1/ros2/src/myworkcell_support/urdf/workcell.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,19 @@
<?xml version="1.0" ?>
<robot name="myworkcell" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />
<xacro:ur5_robot prefix="" joint_limited="true"/>
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>

<!-- ur arm instantiation -->
<xacro:arg name="ur_type" default="ur5"/>
<xacro:arg name="use_fake_hardware" default="true"/>
<xacro:arg name="fake_sensor_commands" default="true"/>
<xacro:ur_robot
prefix=""
joint_limits_parameters_file="$(find ur_description)/config/$(arg ur_type)/joint_limits.yaml"
kinematics_parameters_file="$(find ur_description)/config/$(arg ur_type)/default_kinematics.yaml"
physical_parameters_file="$(find ur_description)/config/$(arg ur_type)/physical_parameters.yaml"
visual_parameters_file="$(find ur_description)/config/$(arg ur_type)/visual_parameters.yaml"
use_fake_hardware="$(arg use_fake_hardware)"
fake_sensor_commands="$(arg fake_sensor_commands)"/>

<link name="world"/>

Expand Down
130 changes: 60 additions & 70 deletions gh_pages/_source/session3/ros2/1-Workcell-XACRO.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,30 +29,42 @@ Specifically, you will need to:

1. Bring in the `ur_description` package into your ROS environment. For ROS2, it currently must be cloned and built from source

1. Clone the repository from [GitHub](https://github.com/jdlangs/universal_robot) into your workspace:
1. Search the [UniversalRobots GitHub repositories](https://github.com/UniversalRobots) for the `ur_description` package, to find that it is available in the `Universal_Robots_ROS2_Driver` repository. Clone the repository and a minimal set of build dependencies into your workspace:

```
cd ~/ros2_ws/src
git clone -b ros2 https://github.com/jdlangs/universal_robot.git
git clone -b foxy https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git
git clone -b master https://github.com/UniversalRobots/Universal_Robots_Client_Library.git
git clone -b ros2 https://github.com/destogl/ur_msgs.git
cd ~/ros2_ws
colcon build
source ~/ros2_ws/install/setup.bash
```

>It’s not uncommon for description packages to put each “module”, “part”, or “assembly” into its own file. In many cases, a package will also define extra files that define a complete cell with the given part so that we can easily visually inspect the result. The UR package defines such a file for the UR5 ([ur5_robot.urdf.xacro](https://github.com/ros-industrial/universal_robot/blob/indigo-devel/ur_description/urdf/ur5_robot.urdf.xacro)): It’s a great example for this module.
> Inspect the UR-provided xacro files at `~/ros2_ws/src/Universal_Robots_ROS2_Driver/ur_description/urdf`. In particular, compare `ur_macro.xacro` with `ur.urdf.xacro`. This is a common design pattern: one xacro file defines a macro that can be called to generate a component of the workcell, while a different xacro file _calls_ that macro to actually create the final URDF model.
1. Locate the xacro file that implements the UR5 macro and include it in your newly renamed `workcell.xacro` file. Add this include line near the top of your `workcell.xacro` file, beneath the `<robot>` tag:
1. Locate the xacro file that defines the "ur_robot" macro and include it in your newly renamed `workcell.xacro` file. Add this include line near the top of your `workcell.xacro` file, beneath the `<robot>` tag:

``` xml
<xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
```

>If you explore the UR5 definition file, or just about any other file that defines a Xacro macro, you’ll find a lot of uses of `${prefix}` in element names. Xacro evaluates anything inside a “${}” at run-time. It can do basic math, and it can look up variables that come to it via properties (ala-global variables) or macro parameters. Most macros will take a “prefix” parameter to allow a user to create multiple instances of said macro. It’s the mechanism by which we can make the eventual URDF element names unique, otherwise we’d get duplicate link names and URDF would complain.
>If you explore the ur_macro definition file, or just about any other file that defines a Xacro macro, you’ll find a lot of uses of `${prefix}` in element names. Xacro evaluates anything inside a “${}” at run-time. It can do basic math, and it can look up variables that come to it via properties (ala-global variables) or macro parameters. Most macros will take a “prefix” parameter to allow a user to create multiple instances of said macro. It’s the mechanism by which we can make the eventual URDF element names unique, otherwise we’d get duplicate link names and URDF would complain.
1. Including the `ur5.urdf.xacro` file does not actually create a UR5 robot in our URDF model. It defines a macro, but we still need to call the macro to create the robot links and joints. _Note the use of the `prefix` tag, as discussed above._
1. Including the `ur_macro.xacro` file does not actually create a UR5 robot in our URDF model. It defines a macro, but we still need to call the macro to create the robot links and joints. _Note the use of the `prefix` tag, as discussed above. An additional "ur_type" argument tells the macro which model of UR-robot to generate._

``` xml
<xacro:ur5_robot prefix="" joint_limited="true"/>
<!-- ur arm instantiation -->
<xacro:arg name="ur_type" default="ur5"/>
<xacro:arg name="use_fake_hardware" default="true"/>
<xacro:arg name="fake_sensor_commands" default="true"/>
<xacro:ur_robot
prefix=""
joint_limits_parameters_file="$(find ur_description)/config/$(arg ur_type)/joint_limits.yaml"
kinematics_parameters_file="$(find ur_description)/config/$(arg ur_type)/default_kinematics.yaml"
physical_parameters_file="$(find ur_description)/config/$(arg ur_type)/physical_parameters.yaml"
visual_parameters_file="$(find ur_description)/config/$(arg ur_type)/visual_parameters.yaml"
use_fake_hardware="$(arg use_fake_hardware)"
fake_sensor_commands="$(arg fake_sensor_commands)"/>
```

>Macros in Xacro are just fancy wrappers around copy-paste. You make a macro and it gets turned into a chunk of links and joints. You still have to connect the rest of your world to that macro’s results. This means you have to look at the macro and see what the base link is and what the end link is. Hopefully your macro follows a standard, like the ROS-Industrial one, that says that base links are named “base_link” and the last link is called “tool0”.
Expand All @@ -70,67 +82,45 @@ Specifically, you will need to:
1. Create a new `urdf.launch.py` file (in the `myworkcell_support` package) to load the URDF model and (optionally) display it in rviz. The launch file starts with several utility functions that are useful for assisting the launch process. This particular file uses `get_package_file` to get the path of the `workcell.urdf.xacro` file you've created, and `run_xacro` to send it to the `xacro` program, generating a plain URDF file. This URDF file is then passed to a `robot_state_publisher` node as an argument just as was done manually in the previous exercise.

```py
import os
import yaml
import launch
import launch_ros
from ament_index_python import get_package_share_directory

def get_package_file(package, file_path):
"""Get the location of a file installed in an ament package"""
package_path = get_package_share_directory(package)
absolute_file_path = os.path.join(package_path, file_path)
return absolute_file_path

def load_file(file_path):
"""Load the contents of a file into a string"""
try:
with open(file_path, 'r') as file:
return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None

def load_yaml(file_path):
"""Load a yaml file into a dictionary"""
try:
with open(file_path, 'r') as file:
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None

def run_xacro(xacro_file):
"""Run xacro and output a file in the same directory with the same name, w/o a .xacro suffix"""
urdf_file, ext = os.path.splitext(xacro_file)
if ext != '.xacro':
raise RuntimeError(f'Input file to xacro must have a .xacro extension, got {xacro_file}')
os.system(f'xacro {xacro_file} -o {urdf_file}')
return urdf_file

def generate_launch_description():
xacro_file = get_package_file('myworkcell_support', 'urdf/workcell.urdf.xacro')
urdf_file = run_xacro(xacro_file)

return launch.LaunchDescription([
launch_ros.actions.Node(
node_name='robot_state_publisher',
package='robot_state_publisher',
node_executable='robot_state_publisher',
output='screen',
arguments=[urdf_file],
),
launch_ros.actions.Node(
node_name='joint_state_publisher_gui',
package='joint_state_publisher_gui',
node_executable='joint_state_publisher_gui',
output='screen',
),
launch_ros.actions.Node(
node_name='rviz',
package='rviz2',
node_executable='rviz2',
output='screen',
)
])
import os
import launch
import launch_ros
import xacro

from ament_index_python import get_package_share_directory

def get_package_file(package, file_path):
"""Get the location of a file installed in an ament package"""
package_path = get_package_share_directory(package)
absolute_file_path = os.path.join(package_path, file_path)
return absolute_file_path

def generate_launch_description():
xacro_file = get_package_file('myworkcell_support', 'urdf/workcell.urdf.xacro')
urdf = xacro.process_file(xacro_file).toprettyxml(indent=' ')

return launch.LaunchDescription([
launch_ros.actions.Node(
name='robot_state_publisher',
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{'robot_description': urdf}],
),
launch_ros.actions.Node(
name='joint_state_publisher_gui',
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
output='screen',
),
launch_ros.actions.Node(
name='rviz',
package='rviz2',
executable='rviz2',
output='screen',
)
])

```

1. Add the urdf folder to the installation rule in your `CMakeLists.txt` so it gets installed where the launch file expects it to be.
Expand Down

0 comments on commit 2b4d33b

Please sign in to comment.