From 29717c1d6e74a7f3956e30a261d9b59a97452743 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Mon, 28 Oct 2019 23:29:46 +0100 Subject: [PATCH 1/7] Replace moveit.rosinstall with moveit2.repos --- .travis.yml | 2 +- moveit.rosinstall | 55 ----------------------------------------------- moveit2.repos | 20 ++++++++--------- 3 files changed, 11 insertions(+), 66 deletions(-) delete mode 100644 moveit.rosinstall diff --git a/.travis.yml b/.travis.yml index 6559cd264f..91b9f62a7f 100644 --- a/.travis.yml +++ b/.travis.yml @@ -16,7 +16,7 @@ env: - MOVEIT_CI_TRAVIS_TIMEOUT=85 # Travis grants us 90 min, but we add a safety margin of 5 min - ROS_DISTRO=dashing - ROS_REPO=ros - - UPSTREAM_WORKSPACE=moveit.rosinstall + - UPSTREAM_WORKSPACE=moveit2.repos - TEST_BLACKLIST=moveit_ros_perception # mesh_filter_test fails due to broken Mesa OpenGL - CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter -Wno-unused-but-set-parameter -Wno-unused-function" - WARNINGS_OK=false diff --git a/moveit.rosinstall b/moveit.rosinstall deleted file mode 100644 index 86e77ad2e1..0000000000 --- a/moveit.rosinstall +++ /dev/null @@ -1,55 +0,0 @@ -# This file is intended for users who want to build MoveIt! from source. -# Used with wstool, users can download source of all packages of MoveIt!. - -- git: - local-name: moveit2 - uri: https://github.com/ros-planning/moveit2.git - version: master -- git: - local-name: moveit_msgs - # TODO(mlautman): update to ros-planning once the package has been merged back in - uri: https://github.com/AcutronicRobotics/moveit_msgs - version: ros2 -- git: - local-name: geometric_shapes - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/AcutronicRobotics/geometric_shapes - version: ros2 -- git: - local-name: object_recognition_msgs - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/AcutronicRobotics/object_recognition_msgs - version: master -- git: - local-name: octomap_msgs - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/AcutronicRobotics/octomap_msgs - version: ros2 -- git: - local-name: random_numbers - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/AcutronicRobotics/random_numbers - version: ros2 -- git: - local-name: srdfdom - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/mlautman/srdfdom - version: ros2 -- git: - local-name: urdf_parser_py - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/AcutronicRobotics/urdf_parser_py - version: ros2 -- git: - local-name: octomap - uri: https://github.com/AcutronicRobotics/octomap - version: ros2 -- git: - local-name: moveit_resources - # TODO(mlautman): update to ros-planning once the package has been ported - uri: https://github.com/AcutronicRobotics/moveit_resources - version: master -- git: - local-name: joint_state_publisher - uri: https://github.com/ros/joint_state_publisher.git - version: ros2-devel diff --git a/moveit2.repos b/moveit2.repos index b4a00e2490..4aa952553a 100644 --- a/moveit2.repos +++ b/moveit2.repos @@ -11,24 +11,24 @@ repositories: type: git url: https://github.com/ros/joint_state_publisher version: ros2-devel - # TODO(henningkayser): Change to 'ros-planning/ros2' once https://github.com/ros-planning/random_numbers/pull/18 is merged random_numbers: type: git - url: https://github.com/PickNikRobotics/random_numbers - version: ros2-devel - # TODO(henningkayser): merge dependencies below into upstream packages + url: https://github.com/ros-planning/random_numbers + version: ros2 geometric_shapes: type: git - url: https://github.com/PickNikRobotics/geometric_shapes - version: ros2 + url: https://github.com/ros-planning/geometric_shapes + version: dashing-devel +# TODO(henningkayser): Remove once dashing release is available + octomap: + type: git + url: https://github.com/ros-gbp/octomap-release.git + version: debian/ros-melodic-octomap_1.9.0-1_bionic +# TODO(henningkayser): merge dependencies below into upstream packages object_recognition_msgs: type: git url: https://github.com/PickNikRobotics/object_recognition_msgs version: master - octomap: - type: git - url: https://github.com/PickNikRobotics/octomap - version: ros2 octomap_msgs: type: git url: https://github.com/PickNikRobotics/octomap_msgs From 341088847cba30d67c489bb68bdd0aa256caf757 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Mon, 28 Oct 2019 23:24:17 +0100 Subject: [PATCH 2/7] Add install instructions to README.md --- README.md | 40 ++++++++++++++++++++++++++++++++++------ 1 file changed, 34 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 99fd4a7a68..973aea56ac 100644 --- a/README.md +++ b/README.md @@ -1,14 +1,44 @@ MoveIt! Logo ------ +The MoveIt Motion Planning Framework for ROS 2 -Contributions are being reviewed. Refer to https://github.com/acutronicrobotics/moveit2 for a fork maintained by @AcutronicRobotics that includes the latest changes. +We are currently working on the upcoming Beta version of MoveIt 2. +See the [MoveIt's website homepage](https://moveit.ros.org) for release dates and [this document](JAFAR's LINK) for our immediate migration progress. ------ +### Build from Source + +> Note: Currently, only the moveit\_core packages are being compiled. + +These instructions assume you are running on Ubuntu 18.04. + +1. [Install ROS2 Dashing](https://index.ros.org/doc/ros2/Installation/Linux-Install-Debians/) (Make sure to set `export CHOOSE_ROS_DISTRO=Dashing` and to source `/opt/ros/dashing/setup.bash`) + +1. [Install ROS2 Build Tools](https://index.ros.org/doc/ros2/Installation/Linux-Development-Setup/#install-development-tools-and-ros-tools) + +1. Create a colcon workspace: + + export COLCON_WS=~/ws_ros2/ + mkdir -p $COLCON_WS/src + cd $COLCON_WS/src + +1. Download the repository and install any dependencies: + + git clone git@github.com:ros-planning/moveit2.git + vcs import < moveit2/moveit2.repos + rosdep install -r --from-paths . --ignore-src --rosdistro dashing -y + +1. Configure and build the workspace: + + cd $COLCON_WS + colcon build --event-handlers desktop_notification- status- --cmake-args -DCMAKE_BUILD_TYPE=Release + +1. Source the workspace: + + source $COLCON_WS/install/local_setup.bash ## Roadmap -The MoveIt! Motion Planning Framework **for ROS 2.0** +The MoveIt Motion Planning Framework **for ROS 2.0** - [Milestones](#milestones) - [Overview of MoveIt!](http://moveit.ros.org) @@ -16,8 +46,6 @@ The MoveIt! Motion Planning Framework **for ROS 2.0** - [Documentation](http://moveit.ros.org/documentation/) - [Get Involved](http://moveit.ros.org/documentation/contributing/) -## Milestones -Refer to https://github.com/acutronicrobotics/moveit2#milestones ## Continuous Integration Status From 87536fb79dce694e8eb4e722314305d8164ec8d8 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 24 May 2019 17:33:11 +0200 Subject: [PATCH 3/7] Update moveit_core CMakeLists.txt and package.xml * Fix compile warnings in moveit_core * Disable code_coverage * Add missing headers to fix '--symlink-install' * Fix include exports * Suppress CMake Warning Co-authored-by: vmayoral , henningkayser --- moveit_core/CMakeLists.txt | 173 +++++++++--------- .../collision_distance_field/CMakeLists.txt | 5 +- moveit_core/package.xml | 14 +- moveit_core/transforms/CMakeLists.txt | 13 +- 4 files changed, 104 insertions(+), 101 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 71d641edf5..79ef44b12f 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(moveit_core) +project(moveit_core VERSION 2.0.0 LANGUAGES CXX) add_compile_options(-std=c++14) @@ -10,59 +10,52 @@ add_compile_options(-Wall -Wextra if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") # This too often has false-positives add_compile_options(-Wno-maybe-uninitialized) -elseif(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") endif() set(CMAKE_EXPORT_COMPILE_COMMANDS ON) - if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) message("${PROJECT_NAME}: You did not request a specific build type: Choosing 'Release' for maximum performance") set(CMAKE_BUILD_TYPE Release) endif() +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) find_package(Boost REQUIRED system filesystem date_time thread iostreams) -find_package(Eigen3 REQUIRED) +find_package(Eigen3 REQUIRED) find_package(PkgConfig REQUIRED) -pkg_check_modules(LIBFCL_PC REQUIRED fcl) -# find *absolute* paths to LIBFCL_INCLUDE_DIRS and LIBFCL_LIBRARIES -find_path(LIBFCL_INCLUDE_DIRS fcl/config.h HINTS ${LIBFCL_PC_INCLUDE_DIR} ${LIBFCL_PC_INCLUDE_DIRS}) -find_library(LIBFCL_LIBRARIES fcl HINTS ${LIBFCL_PC_LIBRARY_DIRS}) + +pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") +# replace LIBFCL_LIBRARIES with full path to the library +find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) +set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") find_package(octomap REQUIRED) find_package(urdfdom REQUIRED) +find_package(urdf REQUIRED) find_package(urdfdom_headers REQUIRED) - -find_package(catkin REQUIRED -COMPONENTS - tf2_eigen - tf2_geometry_msgs - eigen_stl_containers - geometric_shapes - geometry_msgs - kdl_parser - moveit_msgs - octomap_msgs - random_numbers - roslib - rostime - rosconsole - sensor_msgs - shape_msgs - srdfdom - std_msgs - trajectory_msgs - urdf - visualization_msgs - xmlrpcpp -) - -set(VERSION_FILE_PATH "${CATKIN_DEVEL_PREFIX}/include") -# Pass the folder of the generated version.h to catkin_package() for export in devel-space -# This is how gencpp adds the folder of generated message code to the include dirs, see: -# https://github.com/ros/gencpp/blob/e5acaf6/cmake/gencpp-extras.cmake.em#L51-L54 -list(APPEND ${PROJECT_NAME}_INCLUDE_DIRS ${VERSION_FILE_PATH}) -file(MAKE_DIRECTORY "${VERSION_FILE_PATH}/moveit") +find_package(ament_cmake REQUIRED) +find_package(tf2_eigen REQUIRED) +find_package(tf2_kdl REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) +find_package(eigen_stl_containers REQUIRED) +find_package(geometric_shapes REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(kdl_parser REQUIRED) +find_package(moveit_msgs REQUIRED) +find_package(octomap_msgs REQUIRED) +find_package(random_numbers REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(shape_msgs REQUIRED) +find_package(srdfdom REQUIRED) +find_package(std_msgs REQUIRED) +find_package(trajectory_msgs REQUIRED) +find_package(visualization_msgs REQUIRED) +find_package(common_interfaces REQUIRED) +find_package(pluginlib REQUIRED) + +# Set target file path for version.h +set(VERSION_FILE_PATH ${CMAKE_BINARY_DIR}/include) set(THIS_PACKAGE_INCLUDE_DIRS background_processing/include @@ -92,10 +85,7 @@ set(THIS_PACKAGE_INCLUDE_DIRS utils/include ) -catkin_package( - INCLUDE_DIRS - ${THIS_PACKAGE_INCLUDE_DIRS} - LIBRARIES +set(THIS_PACKAGE_LIBRARIES moveit_exceptions moveit_background_processing moveit_kinematics_base @@ -117,55 +107,57 @@ catkin_package( moveit_kinematics_metrics moveit_dynamics_solver moveit_utils - ${OCTOMAP_LIBRARIES} - CATKIN_DEPENDS - 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 - DEPENDS - Boost - EIGEN3 - LIBFCL - OCTOMAP - urdfdom - urdfdom_headers - ) + moveit_test_utils +) +set(THIS_PACKAGE_INCLUDE_DEPENDS + 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 + Boost + OCTOMAP +) +pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) # to run: catkin_make -DENABLE_COVERAGE_TESTING=ON package_name_coverage -if(CATKIN_ENABLE_TESTING AND ENABLE_COVERAGE_TESTING) - find_package(code_coverage REQUIRED) # catkin package ros-*-code-coverage - include(CodeCoverage) - APPEND_COVERAGE_COMPILER_FLAGS() - set(COVERAGE_EXCLUDES "*/test/*") - add_code_coverage(NAME ${PROJECT_NAME}_coverage) -endif() +# TODO(henningkayser): enable once code_coverage is ported +#if(BUILD_TESTING AND ENABLE_COVERAGE_TESTING) +# find_package(code_coverage REQUIRED) # catkin package ros-*-code-coverage +# include(CodeCoverage) +# APPEND_COVERAGE_COMPILER_FLAGS() +# set(COVERAGE_EXCLUDES "*/test/*") +# add_code_coverage(NAME ${PROJECT_NAME}_coverage) +#endif() include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS} ${LIBFCL_INCLUDE_DIRS} - ) +) -#catkin_lint: ignore_once external_directory (${VERSION_FILE_PATH}) include_directories(${THIS_PACKAGE_INCLUDE_DIRS} ${VERSION_FILE_PATH} + ${rclcpp_INCLUDE_DIRS} + ${rmw_implementation_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} - ${catkin_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 string(REGEX REPLACE "^([0-9]+)\\..*" "\\1" MOVEIT_VERSION_MAJOR "${${PROJECT_NAME}_VERSION}") @@ -173,10 +165,9 @@ string(REGEX REPLACE "^[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_MINOR "${${PROJ string(REGEX REPLACE "^[0-9]+\\.[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_PATCH "${${PROJECT_NAME}_VERSION}") set(MOVEIT_VERSION_EXTRA "Alpha") set(MOVEIT_VERSION "${MOVEIT_VERSION_MAJOR}.${MOVEIT_VERSION_MINOR}.${MOVEIT_VERSION_PATCH}-${MOVEIT_VERSION_EXTRA}") -message(STATUS " *** Building MoveIt! ${MOVEIT_VERSION} ***") +message(STATUS " *** Building MoveIt ${MOVEIT_VERSION} ***") configure_file("version/version.h.in" "${VERSION_FILE_PATH}/moveit/version.h") -#catkin_lint: ignore_once external_file -install(FILES "${VERSION_FILE_PATH}/moveit/version.h" DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}/moveit) +install(FILES "${VERSION_FILE_PATH}/moveit/version.h" DESTINATION include/moveit) add_subdirectory(version) add_subdirectory(macros) @@ -185,22 +176,28 @@ add_subdirectory(exceptions) add_subdirectory(profiler) add_subdirectory(utils) add_subdirectory(background_processing) -add_subdirectory(kinematics_base) -add_subdirectory(controller_manager) -add_subdirectory(sensor_manager) add_subdirectory(robot_model) +add_subdirectory(collision_detection) +add_subdirectory(kinematics_base) add_subdirectory(transforms) add_subdirectory(robot_state) -add_subdirectory(robot_trajectory) -add_subdirectory(collision_detection) add_subdirectory(collision_detection_fcl) +add_subdirectory(robot_trajectory) add_subdirectory(kinematic_constraints) +add_subdirectory(trajectory_processing) add_subdirectory(planning_scene) +add_subdirectory(controller_manager) +add_subdirectory(sensor_manager) add_subdirectory(constraint_samplers) add_subdirectory(planning_interface) add_subdirectory(planning_request_adapter) -add_subdirectory(trajectory_processing) add_subdirectory(distance_field) add_subdirectory(collision_distance_field) add_subdirectory(kinematics_metrics) add_subdirectory(dynamics_solver) + +ament_export_include_directories(include) +ament_export_libraries(${THIS_PACKAGE_LIBRARIES}) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) + +ament_package() diff --git a/moveit_core/collision_distance_field/CMakeLists.txt b/moveit_core/collision_distance_field/CMakeLists.txt index 03f3d63b50..23f9b0ff18 100644 --- a/moveit_core/collision_distance_field/CMakeLists.txt +++ b/moveit_core/collision_distance_field/CMakeLists.txt @@ -11,12 +11,12 @@ add_library(${MOVEIT_LIB_NAME} SHARED set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} - moveit_planning_scene - moveit_distance_field urdf visualization_msgs tf2_eigen angles + geometric_shapes + OCTOMAP ) target_link_libraries(${MOVEIT_LIB_NAME} @@ -24,7 +24,6 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_distance_field moveit_collision_detection moveit_robot_state - ${geometric_shapes_LIBRARIES} ) install(TARGETS ${MOVEIT_LIB_NAME} diff --git a/moveit_core/package.xml b/moveit_core/package.xml index 593b495ed6..272724de3b 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -16,15 +16,17 @@ https://github.com/ros-planning/moveit/issues https://github.com/ros-planning/moveit - catkin + ament_cmake pkg-config + eigen3_cmake_module + rclcpp assimp boost eigen eigen_stl_containers libfcl-dev - geometric_shapes + geometric_shapes geometry_msgs kdl_parser libconsole-bridge-dev @@ -35,27 +37,27 @@ octomap octomap_msgs random_numbers - roslib - rostime - rosconsole sensor_msgs shape_msgs srdfdom std_msgs + tf2 tf2_eigen tf2_geometry_msgs trajectory_msgs visualization_msgs - xmlrpcpp angles moveit_resources tf2_kdl orocos_kdl + + ament_cmake diff --git a/moveit_core/transforms/CMakeLists.txt b/moveit_core/transforms/CMakeLists.txt index 075e5615af..4e14187288 100644 --- a/moveit_core/transforms/CMakeLists.txt +++ b/moveit_core/transforms/CMakeLists.txt @@ -3,14 +3,19 @@ set(MOVEIT_LIB_NAME moveit_transforms) add_library(${MOVEIT_LIB_NAME} src/transforms.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_link_libraries(${MOVEIT_LIB_NAME} ${rclcpp_LIBRARIES} ${rmw_implementation_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} ${Boost_LIBRARIES}) ament_target_dependencies(${MOVEIT_LIB_NAME} - tf2_eigen) - + tf2_eigen + rclcpp + rmw_implementation + urdfdom + urdfdom_headers + Boost +) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib - ARCHIVE DESTINATION lib) + ARCHIVE DESTINATION lib +) install(DIRECTORY include/ DESTINATION include) # Unit tests From 7229445aacc051b0a601e61d543b78d309dbcb65 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Mon, 28 Oct 2019 22:54:09 +0100 Subject: [PATCH 4/7] Remove COLCON_IGNORE from moveit_core --- moveit_core/COLCON_IGNORE | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 moveit_core/COLCON_IGNORE diff --git a/moveit_core/COLCON_IGNORE b/moveit_core/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 From 0e49b6d155d57627aadb313c74de19592e79d892 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Mon, 28 Oct 2019 22:01:01 +0100 Subject: [PATCH 5/7] Fix ament dependencies in moveit_core libraries * collision_detection * collision_distance_field * moveit_utils * moveit_profiler * distance_field * robot_model * moveit_transforms --- .../collision_detection/CMakeLists.txt | 13 +------- moveit_core/distance_field/CMakeLists.txt | 13 ++++---- moveit_core/profiler/CMakeLists.txt | 14 ++++++-- moveit_core/robot_model/CMakeLists.txt | 32 +++++++++++++------ moveit_core/transforms/CMakeLists.txt | 2 +- moveit_core/utils/CMakeLists.txt | 16 ++++------ 6 files changed, 48 insertions(+), 42 deletions(-) diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index 7a1f4739e2..4118eb1ca2 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -23,19 +23,8 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} visualization_msgs tf2_eigen geometric_shapes -) - -ament_target_dependencies(${MOVEIT_LIB_NAME} - moveit_robot_state - rclcpp - rmw_implementation - urdf - urdfdom - urdfdom_headers - visualization_msgs - tf2_eigen Boost - geometric_shapes + OCTOMAP ) # unit tests diff --git a/moveit_core/distance_field/CMakeLists.txt b/moveit_core/distance_field/CMakeLists.txt index 4e66fa5a35..eb80b86b82 100644 --- a/moveit_core/distance_field/CMakeLists.txt +++ b/moveit_core/distance_field/CMakeLists.txt @@ -9,20 +9,19 @@ add_library(${MOVEIT_LIB_NAME} SHARED set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} - boost + Boost urdfdom urdfdom_headers visualization_msgs - tf2_eigen) - -target_link_libraries(${MOVEIT_LIB_NAME} - ${Boost_LIBRARIES} - ${geometric_shapes_LIBRARIES} + geometric_shapes + tf2_eigen + OCTOMAP ) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib - ARCHIVE DESTINATION lib) + ARCHIVE DESTINATION lib +) install(DIRECTORY include/ DESTINATION include) if(BUILD_TESTING) diff --git a/moveit_core/profiler/CMakeLists.txt b/moveit_core/profiler/CMakeLists.txt index e3db473525..0e8498b3ee 100644 --- a/moveit_core/profiler/CMakeLists.txt +++ b/moveit_core/profiler/CMakeLists.txt @@ -1,11 +1,19 @@ set(MOVEIT_LIB_NAME moveit_profiler) -add_library(${MOVEIT_LIB_NAME} src/profiler.cpp) +add_library(${MOVEIT_LIB_NAME} SHARED src/profiler.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_link_libraries(${MOVEIT_LIB_NAME} ${rclcpp_LIBRARIES} ${rmw_implementation_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} ${Boost_LIBRARIES}) +ament_target_dependencies(${MOVEIT_LIB_NAME} + rclcpp + rmw_implementation + urdfdom + urdfdom_headers + Boost + random_numbers +) install(TARGETS ${MOVEIT_LIB_NAME} + ARCHIVE DESTINATION lib LIBRARY DESTINATION lib - ARCHIVE DESTINATION lib) +) install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_core/robot_model/CMakeLists.txt b/moveit_core/robot_model/CMakeLists.txt index da17110ab7..34661afcd9 100644 --- a/moveit_core/robot_model/CMakeLists.txt +++ b/moveit_core/robot_model/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.5) set(MOVEIT_LIB_NAME moveit_robot_model) -add_library(${MOVEIT_LIB_NAME} +add_library(${MOVEIT_LIB_NAME} SHARED src/aabb.cpp src/fixed_joint_model.cpp src/floating_joint_model.cpp @@ -15,24 +15,36 @@ add_library(${MOVEIT_LIB_NAME} ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -ament_target_dependencies(${MOVEIT_LIB_NAME} - urdf - urdfdom_headers - visualization_msgs +target_link_libraries(${MOVEIT_LIB_NAME} moveit_profiler moveit_exceptions - moveit_kinematics_base) + moveit_kinematics_base + Eigen3::Eigen + ${urdf_LIBRARIES} + ${srdfdom_LIBRARIES} + ${urdfdom_headers_LIBRARIES} + ${visualization_msgs_LIBRARIES} + ${geometric_shapes_LIBRARIES} +) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(moveit_resources REQUIRED) - include_directories(${moveit_resources_INCLUDE_DIRS}) - ament_add_gtest(test_robot_model test/test.cpp) - target_link_libraries(test_robot_model moveit_test_utils ${rclcpp_LIBRARIES} ${rmw_implementation_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} ${MOVEIT_LIB_NAME}) + 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}) endif() install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib - ARCHIVE DESTINATION lib) + ARCHIVE DESTINATION lib +) install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_core/transforms/CMakeLists.txt b/moveit_core/transforms/CMakeLists.txt index 4e14187288..1cd532fa4b 100644 --- a/moveit_core/transforms/CMakeLists.txt +++ b/moveit_core/transforms/CMakeLists.txt @@ -1,6 +1,6 @@ set(MOVEIT_LIB_NAME moveit_transforms) -add_library(${MOVEIT_LIB_NAME} src/transforms.cpp) +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} diff --git a/moveit_core/utils/CMakeLists.txt b/moveit_core/utils/CMakeLists.txt index 17849bc9d9..5c38297ecd 100644 --- a/moveit_core/utils/CMakeLists.txt +++ b/moveit_core/utils/CMakeLists.txt @@ -18,15 +18,13 @@ if(BUILD_TESTING) set(MOVEIT_TEST_LIB_NAME moveit_test_utils) add_library(${MOVEIT_TEST_LIB_NAME} src/robot_model_test_utils.cpp) - - include_directories(${moveit_resources_INCLUDE_DIRS}) - - target_link_libraries(${MOVEIT_TEST_LIB_NAME} - ${Boost_LIBRARIES} - ${urdf_LIBRARIES} - ${srdfdom_LIBRARIES} - ${urdfdom_LIBRARIES} - ${urdfdom_headers_LIBRARIES} + ament_target_dependencies(${MOVEIT_TEST_LIB_NAME} + Boost + urdf + srdfdom + urdfdom + urdfdom_headers + moveit_resources ) set_target_properties(${MOVEIT_TEST_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") From 02fdc64730e2c340a204fc1d79385a66f9edd17f Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Mon, 18 Nov 2019 13:14:58 +0100 Subject: [PATCH 6/7] Temporarily skip "rosdep install" * Install libfcl-dev and ros-dashing-angles before CI --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index 91b9f62a7f..2a05254d07 100644 --- a/.travis.yml +++ b/.travis.yml @@ -20,6 +20,8 @@ env: - TEST_BLACKLIST=moveit_ros_perception # mesh_filter_test fails due to broken Mesa OpenGL - CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter -Wno-unused-but-set-parameter -Wno-unused-function" - WARNINGS_OK=false + - BEFORE_DOCKER_SCRIPT="sed -i 's/travis_run --retry rosdep install/#rosdep install/g' .moveit_ci/travis.sh" + - BEFORE_SCRIPT="sudo apt-get -qq update; sudo apt-get -qq install -y libfcl-dev ros-dashing-angles" matrix: # TODO(mlautman): Enable these in the future once they pass # - TEST="clang-format ament_lint" From 362f98367b4297a699b3c02a478e11f61f56912e Mon Sep 17 00:00:00 2001 From: RoboticsYY Date: Fri, 8 Nov 2019 17:25:31 +0800 Subject: [PATCH 7/7] Suppress -Wcast-qual warning --- moveit_core/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 79ef44b12f..37e902b807 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -4,8 +4,10 @@ project(moveit_core VERSION 2.0.0 LANGUAGES CXX) add_compile_options(-std=c++14) # Warnings +# Remove -Wcast-qual to avoid warnings in tf2/LinearMath/Vector3.h. +# TODO: Add -Wcast-qual back when PR(https://github.com/ros2/geometry2/pull/193) is merged. add_compile_options(-Wall -Wextra - -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual + -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter -Wno-unused-function) if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") # This too often has false-positives