mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
Improve cmake
- Modernize - Add include folder for INSTALL_INTERFACE
This commit is contained in:
parent
a0befc5b75
commit
45ff3ea437
@ -34,8 +34,7 @@ install(DIRECTORY include/ DESTINATION include
|
||||
|
||||
pluginlib_export_plugin_description_file(${PROJECT_NAME} motion_planning_stages_plugin_description.xml)
|
||||
|
||||
ament_export_include_directories(include)
|
||||
ament_export_libraries(${PROJECT_NAME} ${PROJECT_NAME}_stages)
|
||||
ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET)
|
||||
ament_export_dependencies(Boost)
|
||||
ament_export_dependencies(geometry_msgs)
|
||||
ament_export_dependencies(moveit_core)
|
||||
|
||||
@ -47,12 +47,13 @@ ament_target_dependencies(${PROJECT_NAME}
|
||||
)
|
||||
target_include_directories(${PROJECT_NAME}
|
||||
PUBLIC $<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
|
||||
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>
|
||||
$<INSTALL_INTERFACE:include>
|
||||
)
|
||||
|
||||
add_subdirectory(stages)
|
||||
|
||||
install(TARGETS ${PROJECT_NAME}
|
||||
EXPORT ${PROJECT_NAME}
|
||||
EXPORT ${PROJECT_NAME}Targets
|
||||
ARCHIVE DESTINATION lib
|
||||
LIBRARY DESTINATION lib)
|
||||
|
||||
Loading…
Reference in New Issue
Block a user