Skip to content

Commit

Permalink
Added setup-gazebo action to CI
Browse files Browse the repository at this point in the history
Signed-off-by: Saurabh Kamat <[email protected]>
  • Loading branch information
sauk2 authored and srmainwaring committed Nov 4, 2024
1 parent e8e95b6 commit 4b30a3d
Showing 1 changed file with 6 additions and 7 deletions.
13 changes: 6 additions & 7 deletions .github/workflows/ubuntu-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,21 @@ jobs:
with:
submodules: 'recursive'

- name: Setup Gazebo
uses: gazebo-tooling/[email protected]
with:
required-gazebo-distributions: harmonic

- name: Install Build Dependencies
shell: bash
run: |
sudo apt update && sudo apt install --no-install-recommends -y \
lsb-release \
sudo \
software-properties-common \
wget \
make \
cmake \
ccache \
g++ \
git
sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null
sudo apt update && sudo apt install --no-install-recommends -y \
rapidjson-dev \
libopencv-dev \
Expand All @@ -41,8 +41,7 @@ jobs:
libgstreamer-plugins-base1.0-dev \
gstreamer1.0-plugins-bad \
gstreamer1.0-libav \
gstreamer1.0-gl \
gz-harmonic
gstreamer1.0-gl
# Put ccache into github cache for faster build
- name: Prepare ccache timestamp
Expand Down

0 comments on commit 4b30a3d

Please sign in to comment.