Skip to content

Commit

Permalink
Update Ionic tutorial with latest changes that were made in the Harmo…
Browse files Browse the repository at this point in the history
…nic directory

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey committed Aug 29, 2024
1 parent 79016ed commit 7edfaab
Show file tree
Hide file tree
Showing 13 changed files with 317 additions and 66 deletions.
2 changes: 1 addition & 1 deletion ionic/comparison.md
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ Sonar | ✓ | [Issue](https://github.com/gazebosim/gz-sensors/issues/19)
Thermal camera | ✕ | ✓
Triggered camera | ✕ | ✓
Wide-angle camera | ✓ | ✓
Wireless | ✓ | [Issue](https://github.com/gazebosim/gz-sensors/issues/28)
Wireless | ✓ | ✓ RFComms

Sensor features | Gazebo-classic | Gazebo Sim
-- | -- | --
Expand Down
11 changes: 10 additions & 1 deletion ionic/index.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -85,9 +85,18 @@ pages:
- name: spawn_urdf
title: Spawn URDF
file: spawn_urdf.md
- name: ros2_overview
title: ROS 2 integration overview
file: ros2_overview.md
- name: ros2_launch_gazebo
title: Launch Gazebo from ROS 2
file: ros2_launch_gazebo.md
- name: ros2_integration
title: ROS 2 integration via bridge
title: Use ROS 2 to interact with Gazebo
file: ros2_integration.md
- name: ros2_spawn_model
title: Use ROS 2 to spawn a Gazebo model
file: ros2_spawn_model.md
- name: ros2_interop
title: ROS 2 interoperability
file: ros2_interop.md
Expand Down
12 changes: 2 additions & 10 deletions ionic/install_osx.md
Original file line number Diff line number Diff line change
@@ -1,15 +1,7 @@
# Binary Installation on MacOS

All the Ionic binaries are available in Big Sur and Monterey using the
[homebrew package manager](https://brew.sh/).

The homebrew tool can be installed using:

```bash
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install.sh)"
```

After installing the homebrew package manager, Gazebo Ionic can be installed running:
All the Harmonic binaries are available in Monterey and Ventura using the
[Homebrew package manager](https://brew.sh/). After installing Homebrew, Gazebo Harmonic can be installed running:

```bash
brew tap osrf/simulation
Expand Down
61 changes: 21 additions & 40 deletions ionic/install_osx_src.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,33 +12,34 @@ The easiest way to get the sources of all libraries is to use

To compile all the different libraries and gz-sim in the right order
[colcon](https://colcon.readthedocs.io/en/released/) is recommended.
The colcon tool is available on all platforms using pip (or pip3, if pip fails).

## Python3 from homebrew

Tools and dependencies for Ionic can be installed using the [homebrew package manager](https://brew.sh/).
The homebrew tool can be installed by entering the following in a terminal:
Tools and dependencies for Ionic can be installed using the [Homebrew package manager](https://brew.sh/). After installing Homebrew, add the `osrf/simulation` to Homebrew tap to be able to install prebuilt dependencies.

```bash
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install.sh)"
brew tap osrf/simulation
brew update
```

Ionic is compatible with Python3; it can be installed by running the following in a terminal:
### Install compiler requirements

Building Gazebo Libraries require at least Xcode 10 on MacOS Mojave. The Xcode Command Line Tools are sufficient, and can be installed with:

```bash
brew install python3
xcode-select --install
```

## vcstool and colcon from pip
## Python 3 from Homebrew

PIP is available on all platforms:
Ionic is compatible with Python 3. Install the latest version from Homebrew:

```bash
python3 -m pip install vcstool
brew install python3
```

## vcstool and colcon from PyPI

```bash
python3 -m pip install -U colcon-common-extensions
python3 -m pip install -U colcon-common-extensions vcstool
```

## Getting the sources
Expand All @@ -55,7 +56,7 @@ All the sources of gazebo-ionic are declared in a yaml file. Download
it to the workspace:

```bash
curl -O https://raw.githubusercontent.com/gazebo-tooling/gazebodistro/master/collection-ionic.yaml
curl -OL https://raw.githubusercontent.com/gazebo-tooling/gazebodistro/master/collection-ionic.yaml
```

Use `vcstool` to automatically retrieve all the Gazebo libraries sources from
Expand All @@ -69,19 +70,10 @@ The src subdirectory should contain all the sources ready to be built.

## Install dependencies

Add `osrf/simulation` to Homebrew formulae

```bash
brew update
brew tap osrf/simulation
```

Install all dependencies:

Dependency for Ogre:

```bash
brew cask install xquartz
brew install --cask xquartz
```

General dependencies:
Expand All @@ -103,17 +95,6 @@ Unlink `qt` to avoid conflicts with other versions of qt (e.g. qt6)
brew unlink qt
```

### Install compiler requirements

The Gazebo Libraries require the Xcode 10 compiler on MacOS Mojave.

On Mac machines, gcc is acquired by installing Xcode command line tools.
The required version of Xcode for Ionic is Xcode 10.3, which can be downloaded from
[Apple Developer Site](https://developer.apple.com/download/more/).
You will need to sign in to your Apple account and download the Mojave version of
Xcode command line tools. Command line tools can also be obtained by downloading
Xcode from the Apple App Store (installing the full app may take over an hour).

## Building the Gazebo Libraries

Once the compiler and all the sources are in place it is time to compile them.
Expand Down Expand Up @@ -172,16 +153,16 @@ If there are no errors, all the binaries should be ready to use.

The workspace needs to be sourced every time a new terminal is used.

Run the following command to source the workspace in bash:
Run the following command to source the workspace in zsh (the default macOS shell):

```bash
. ~/workspace/install/setup.bash
```zsh
. ~/workspace/install/setup.zsh
```

Or in zsh:
Or if you are using bash:

```zsh
. ~/workspace/install/setup.zsh
```bash
. ~/workspace/install/setup.bash
```

You should now be able to launch gazebo:
Expand Down
2 changes: 1 addition & 1 deletion ionic/install_ubuntu.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# Binary Installation on Ubuntu

Ionic binaries are provided for Ubuntu Jammy (22.04) and Ubuntu Noble (24.04). The
Ionic binaries are provided for Ubuntu Noble (24.04). The
Ionic binaries are hosted in the packages.osrfoundation.org repository.
To install all of them, the metapackage `gz-ionic` can be installed.

Expand Down
2 changes: 1 addition & 1 deletion ionic/moving_robot.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ After the `-p` option we specify the content (value) of the message: linear spee

**Hint:** You can know what every topic option does using this command: `gz topic -h`

For more information about `Topics` and `Messages` in Gazebo check the [Transport library tutorials](https://gazebosim.org/api/transport/9.0/tutorials.html)
For more information about `Topics` and `Messages` in Gazebo check the [Transport library tutorials](https://gazebosim.org/api/transport/14/tutorials.html)

## Moving the robot using the keyboard

Expand Down
75 changes: 65 additions & 10 deletions ionic/ros2_integration.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# ROS 2 Integration
# Use ROS 2 to interact with Gazebo

In this tutorial we will learn how to Integrate ROS 2 with Gazebo. We will establish
communication between them. This can help in many aspects; we can receive data (like joint states, TFs) or commands
In this tutorial we will learn how to use ROS 2 to communicate with Gazebo.
This can help in many aspects; we can receive data (like joint states, TFs) or commands
from ROS and apply it to Gazebo and vice versa. This can also help to enable RViz to visualize a robot model
simulatenously simulated by a Gazebo world.

Expand All @@ -11,13 +11,7 @@ simulatenously simulated by a Gazebo world.

Example uses of the bridge can be found in [`ros_gz_sim_demos`](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_sim_demos), including demo launch files with bridging of all major actuation and sensor types.

## Requirements

Please follow the [Install Gazebo and ROS document](ros_installation)
before starting this tutorial. A working installation of ROS 2 and Gazebo is
required to go further.

## Bidirectional communication
## Launching the bridge manually

We can initialize a bidirectional bridge so we can have ROS as the publisher and Gazebo as the subscriber or vice versa. The syntax is `/TOPIC@ROS_MSG@GZ_MSG`, such that `TOPIC` is the Gazebo internal topic, `ROS_MSG` is the ROS message type for this topic, and `GZ_MSG` is the Gazebo message type.

Expand Down Expand Up @@ -48,6 +42,67 @@ It is also possible to use ROS Launch with the `ros_gz_bridge` and represent the
direction: GZ_TO_ROS # BIDIRECTIONAL or ROS_TO_GZ
```

The configuration file is a YAML file that contains the mapping between the ROS
and Gazebo topics to be bridged. For each pair of topics to be bridged, the
following parameters are accepted:

* `ros_topic_name`: The topic name on the ROS side.
* `gz_topic_name`: The corresponding topic name on the Gazebo side.
* `ros_type_name`: The type of this ROS topic.
* `gz_type_name`: The type of this Gazebo topic.
* `subscriber_queue`: The size of the ROS subscriber queue.
* `publisher_queue`: The size of the ROS publisher queue.
* `lazy`: Whether there's a lazy subscriber or not. If there's no real
subscribers the bridge won't create the internal subscribers either. This should
speedup performance.
* `direction`: It's possible to specify `GZ_TO_ROS`, `ROS_TO_GZ` and
`BIDIRECTIONAL`.

See [this example](https://github.com/gazebosim/ros_gz/blob/ros2/ros_gz_bridge/test/config/full.yaml)
for a valid configuration file.

## Launching the bridge using the launch files included in `ros_gz_bridge` package.

The package `ros_gz_bridge` contains a launch file named
`ros_gz_bridge.launch.py`. You can use it to start a ROS 2 and Gazebo bridge.
Here's an example:

```bash
ros2 launch ros_gz_bridge ros_gz_bridge.launch.py name:=ros_gz_bridge config_file:=<path_to_your_YAML_file>
```

## Launching the bridge from a custom launch file.

It's also possible to trigger the bridge from your custom launch file. For that
purpose we have created the `<ros_gz_bridge/>` tag that can be used from you
XML or YAML launch file. In this case, the arguments are passed as attributes
within this tag. Here's an example:

```xml
<launch>
<arg name="name" default="ros_gz_bridge" />
<arg name="config_file" default="" />
<arg name="container_name" default="ros_gz_container" />
<arg name="namespace" default="" />
<arg name="use_composition" default="True" />
<arg name="use_respawn" default="False" />
<arg name="log_level" default="info" />
<ros_gz_bridge
name="$(var name)"
config_file="$(var config_file)"
container_name="$(var container_name)"
namespace="$(var namespace)"
use_composition="$(var use_composition)"
use_respawn="$(var use_respawn)"
log_level="$(var log_level)">
</ros_gz_bridge>
</launch>
```

In this case the `<ros_gz_bridge>` parameters are read from the command line.
That's an option but not strictly necessary as you could decide to hardcode some
of the values.

## Publish key strokes to ROS

Let's send messages to ROS using the `Key Publisher` an Gazebo plugin.
Expand Down
102 changes: 102 additions & 0 deletions ionic/ros2_launch_gazebo.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
# Launch Gazebo from ROS 2

Gazebo can be launched from a ROS 2 launch system in multiple ways:

## Using the launch files included in
[ros_gz_sim](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_sim).

The package `ros_gz_sim` contains two launch files named `gz_server.launch.py`
and `gz_sim.launch.py`. You can use them to start Gazebo server or Gazebo (server and GUI)
respectively.

```bash
ros2 launch ros_gz_sim gz_sim.launch.py gz_args:=empty.sdf
```

Or you can just start the server:

```bash
ros2 launch ros_gz_sim gz_server.launch.py world_sdf_file:=empty.sdf
```

Consult the argument block of each launch file
[here](https://github.com/gazebosim/ros_gz/blob/ros2/ros_gz_sim/launch/gz_sim.launch.py.in#L75-L96)
and [here](https://github.com/gazebosim/ros_gz/blob/ros2/ros_gz_sim/launch/gz_server.launch.py#L27-L38)
to learn about the different parameters that are accepted by each launch file.

## Using a custom launch file.

### XML
It's also possible to start Gazebo from your custom launch file. For that
purpose we have created the custom `<gz_server/>` tag that can be used from your
XML launch file. In this case, the arguments are passed as attributes
within this tag. Here's an example for launching Gazebo server:

```xml
<launch>
<arg name="world_sdf_file" default="empty.sdf" />
<arg name="world_sdf_string" default="" />
<arg name="container_name" default="ros_gz_container" />
<arg name="use_composition" default="True" />
<gz_server
world_sdf_file="$(var world_sdf_file)"
world_sdf_string="$(var world_sdf_string)"
container_name="$(var container_name)"
use_composition="$(var use_composition)">
</gz_server>
</launch>
```

In this case the `<gz_server>` parameters are read from the command line. That's
an option but not strictly necessary as you could decide to hardcode some of the
values.

### Python
Python launch files provide more low-level customization and logic compared to XML launch files.
In the following example, the user can specify a world argument to launch an environment for
the Moon, Mars, or Enceladus. It additionally sets the resource path environment variable and
sets up empty arrays for topics to be bridged and remapped from Gazebo to ROS 2:
```python
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument, SetEnvironmentVariable,
IncludeLaunchDescription, SetLaunchConfiguration)
from launch.substitutions import PathJoinSubstitution, LaunchConfiguration, TextSubstitution
from launch_ros.actions import Node
from launch.launch_description_sources import PythonLaunchDescriptionSource


def generate_launch_description():
pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim')
pkg_spaceros_gz_sim = get_package_share_directory('spaceros_gz_sim')
gz_launch_path = PathJoinSubstitution([pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py'])
gz_model_path = PathJoinSubstitution([pkg_spaceros_gz_sim, 'models'])

return LaunchDescription([
DeclareLaunchArgument(
'world',
default_value='moon',
choices=['moon', 'mars', 'enceladus'],
description='World to load into Gazebo'
),
SetLaunchConfiguration(name='world_file',
value=[LaunchConfiguration('world'),
TextSubstitution(text='.sdf')]),
SetEnvironmentVariable('GZ_SIM_RESOURCE_PATH', gz_model_path),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(gz_launch_path),
launch_arguments={
'gz_args': [PathJoinSubstitution([pkg_spaceros_gz_sim, 'worlds',
LaunchConfiguration('world_file')])],
'on_exit_shutdown': 'True'
}.items(),
),
Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[],
remappings=[],
output='screen'
),
])
```
Loading

0 comments on commit 7edfaab

Please sign in to comment.