Skip to content

Commit

Permalink
Restructure source dependencies for Jammy, Noble distros
Browse files Browse the repository at this point in the history
* Only source generate_parameter_library for Humble and Iron
* Depend on moveit2.repos for Jazzy, Rolling
* Switch GitHub orgs from ros-planning to "moveit"
  • Loading branch information
henningkayser committed Jun 13, 2024
1 parent 6b5494e commit 871b9c3
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 15 deletions.
12 changes: 6 additions & 6 deletions moveit2.repos
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
repositories:
# Keep moveit_* repos here because they are released with moveit
geometric_shapes:
type: git
url: https://github.com/moveit/geometric_shapes.git
version: ros2
moveit_msgs:
type: git
url: https://github.com/ros-planning/moveit_msgs.git
url: https://github.com/moveit/moveit_msgs.git
version: ros2
moveit_resources:
type: git
url: https://github.com/ros-planning/moveit_resources.git
url: https://github.com/moveit/moveit_resources.git
version: ros2
generate_parameter_library:
type: git
url: https://github.com/PickNikRobotics/generate_parameter_library.git
version: 0.3.7
5 changes: 5 additions & 0 deletions moveit2_humble.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
repositories:
generate_parameter_library:
type: git
url: https://github.com/PickNikRobotics/generate_parameter_library.git
version: 0.3.7
5 changes: 5 additions & 0 deletions moveit2_iron.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
repositories:
generate_parameter_library:
type: git
url: https://github.com/PickNikRobotics/generate_parameter_library.git
version: 0.3.7
9 changes: 0 additions & 9 deletions moveit2_rolling.repos

This file was deleted.

0 comments on commit 871b9c3

Please sign in to comment.