Skip to content

Commit

Permalink
add rsl depend to moveit_core
Browse files Browse the repository at this point in the history
- This should fix moveit#2516
- Several moveit2 packages already depend on rsl
- PR moveit#2482 added a depend in moveit_core

This is only broken when building all of moveit2 deps in one colcon workspace
And not using rosdep because colcon uses the package.xml and rsl might not have been built

Signed-off-by: Alex Moriarty <alex.moriarty@picknik.ai>
  • Loading branch information
moriarty committed Nov 15, 2023
1 parent 2487b24 commit 9d9cc4a
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 0 deletions.
2 changes: 2 additions & 0 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ find_package(octomap_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(random_numbers REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rsl REQUIRED)
find_package(ruckig REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(shape_msgs REQUIRED)
Expand Down Expand Up @@ -150,6 +151,7 @@ ament_export_dependencies(
pluginlib
random_numbers
rclcpp
rsl
ruckig
sensor_msgs
shape_msgs
Expand Down
1 change: 1 addition & 0 deletions moveit_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
<depend>pybind11_vendor</depend>
<depend>random_numbers</depend>
<depend>rclcpp</depend>
<depend>rsl</depend>
<depend>ruckig</depend>
<depend>sensor_msgs</depend>
<depend>shape_msgs</depend>
Expand Down

0 comments on commit 9d9cc4a

Please sign in to comment.