Skip to content

Commit

Permalink
Remove unnecessary CMake variables and lists
Browse files Browse the repository at this point in the history
Signed-off-by: Tyler Weaver <tyler@picknik.ai>
  • Loading branch information
tylerjw committed Dec 6, 2022
1 parent bbbccbd commit d67f659
Showing 1 changed file with 74 additions and 77 deletions.
151 changes: 74 additions & 77 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,6 @@ project(moveit_core LANGUAGES CXX)
find_package(moveit_common REQUIRED)
moveit_package()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)

find_package(PkgConfig REQUIRED)
pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0")
# replace LIBFCL_LIBRARIES with full paths to the libraries
Expand All @@ -20,32 +15,35 @@ foreach(LIBFCL_LIBRARY ${LIBFCL_LIBRARIES})
endforeach()
set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}")

find_package(Bullet 2.87 REQUIRED)
find_package(angles REQUIRED)
find_package(OCTOMAP REQUIRED)
find_package(urdfdom REQUIRED)
find_package(urdf REQUIRED)
find_package(urdfdom_headers REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_kdl REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(angles REQUIRED)
find_package(Bullet 2.87 REQUIRED)
find_package(common_interfaces REQUIRED)
find_package(eigen_stl_containers REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(geometric_shapes REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(kdl_parser REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(OCTOMAP REQUIRED)
find_package(octomap_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(random_numbers REQUIRED)
find_package(rclcpp REQUIRED)
find_package(ruckig REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(shape_msgs REQUIRED)
find_package(srdfdom REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_kdl REQUIRED)
find_package(trajectory_msgs REQUIRED)
find_package(urdf REQUIRED)
find_package(urdfdom REQUIRED)
find_package(urdfdom_headers REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(common_interfaces REQUIRED)
find_package(pluginlib REQUIRED)
# TODO: Port python bindings
# find_package(pybind11 REQUIRED)

Expand All @@ -55,63 +53,10 @@ include(ConfigExtras.cmake)
# Set target file path for version.h
set(VERSION_FILE_PATH ${CMAKE_BINARY_DIR}/include)

set(THIS_PACKAGE_LIBRARIES
moveit_butterworth_filter
moveit_collision_distance_field
moveit_collision_detection
moveit_collision_detection_fcl
moveit_collision_detection_bullet
moveit_dynamics_solver
moveit_constraint_samplers
moveit_distance_field
moveit_exceptions
moveit_kinematics_base
moveit_kinematic_constraints
moveit_kinematics_metrics
moveit_macros
moveit_planning_interface
moveit_planning_scene
moveit_planning_request_adapter
# TODO: Port python bindings
# moveit_python_tools
moveit_robot_model
moveit_robot_state
moveit_robot_trajectory
moveit_smoothing_base
moveit_test_utils
moveit_trajectory_processing
moveit_transforms
moveit_utils
)

set(THIS_PACKAGE_INCLUDE_DEPENDS
angles
eigen_stl_containers
geometric_shapes
geometry_msgs
kdl_parser
moveit_msgs
octomap_msgs
random_numbers
sensor_msgs
shape_msgs
srdfdom
std_msgs
tf2_eigen
tf2_geometry_msgs
trajectory_msgs
visualization_msgs
Eigen3
eigen3_cmake_module
OCTOMAP
Bullet
ruckig
)

# Generate and install version.h
string(REGEX REPLACE "^([0-9]+)\\..*" "\\1" MOVEIT_VERSION_MAJOR "${${PROJECT_NAME}_VERSION}")
string(REGEX REPLACE "^[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_MINOR "${${PROJECT_NAME}_VERSION}")
string(REGEX REPLACE "^[0-9]+\\.[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_PATCH "${${PROJECT_NAME}_VERSION}")
string(REGEX REPLACE "^([0-9]+)\\..*" "\\1" MOVEIT_VERSION_MAJOR "${moveit_core_VERSION}")
string(REGEX REPLACE "^[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_MINOR "${moveit_core_VERSION}")
string(REGEX REPLACE "^[0-9]+\\.[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_PATCH "${moveit_core_VERSION}")
set(MOVEIT_VERSION "${MOVEIT_VERSION_MAJOR}.${MOVEIT_VERSION_MINOR}.${MOVEIT_VERSION_PATCH}")
message(STATUS " *** Building MoveIt ${MOVEIT_VERSION} ***")
configure_file("version/version.h.in" "${VERSION_FILE_PATH}/moveit/version.h")
Expand Down Expand Up @@ -172,16 +117,68 @@ add_subdirectory(collision_detection_fcl)


install(
TARGETS ${THIS_PACKAGE_LIBRARIES}
EXPORT ${PROJECT_NAME}Targets
TARGETS
moveit_butterworth_filter
moveit_collision_distance_field
moveit_collision_detection
moveit_collision_detection_fcl
moveit_collision_detection_bullet
moveit_dynamics_solver
moveit_constraint_samplers
moveit_distance_field
moveit_exceptions
moveit_kinematics_base
moveit_kinematic_constraints
moveit_kinematics_metrics
moveit_macros
moveit_planning_interface
moveit_planning_scene
moveit_planning_request_adapter
moveit_robot_model
moveit_robot_state
moveit_robot_trajectory
moveit_smoothing_base
moveit_test_utils
moveit_trajectory_processing
moveit_transforms
moveit_utils
EXPORT moveit_coreTargets
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)

ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} orocos_kdl_vendor)
ament_export_targets(moveit_coreTargets HAS_LIBRARY_TARGET)
ament_export_dependencies(
angles
Bullet
common_interfaces
eigen_stl_containers
Eigen3
eigen3_cmake_module
geometric_shapes
geometry_msgs
kdl_parser
moveit_msgs
OCTOMAP
octomap_msgs
pluginlib
random_numbers
rclcpp
ruckig
sensor_msgs
shape_msgs
srdfdom
std_msgs
tf2_eigen
tf2_geometry_msgs
tf2_kdl
trajectory_msgs
urdf
urdfdom
urdfdom_headers
visualization_msgs
)

# Plugin exports
pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml)
Expand Down

0 comments on commit d67f659

Please sign in to comment.