Skip to content

Commit

Permalink
Merge branch 'main' into pr-fix_inter_markers_fixed_frame
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser authored Jan 18, 2022
2 parents 196af08 + 5073795 commit 6b73fc4
Show file tree
Hide file tree
Showing 9 changed files with 2,440 additions and 14 deletions.
2,427 changes: 2,427 additions & 0 deletions Doxyfile

Large diffs are not rendered by default.

3 changes: 3 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@ See the [MoveItCpp Tutorial](https://moveit.picknik.ai/foxy/doc/moveit_cpp/movei
The [Move Group C++ Interface](https://moveit.picknik.ai/foxy/doc/move_group_interface/move_group_interface_tutorial.html) provides a simple launch file for running a MoveGroup setup.
You can test it using the MotionPlanning display in RViz or by implementing your own MoveGroupInterface application.

## Having Doxygen Reference Locally
See [How To Generate API Doxygen Reference Locally](https://moveit.picknik.ai/main/doc/how_to_guides/how_to_generate_api_doxygen_locally.html)

## Supporters

This open source project is maintained by supporters from around the world — see [MoveIt maintainers](https://moveit.ros.org/about/). Special thanks to contributor from Intel and Open Robotics.
Expand Down
6 changes: 3 additions & 3 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,6 @@ find_package(rclcpp REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)

# Finds Boost Components
include(ConfigExtras.cmake)

find_package(PkgConfig REQUIRED)
pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0")
# replace LIBFCL_LIBRARIES with full paths to the libraries
Expand Down Expand Up @@ -52,6 +49,9 @@ find_package(pluginlib REQUIRED)
# TODO: Port python bindings
# find_package(pybind11 REQUIRED)

# Finds Boost Components
include(ConfigExtras.cmake)

# Set target file path for version.h
set(VERSION_FILE_PATH ${CMAKE_BINARY_DIR}/include)

Expand Down
1 change: 0 additions & 1 deletion moveit_core/distance_field/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
tf2_eigen
OCTOMAP
)
target_link_libraries(${MOVEIT_LIB_NAME} Boost::iostreams)

install(DIRECTORY include/ DESTINATION include)

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ install(DIRECTORY include/ DESTINATION include)
find_package(ament_index_cpp REQUIRED)
set(MOVEIT_TEST_LIB_NAME moveit_test_utils)
add_library(${MOVEIT_TEST_LIB_NAME} SHARED src/robot_model_test_utils.cpp)
target_link_libraries(${MOVEIT_TEST_LIB_NAME} moveit_robot_model Boost::regex)
target_link_libraries(${MOVEIT_TEST_LIB_NAME} moveit_robot_model)
ament_target_dependencies(${MOVEIT_TEST_LIB_NAME}
ament_index_cpp
Boost
Expand Down
7 changes: 3 additions & 4 deletions moveit_ros/occupancy_map_monitor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wno-pedantic)
endif()

# Finds Boost Components
include(ConfigExtras.cmake)

if(APPLE)
find_package(X11 REQUIRED)
endif()
Expand All @@ -27,6 +24,9 @@ find_package(octomap REQUIRED)
find_package(geometric_shapes REQUIRED)
find_package(tf2_ros REQUIRED)

# Finds Boost Components
include(ConfigExtras.cmake)

include_directories(include)
include_directories(SYSTEM
${EIGEN3_INCLUDE_DIRS}
Expand All @@ -52,7 +52,6 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V
ament_target_dependencies(${MOVEIT_LIB_NAME}
${THIS_PACKAGE_INCLUDE_DEPENDS}
)
target_link_libraries(${MOVEIT_LIB_NAME} Boost::thread)

add_executable(moveit_ros_occupancy_map_server src/occupancy_map_server.cpp)
ament_target_dependencies(moveit_ros_occupancy_map_server
Expand Down
6 changes: 3 additions & 3 deletions moveit_ros/perception/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wpedantic)
endif()

# Finds Boost Components
include(ConfigExtras.cmake)

if(WITH_OPENGL)
# Prefer newer vendor-specific OpenGL library
if(POLICY CMP0072)
Expand Down Expand Up @@ -62,6 +59,9 @@ find_package(Eigen3 REQUIRED)
find_package(OpenMP REQUIRED)
find_package(OpenCV)

# Finds Boost Components
include(ConfigExtras.cmake)

set(THIS_PACKAGE_INCLUDE_DIRS
depth_image_octomap_updater/include
lazy_free_space_updater/include
Expand Down
1 change: 0 additions & 1 deletion moveit_ros/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,6 @@ add_subdirectory(move_group_interface)
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ros_testing REQUIRED)
find_package(Boost REQUIRED COMPONENTS filesystem)

# TODO (vatanaksoytezer): Enable once this test is not flaky
# Move group interface cpp ompl constrained planning integration test
Expand Down
1 change: 0 additions & 1 deletion moveit_ros/planning_interface/ConfigExtras.cmake
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
# Extras module needed for dependencies to find boost components

find_package(Boost REQUIRED)
#if(Boost_VERSION LESS 106700)
# set(BOOST_PYTHON_COMPONENT python)
#else()
Expand Down

0 comments on commit 6b73fc4

Please sign in to comment.