diff --git a/.github/upstream.repos b/.github/upstream.repos index f09982304c..d7566131ae 100644 --- a/.github/upstream.repos +++ b/.github/upstream.repos @@ -7,14 +7,6 @@ repositories: type: git url: https://github.com/moveit/moveit_visual_tools version: ros2 - rosparam_shortcuts: - type: git - url: https://github.com/PickNikRobotics/rosparam_shortcuts - version: ros2 - rviz_visual_tools: - type: git - url: https://github.com/PickNikRobotics/rviz_visual_tools.git - version: ros2 # Remove ros2_kortex when rolling binaries are available. ros2_kortex: type: git @@ -30,3 +22,19 @@ repositories: type: git url: https://github.com/tylerjw/serial.git version: ros2 + rviz_visual_tools: + type: git + url: https://github.com/PickNikRobotics/rviz_visual_tools.git + version: ros2 + moveit2: + type: git + url: https://github.com/moveit/moveit2 + version: main + moveit_resources: + type: git + url: https://github.com/moveit/moveit_resources + version: ros2 + moveit_msgs: + type: git + url: https://github.com/moveit/moveit_msgs + version: ros2 diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index af0f185e45..f26cb78bee 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -20,7 +20,7 @@ jobs: strategy: matrix: env: - - IMAGE: rolling-source + - IMAGE: rolling-ci env: DOCKER_IMAGE: moveit/moveit2:${{ matrix.env.IMAGE }} @@ -35,11 +35,11 @@ jobs: name: ${{ matrix.env.IMAGE }} runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: fetch-depth: 0 - name: cache upstream_ws - uses: actions/cache@v4 + uses: actions/cache@v5 with: save-always: true path: ${{ env.BASEDIR }}/upstream_ws @@ -49,7 +49,7 @@ jobs: # The target directory cache doesn't include the source directory because # that comes from the checkout. See "prepare target_ws for cache" task below - name: cache target_ws - uses: actions/cache@v4 + uses: actions/cache@v5 with: save-always: true path: ${{ env.BASEDIR }}/target_ws @@ -57,7 +57,7 @@ jobs: restore-keys: | target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }} - name: cache ccache - uses: actions/cache@v4 + uses: actions/cache@v5 with: save-always: true path: ${{ env.CCACHE_DIR }}