Skip to content

Commit

Permalink
Remove dependency to moveit_common
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Nov 10, 2021
1 parent 9567962 commit da5a9b8
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 5 deletions.
19 changes: 15 additions & 4 deletions prbt_ikfast_manipulator_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,9 +1,20 @@
cmake_minimum_required(VERSION 3.10.2)
project(moveit_resources_prbt_ikfast_manipulator_plugin)

# Common cmake code applied to all moveit packages
find_package(moveit_common REQUIRED)
moveit_package()
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_EXTENSIONS OFF)

add_compile_options(-Wall)
add_compile_options(-Wextra)
add_compile_options(-Wno-unused-parameter)
add_compile_options(-Wno-unused-variable)

# enable aligned new in gcc7+
if(CMAKE_COMPILER_IS_GNUCXX)
if (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 7.0)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -faligned-new")
endif()
endif()

find_package(ament_cmake REQUIRED)
find_package(moveit_core REQUIRED)
Expand All @@ -28,7 +39,7 @@ ament_target_dependencies(prbt_manipulator_moveit_ikfast_plugin
tf2_eigen
tf2_eigen_kdl
tf2_geometry_msgs
)
)

pluginlib_export_plugin_description_file(moveit_core prbt_manipulator_moveit_ikfast_plugin_description.xml)

Expand Down
1 change: 0 additions & 1 deletion prbt_ikfast_manipulator_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@

<depend>tf2_geometry_msgs</depend>

<build_depend>moveit_common</build_depend>
<build_depend>moveit_core</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>rclcpp</build_depend>
Expand Down

0 comments on commit da5a9b8

Please sign in to comment.