Skip to content

Commit

Permalink
Fix CI for Rolling / Ubuntu Noble (#2793)
Browse files Browse the repository at this point in the history
* docker.yaml: Enable caching
* [TEMP] moveit2_rolling.repos: add not yet released packages
* Skip broken ci-testing image: osrf/ros2:testing doesn't contain /opt/ros!
* use boost::timer::progress_display if available
   check for header to stay compatible with ubuntu 20.04.
   Support boost >= 1.83

   Slightly ugly due to the double alias, but boost::timer was a class
   before 1.72, so using `boost::timer::progress_display` in the code
   breaks with older versions.
* cherry-pick of #3547 from MoveIt1
* Tag ci image as ci-testing as well

---------

Co-authored-by: Michael Görner <me@v4hn.de>
Co-authored-by: Sebastian Jahr <sebastian.jahr@picknik.ai>
Co-authored-by: Henning Kayser <henningkayser@picknik.ai>
  • Loading branch information
4 people authored May 23, 2024
1 parent c72ac1b commit bee0a29
Show file tree
Hide file tree
Showing 4 changed files with 55 additions and 49 deletions.
2 changes: 1 addition & 1 deletion .docker/source/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
# Downloads the moveit source code and install remaining debian dependencies

ARG ROS_DISTRO=rolling
FROM moveit/moveit2:${ROS_DISTRO}-ci-testing
FROM moveit/moveit2:${ROS_DISTRO}-ci
LABEL maintainer Robert Haschke rhaschke@techfak.uni-bielefeld.de

# Export ROS_UNDERLAY for downstream docker containers
Expand Down
76 changes: 31 additions & 45 deletions .github/workflows/docker.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,16 @@ jobs:
PUSH: ${{ (github.event_name != 'pull_request') && (github.repository == 'ros-planning/moveit2') }}

steps:
- uses: rhaschke/docker-run-action@v5
name: Check for apt updates
continue-on-error: true
id: apt
with:
image: ${{ env.IMAGE }}
run: |
apt-get update
have_updates=$(apt-get --simulate upgrade | grep -q "^0 upgraded, 0 newly installed, 0 to remove and 0 not upgraded.$" && echo false || echo true)
echo "no_cache=$have_updates" >> "$GITHUB_OUTPUT"
- name: Set up Docker Buildx
uses: docker/setup-buildx-action@v3
- name: Login to Github Container Registry
Expand All @@ -51,7 +61,9 @@ jobs:
file: .docker/${{ github.job }}/Dockerfile
build-args: ROS_DISTRO=${{ matrix.ROS_DISTRO }}
push: ${{ env.PUSH }}
no-cache: true
no-cache: ${{ steps.apt.outputs.no_cache || github.event_name == 'workflow_dispatch' }}
cache-from: type=registry,ref=${{ env.GH_IMAGE }}
cache-to: type=inline
tags: |
${{ env.GH_IMAGE }}
${{ env.DH_IMAGE }}
Expand All @@ -71,47 +83,16 @@ jobs:
PUSH: ${{ (github.event_name != 'pull_request') && (github.repository == 'ros-planning/moveit2') }}

steps:
- name: Set up Docker Buildx
uses: docker/setup-buildx-action@v3
- name: Login to Github Container Registry
if: env.PUSH == 'true'
uses: docker/login-action@v3
with:
registry: ghcr.io
username: ${{ github.repository_owner }}
password: ${{ secrets.GITHUB_TOKEN }}
- name: Login to DockerHub
if: env.PUSH == 'true'
uses: docker/login-action@v3
with:
username: ${{ secrets.DOCKERHUB_USERNAME }}
password: ${{ secrets.DOCKERHUB_TOKEN }}
- name: Build and Push
uses: docker/build-push-action@v5
- uses: rhaschke/docker-run-action@v5
name: Check for apt updates
continue-on-error: true
id: apt
with:
file: .docker/${{ github.job }}/Dockerfile
build-args: ROS_DISTRO=${{ matrix.ROS_DISTRO }}
push: ${{ env.PUSH }}
no-cache: true
tags: |
${{ env.GH_IMAGE }}
${{ env.DH_IMAGE }}
ci-testing:
strategy:
fail-fast: false
matrix:
ROS_DISTRO: [rolling]
runs-on: ubuntu-latest
permissions:
packages: write
contents: read
env:
GH_IMAGE: ghcr.io/ros-planning/moveit2:${{ matrix.ROS_DISTRO }}-${{ github.job }}
DH_IMAGE: moveit/moveit2:${{ matrix.ROS_DISTRO }}-${{ github.job }}
PUSH: ${{ (github.event_name != 'pull_request') && (github.repository == 'ros-planning/moveit2') }}

steps:
image: ${{ env.IMAGE }}
run: |
apt-get update
have_updates=$(apt-get --simulate upgrade | grep -q "^0 upgraded, 0 newly installed, 0 to remove and 0 not upgraded.$" && echo false || echo true)
echo "no_cache=$have_updates" >> "$GITHUB_OUTPUT"
- name: Set up Docker Buildx
uses: docker/setup-buildx-action@v3
- name: Login to Github Container Registry
Expand All @@ -131,15 +112,19 @@ jobs:
uses: docker/build-push-action@v5
with:
file: .docker/${{ github.job }}/Dockerfile
build-args: OUR_ROS_DISTRO=${{ matrix.ROS_DISTRO }}
build-args: ROS_DISTRO=${{ matrix.ROS_DISTRO }}
push: ${{ env.PUSH }}
no-cache: true
no-cache: ${{ steps.apt.outputs.no_cache || github.event_name == 'workflow_dispatch' }}
cache-from: type=registry,ref=${{ env.GH_IMAGE }}
cache-to: type=inline
tags: |
${{ env.GH_IMAGE }}
${{ env.GH_IMAGE }}-testing
${{ env.DH_IMAGE }}
${{ env.DH_IMAGE }}-testing
source:
needs: ci-testing
needs: ci
strategy:
fail-fast: false
matrix:
Expand Down Expand Up @@ -179,7 +164,8 @@ jobs:
file: .docker/${{ github.job }}/Dockerfile
build-args: ROS_DISTRO=${{ matrix.ROS_DISTRO }}
push: ${{ env.PUSH }}
no-cache: true
cache-from: type=registry,ref=${{ env.GH_IMAGE }}
cache-to: type=inline
tags: |
${{ env.GH_IMAGE }}
${{ env.DH_IMAGE }}
Expand Down
9 changes: 9 additions & 0 deletions moveit2_rolling.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
repositories:
octomap:
type: git
url: https://github.com/octomap/octomap.git
version: devel
geometric_shapes:
type: git
url: https://github.com/ros-planning/geometric_shapes.git
version: ros2
17 changes: 14 additions & 3 deletions moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,21 @@
#include <tf2_eigen/tf2_eigen.hpp>
#include <moveit/utils/logger.hpp>

#define BOOST_ALLOW_DEPRECATED_HEADERS
#include <boost/regex.hpp>
#undef BOOST_ALLOW_DEPRECATED_HEADERS

#if __has_include(<boost/timer/progress_display.hpp>)
#include <boost/timer/progress_display.hpp>
using boost_progress_display = boost::timer::progress_display;
#else
// boost < 1.72
#define BOOST_TIMER_ENABLE_DEPRECATED 1
#include <boost/progress.hpp>
#undef BOOST_TIMER_ENABLE_DEPRECATED
using boost_progress_display = boost::progress_display;
#endif

#include <boost/math/constants/constants.hpp>
#include <boost/filesystem.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <math.h>
#include <limits>
Expand Down Expand Up @@ -773,7 +784,7 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request
}
num_planners += options.parallel_planning_pipelines.size();

boost::timer::progress_display progress(num_planners * options.runs, std::cout);
boost_progress_display progress(num_planners * options.runs, std::cout);

// Iterate through all planning pipelines
auto planning_pipelines = moveit_cpp_->getPlanningPipelines();
Expand Down

0 comments on commit bee0a29

Please sign in to comment.