Skip to content

Commit

Permalink
Remove Bionic from future releases (Garden+) (#583)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Steve Peters <[email protected]>
  • Loading branch information
chapulina and scpeters authored Mar 15, 2022
1 parent 8cc48ac commit 23955a9
Show file tree
Hide file tree
Showing 6 changed files with 11 additions and 37 deletions.
17 changes: 5 additions & 12 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,6 @@ name: Ubuntu CI
on: [push, pull_request]

jobs:
bionic-ci:
runs-on: ubuntu-latest
name: Ubuntu Bionic CI
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-enabled: true
doxygen-enabled: true
focal-ci:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
Expand All @@ -24,3 +12,8 @@ jobs:
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@focal
with:
codecov-enabled: true
cppcheck-enabled: true
cpplint-enabled: true
doxygen-enabled: true
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/default)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-main-bionic-amd64)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-main-focal-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-main-focal-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_rendering-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_rendering-ci-win/)

Expand Down
4 changes: 2 additions & 2 deletions include/ignition/rendering/HeightmapDescriptor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -191,15 +191,15 @@ inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
public: ignition::math::Vector3d Size() const;

/// \brief Set the heightmap's final size in world units. Defaults to 1x1x1.
/// \return The heightmap's size factor.
/// \param[in] _size The heightmap's size factor.
public: void SetSize(const ignition::math::Vector3d &_size);

/// \brief Get the heightmap's position offset.
/// \return The heightmap's position offset.
public: ignition::math::Vector3d Position() const;

/// \brief Set the heightmap's position offset.
/// \return The heightmap's position offset.
/// \param[in] _position The heightmap's position offset.
public: void SetPosition(const ignition::math::Vector3d &_position);

/// \brief Get whether the heightmap uses terrain paging.
Expand Down
4 changes: 2 additions & 2 deletions include/ignition/rendering/Mesh.hh
Original file line number Diff line number Diff line change
Expand Up @@ -121,8 +121,8 @@ namespace ignition
public: virtual SubMeshPtr SubMeshByIndex(
unsigned int _index) const = 0;

/// \brief Set the mesh's mesh descriptor
/// \return The mesh's mesh descriptor
/// \brief Set the mesh's descriptor
/// \param[in] _desc The new mesh descriptor
public: virtual void SetDescriptor(const MeshDescriptor &_desc) = 0;

/// \brief Get the mesh's mesh descriptor
Expand Down
17 changes: 0 additions & 17 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -570,23 +570,6 @@ void CameraTest::ShaderSelection(const std::string &_renderEngine)
<< _renderEngine << std::endl;
return;
}
else if (_renderEngine == "ogre2")
{
// \todo(anyone) test fails on github action (Bionic) but pass on other
// builds. Need to investigate further.
// Github action sets the MESA_GL_VERSION_OVERRIDE variable
// so check for this variable and disable test if it is set.
#ifdef __linux__
std::string value;
bool result = common::env("MESA_GL_VERSION_OVERRIDE", value, true);
if (result && value == "3.3")
{
igndbg << "Test is run on machine with software rendering or mesa driver "
<< "Skipping test. " << std::endl;
return;
}
#endif
}

// This test checks that custom shaders are being rendering correctly in
// camera view. It also verifies that visual selection is working and the
Expand Down
4 changes: 1 addition & 3 deletions tutorials/02_install.md
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ Be sure to replace `<#>` with a number value, such as `1` or `2`, depending on w

### Prerequisites

Ubuntu Bionic 18.04 or above:
Ubuntu Focal 20.04 or above:

Install dependencies:
```
Expand All @@ -49,7 +49,6 @@ sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `ls
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt update
sudo apt install -y \
g++-8 \
cmake \
pkg-config \
git \
Expand All @@ -62,7 +61,6 @@ sudo apt install -y \
libignition-math7-dev \
libignition-common5-dev \
libignition-plugin-dev
sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-8 800 --slave /usr/bin/g++ g++ /usr/bin/g++-8 --slave /usr/bin/gcov gcov /usr/bin/gcov-8
```

### Supported Rendering Engines
Expand Down

0 comments on commit 23955a9

Please sign in to comment.