Skip to content

Commit

Permalink
add moveit
Browse files Browse the repository at this point in the history
  • Loading branch information
v4hn committed Aug 30, 2024
1 parent b3e0072 commit bf6bc9b
Show file tree
Hide file tree
Showing 3 changed files with 117 additions and 9 deletions.
9 changes: 8 additions & 1 deletion .github/workflows/build.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
109 changes: 109 additions & 0 deletions ros-manipulation.repos
Original file line number Diff line number Diff line change
@@ -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
8 changes: 0 additions & 8 deletions universe-1.repos
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down

0 comments on commit bf6bc9b

Please sign in to comment.