diff --git a/.github/workflows/build.yaml b/.github/workflows/build.yaml index 881b10ba41..119b2098cd 100644 --- a/.github/workflows/build.yaml +++ b/.github/workflows/build.yaml @@ -28,13 +28,20 @@ jobs: with: repos: ros-desktop-full depends: ros-desktop + ros-manipulation: + if: success() || failure() # can get cancelled + needs: ros-desktop-full + uses: ./.github/workflows/debs-from-repos.yaml + with: + repos: ros-manipulation + depends: ros-desktop-full universe-0: if: success() || failure() # can get cancelled needs: ros-desktop-full uses: ./.github/workflows/debs-from-repos.yaml with: repos: universe-0 - depends: ros-desktop-full + depends: ros-manipulation universe-1: if: success() || failure() # can get cancelled needs: universe-0 diff --git a/ros-manipulation.repos b/ros-manipulation.repos new file mode 100644 index 0000000000..9659744a86 --- /dev/null +++ b/ros-manipulation.repos @@ -0,0 +1,109 @@ +repositories: + bio_ik: + type: git + url: https://github.com/TAMS-Group/bio_ik.git + version: master + eigenpy: + type: git + url: https://github.com/stack-of-tasks/eigenpy + version: master + geometric_shapes: + type: git + url: https://github.com/ros-planning/geometric_shapes.git + version: noetic-devel + moveit: + type: git + url: https://github.com/ros-planning/moveit + version: master + moveit_by_name: + type: git + url: https://github.com/TAMS-Group/moveit_by_name + version: main + moveit_monitoring: + type: git + url: https://github.com/v4hn/moveit_monitoring + version: main + moveit_msgs: + type: git + url: https://github.com/ros-planning/moveit_msgs.git + version: master + moveit_python: + type: git + url: https://github.com/mikeferguson/moveit_python.git + version: ros1 + moveit_resources: + type: git + url: https://github.com/ros-planning/moveit_resources.git + version: master + moveit_tutorials: + type: git + url: https://github.com/ros-planning/moveit_tutorials.git + version: master + moveit_visual_tools: + type: git + url: https://github.com/ros-planning/moveit_visual_tools.git + version: master + moveit_task_constructor: + type: git + url: https://github.com/v4hn/moveit_task_constructor + version: master + mtc_pour: + type: git + url: https://github.com/TAMS-Group/mtc_pour + version: master + object_recognition_msgs: + type: git + url: https://github.com/wg-perception/object_recognition_msgs.git + version: noetic-devel + octomap_msgs: + type: git + url: https://github.com/OctoMap/octomap_msgs.git + version: melodic-devel + ompl: + type: git + url: https://github.com/ompl/ompl + version: main + panda_moveit_config: + type: git + url: https://github.com/ros-planning/panda_moveit_config.git + version: noetic-devel + pybind11_catkin: + type: git + url: https://github.com/ipab-slmc/pybind11_catkin + version: master + random_numbers: + type: git + url: https://github.com/ros-planning/random_numbers + version: master + ros_industrial/industrial_core: + type: git + url: https://github.com/ros-o/industrial_core + version: obese-devel + ros_industrial/moveit_opw_kinematics_plugin: + type: git + url: https://github.com/JeroenDM/moveit_opw_kinematics_plugin + version: noetic-devel + ros_industrial/opw_kinematics: + type: git + url: https://github.com/Jmeyer1292/opw_kinematics + version: master + ros_industrial/ros_industrial_cmake_boilerplate: + type: git + url: https://github.com/ros-industrial/ros_industrial_cmake_boilerplate + version: master + ruckig: + type: git + url: https://github.com/pantor/ruckig + version: main + srdfdom: + type: git + url: https://github.com/ros-planning/srdfdom + version: noetic-devel + warehouse_ros: + type: git + url: https://github.com/ros-planning/warehouse_ros + version: kinetic-devel + warehouse_ros_sqlite: + type: git + url: https://github.com/ros-planning/warehouse_ros_sqlite + version: master diff --git a/universe-1.repos b/universe-1.repos index 078329da7b..e8f4215c34 100644 --- a/universe-1.repos +++ b/universe-1.repos @@ -3,10 +3,6 @@ repositories: type: git url: https://github.com/ros-o/openni_camera.git version: obese-devel - octomap_msgs: - type: git - url: https://github.com/OctoMap/octomap_msgs.git - version: melodic-devel camera_info_manager_py: type: git url: https://github.com/ros-o/camera_info_manager_py @@ -59,10 +55,6 @@ repositories: type: git url: https://github.com/mikeferguson/robot_calibration version: ros1 - object_recognition_msgs: - type: git - url: https://github.com/wg-perception/object_recognition_msgs.git - version: noetic-devel laser_filtering: type: git url: https://github.com/DLu/laser_filtering.git