Skip to content

Commit

Permalink
Fix ament_lint
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Dec 5, 2019
1 parent bfdb0e6 commit de6ed4e
Show file tree
Hide file tree
Showing 9 changed files with 39 additions and 39 deletions.
24 changes: 12 additions & 12 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -135,21 +135,21 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml)

include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS}
${LIBFCL_INCLUDE_DIRS}
${LIBFCL_INCLUDE_DIRS}
)

include_directories(${THIS_PACKAGE_INCLUDE_DIRS}
${VERSION_FILE_PATH}
${rclcpp_INCLUDE_DIRS}
${rmw_implementation_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${urdfdom_INCLUDE_DIRS}
${urdfdom_headers_INCLUDE_DIRS}
${OCTOMAP_INCLUDE_DIRS}
${moveit_msgs_INCLUDE_DIRS}
${random_numbers_INCLUDE_DIRS}
${srdfdom_INCLUDE_DIRS}
${geometric_shapes_INCLUDE_DIRS}
${VERSION_FILE_PATH}
${rclcpp_INCLUDE_DIRS}
${rmw_implementation_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${urdfdom_INCLUDE_DIRS}
${urdfdom_headers_INCLUDE_DIRS}
${OCTOMAP_INCLUDE_DIRS}
${moveit_msgs_INCLUDE_DIRS}
${random_numbers_INCLUDE_DIRS}
${srdfdom_INCLUDE_DIRS}
${geometric_shapes_INCLUDE_DIRS}
)

# Generate and install version.h
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/collision_detection/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ if(BUILD_TESTING)
if(WIN32)
# TODO add window paths
else()
set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../robot_model;${CMAKE_CURRENT_BINARY_DIR}/../utils")
set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../robot_model;${CMAKE_CURRENT_BINARY_DIR}/../utils")
endif()

ament_add_gtest(test_world test/test_world.cpp
Expand All @@ -55,7 +55,7 @@ if(BUILD_TESTING)
)

ament_add_gtest(test_all_valid test/test_all_valid.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
APPEND_LIBRARY_DIRS "${append_library_dirs}")
target_link_libraries(test_all_valid
${MOVEIT_LIB_NAME}
moveit_robot_model
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/collision_distance_field/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,13 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
OCTOMAP
)

target_link_libraries(${MOVEIT_LIB_NAME}
target_link_libraries(${MOVEIT_LIB_NAME}
moveit_planning_scene
moveit_distance_field
moveit_collision_detection
moveit_robot_state
)

install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/constraint_samplers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ target_link_libraries(${MOVEIT_LIB_NAME}
install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
RUNTIME DESTINATION bin
)

install(DIRECTORY include/ DESTINATION include)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/distance_field/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
RUNTIME DESTINATION bin
)
install(DIRECTORY include/ DESTINATION include)

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_scene/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ target_link_libraries(${MOVEIT_LIB_NAME}
install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin)
RUNTIME DESTINATION bin)
install(DIRECTORY include/ DESTINATION include)

if(BUILD_TESTING)
Expand Down
22 changes: 11 additions & 11 deletions moveit_core/robot_model/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED
src/prismatic_joint_model.cpp
src/revolute_joint_model.cpp
src/robot_model.cpp
)
)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

target_link_libraries(${MOVEIT_LIB_NAME}
Expand All @@ -32,20 +32,20 @@ if(BUILD_TESTING)
find_package(moveit_resources REQUIRED)
ament_add_gtest(test_robot_model test/test.cpp)
target_link_libraries(test_robot_model
moveit_test_utils
moveit_profiler
${Boost_LIBRARIES}
${rclcpp_LIBRARIES}
${rmw_implementation_LIBRARIES}
${urdfdom_LIBRARIES}
${urdfdom_headers_LIBRARIES}
${geometric_shapes_LIBRARIES}
${MOVEIT_LIB_NAME})
moveit_test_utils
moveit_profiler
${Boost_LIBRARIES}
${rclcpp_LIBRARIES}
${rmw_implementation_LIBRARIES}
${urdfdom_LIBRARIES}
${urdfdom_headers_LIBRARIES}
${geometric_shapes_LIBRARIES}
${MOVEIT_LIB_NAME})
endif()

install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
RUNTIME DESTINATION bin
)
install(DIRECTORY include/ DESTINATION include)
4 changes: 2 additions & 2 deletions moveit_core/robot_state/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin)
RUNTIME DESTINATION bin)
install(DIRECTORY include/ DESTINATION include)

# Unit tests
Expand Down Expand Up @@ -76,7 +76,7 @@ if(BUILD_TESTING)

# As an executable, this benchmark is not run as a test by default
ament_add_gtest(test_robot_state_benchmark test/robot_state_benchmark.cpp)
target_include_directories(test_robot_state_benchmark PUBLIC
target_include_directories(test_robot_state_benchmark PUBLIC
${tf2_geometry_msgs_INCLUDE_DIRS}
${urdf_INCLUDE_DIRS}
${visualization_msgs_INCLUDE_DIRS}
Expand Down
14 changes: 7 additions & 7 deletions moveit_core/transforms/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,18 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/transforms.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

ament_target_dependencies(${MOVEIT_LIB_NAME}
tf2_eigen
rclcpp
rmw_implementation
urdfdom
urdfdom_headers
Boost
tf2_eigen
rclcpp
rmw_implementation
urdfdom
urdfdom_headers
Boost
)

install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
RUNTIME DESTINATION bin
)
install(DIRECTORY include/ DESTINATION include)

Expand Down

0 comments on commit de6ed4e

Please sign in to comment.