diff --git a/moveit2.repos b/moveit2.repos index c0f93c4298..aec6f2851e 100644 --- a/moveit2.repos +++ b/moveit2.repos @@ -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 diff --git a/moveit2_humble.repos b/moveit2_humble.repos new file mode 100644 index 0000000000..71a9316f22 --- /dev/null +++ b/moveit2_humble.repos @@ -0,0 +1,5 @@ +repositories: + generate_parameter_library: + type: git + url: https://github.com/PickNikRobotics/generate_parameter_library.git + version: 0.3.7 diff --git a/moveit2_iron.repos b/moveit2_iron.repos new file mode 100644 index 0000000000..71a9316f22 --- /dev/null +++ b/moveit2_iron.repos @@ -0,0 +1,5 @@ +repositories: + generate_parameter_library: + type: git + url: https://github.com/PickNikRobotics/generate_parameter_library.git + version: 0.3.7 diff --git a/moveit2_rolling.repos b/moveit2_rolling.repos deleted file mode 100644 index 4d39d584b4..0000000000 --- a/moveit2_rolling.repos +++ /dev/null @@ -1,9 +0,0 @@ -repositories: - octomap: - type: git - url: https://github.com/octomap/octomap.git - version: devel - geometric_shapes: - type: git - url: https://github.com/moveit/geometric_shapes.git - version: ros2