Skip to content

Commit

Permalink
Ros package and nav2 demo (#1)
Browse files Browse the repository at this point in the history
* launching the demo world
* Added new laser scan and updated launch file
* Setting up ionic_demo as its own pacakge
* Updated with gif
* Clean up and add license
* Remove unused launch file
* Add media

---------

Signed-off-by: Aaron Chong <[email protected]>
Co-authored-by: Tully Foote <[email protected]>
  • Loading branch information
aaronchongth and tfoote authored Sep 19, 2024
1 parent 6d1208c commit 64c8761
Show file tree
Hide file tree
Showing 14 changed files with 143 additions and 2 deletions.
49 changes: 47 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,57 @@ Ionic demo world and resources
Usage:

```
cd Ionic
git clone https://github.com/gazebosim/ionic_demo
cd ionic_demo/ionic_demo/worlds
gz sim -v 4 ionic.sdf
```


In Harmonic:
```
sudo apt install ros-rolling-ros-gz
```

# Running the navigation demo

![](media/ionic-nav-demo-faster-smaller.gif)

This demo requires at least [ROS 2 Jazzy](https://docs.ros.org/en/jazzy/index.html).

Create a new colcon workspace, install dependencies and build the packages,

```
mkdir -p ~/ionic_ws/src
cd ~/ionic_w/src
git clone https://github.com/gazebosim/ionic_demo
source /opt/ros/jazzy/setup.bash
rosdep install --from-paths src --ignore-src --rosdistro $ROS_DISTRO -y
cd ~/ionic_ws/
colcon build
```

Launch the demo,

```
source ~/ionic_ws/install/setup.bash
ros2 launch ionic_demo ionic_navigation_demo_launch.py headless:=0
```

On rviz, initialize the position at the origin towards the right of the map, using the `2D Pose Estimate button`.

![](media/rviz-estimate.png)

Navigation commands can now be sent via the `Nav2 Goal` button.

![](media/rviz-navigate.png)

# Troubleshooting

* If there are communication/middleware related issues while running the demos, we recommend trying again [using a different RMW implementation](https://docs.ros.org/en/jazzy/How-To-Guides/Working-with-multiple-RMW-implementations.html#specifying-rmw-implementations), for example `rmw_cyclonedds_cpp`.


# TODOs

* package descriptions
* fleet adapter
32 changes: 32 additions & 0 deletions ionic_demo/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
cmake_minimum_required(VERSION 3.8)
project(ionic_demo)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY maps DESTINATION share/${PROJECT_NAME})
install(DIRECTORY worlds DESTINATION share/${PROJECT_NAME})

ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in")

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
1 change: 1 addition & 0 deletions ionic_demo/hooks/ionic_demo.dsv.in
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/@PROJECT_NAME@/worlds/
36 changes: 36 additions & 0 deletions ionic_demo/launch/ionic_navigation_demo_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
from launch_ros.substitutions import FindPackageShare

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution, TextSubstitution


def generate_launch_description():

return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare('nav2_bringup'),
'launch',
'tb4_simulation_launch.py'
])
]),
launch_arguments={
'map': PathJoinSubstitution([
FindPackageShare('ionic_demo'),
'maps',
'ionic_demo.yaml'
]),
'world': PathJoinSubstitution([
FindPackageShare('ionic_demo'),
'worlds',
'ionic.sdf'
]),
'x_pose': '0.0',
'y_pose': '0.0',
'z_pose': '0.0'
}.items()
)
])
Binary file added ionic_demo/maps/ionic_demo.pgm
Binary file not shown.
7 changes: 7 additions & 0 deletions ionic_demo/maps/ionic_demo.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: ionic_demo.pgm
mode: trinary
resolution: 0.05
origin: [-5.57, -3.69, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
20 changes: 20 additions & 0 deletions ionic_demo/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ionic_demo</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">tullyfoote</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>nav2_bringup</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Binary file added media/ionic-nav-demo-faster-smaller.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added media/rviz-estimate.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added media/rviz-navigate.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.

0 comments on commit 64c8761

Please sign in to comment.