From ad19978662217270a9d33bceb1265aeb45490c98 Mon Sep 17 00:00:00 2001 From: Akash Date: Thu, 29 Jul 2021 20:29:15 -0500 Subject: [PATCH] Fixes for Windows (#530) Co-authored-by: JafarAbdi Co-authored-by: Nisala Kalupahana Co-authored-by: Jorge Nicho Co-authored-by: Henning Kayser Co-authored-by: Vatan Aksoy Tezer Co-authored-by: Tyler Weaver Co-authored-by: Lior Lustgarten --- moveit_core/CMakeLists.txt | 14 +++++++------- moveit_core/CMakeModules/FindBULLET.cmake | 10 ---------- moveit_core/ConfigExtras.cmake | 5 ----- moveit_core/collision_detection/CMakeLists.txt | 5 ++++- .../collision_detector_allocator_allvalid.h | 4 +++- .../collision_detection_bullet/CMakeLists.txt | 16 +++++++++++++--- .../collision_detector_allocator_bullet.h | 4 +++- .../collision_detection_fcl/CMakeLists.txt | 12 ++++++++++-- .../collision_detector_allocator_fcl.h | 4 +++- .../constraint_samplers/test/pr2_arm_ik.cpp | 2 +- .../test/pr2_arm_kinematics_plugin.cpp | 3 ++- moveit_core/kinematics_base/CMakeLists.txt | 5 ++++- .../moveit/kinematics_base/kinematics_base.h | 4 +++- moveit_core/planning_scene/CMakeLists.txt | 4 ++++ .../moveit/planning_scene/planning_scene.h | 5 ++++- .../include/moveit/robot_model/joint_model.h | 2 ++ moveit_ros/benchmarks/CMakeLists.txt | 4 ++++ moveit_ros/benchmarks/src/BenchmarkExecutor.cpp | 3 +++ .../include/moveit_servo/servo_calcs.h | 2 +- moveit_ros/perception/CMakeLists.txt | 6 +++++- .../src/depth_image_octomap_updater.cpp | 1 + moveit_ros/perception/mesh_filter/CMakeLists.txt | 4 ++++ .../include/moveit/mesh_filter/gl_renderer.h | 3 +++ .../moveit/mesh_filter/stereo_camera_model.h | 4 +++- .../src/pointcloud_octomap_updater.cpp | 1 + .../planning/planning_pipeline/CMakeLists.txt | 4 ++++ .../moveit/planning_pipeline/planning_pipeline.h | 4 +++- .../planning_scene_monitor/CMakeLists.txt | 4 ++++ .../planning_scene_monitor.h | 5 ++++- .../planning/rdf_loader/src/rdf_loader.cpp | 8 ++++++++ .../trajectory_execution_manager/CMakeLists.txt | 4 ++++ .../trajectory_execution_manager.h | 5 ++++- .../move_group_interface/CMakeLists.txt | 4 ++++ .../move_group_interface/move_group_interface.h | 4 +++- moveit_ros/robot_interaction/CMakeLists.txt | 4 ++++ .../robot_interaction/kinematic_options_map.h | 4 +++- .../planning_scene_rviz_plugin/CMakeLists.txt | 4 ++++ .../planning_scene_display.h | 4 +++- moveit_ros/warehouse/warehouse/CMakeLists.txt | 4 ++++ .../moveit/warehouse/constraints_storage.h | 4 +++- .../moveit/warehouse/planning_scene_storage.h | 4 +++- .../include/moveit/warehouse/state_storage.h | 4 +++- .../warehouse/src/warehouse_connector.cpp | 15 ++++++++++++++- 43 files changed, 167 insertions(+), 49 deletions(-) delete mode 100644 moveit_core/CMakeModules/FindBULLET.cmake diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index c8db89ea76..487d0a03df 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -13,17 +13,17 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") - -find_package(Bullet 2.87 REQUIRED) - find_package(PkgConfig REQUIRED) - 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}) +# replace LIBFCL_LIBRARIES with full paths to the libraries +set(LIBFCL_LIBRARIES_FULL "") +foreach(LIBFCL_LIBRARY ${LIBFCL_LIBRARIES}) + find_library(${LIBFCL_LIBRARY}_LIB ${LIBFCL_LIBRARY} ${LIBFCL_LIBRARY_DIRS}) + list(APPEND LIBFCL_LIBRARIES_FULL ${${LIBFCL_LIBRARY}_LIB}) +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) diff --git a/moveit_core/CMakeModules/FindBULLET.cmake b/moveit_core/CMakeModules/FindBULLET.cmake deleted file mode 100644 index bfe4056a14..0000000000 --- a/moveit_core/CMakeModules/FindBULLET.cmake +++ /dev/null @@ -1,10 +0,0 @@ -include(FindPackageHandleStandardArgs) -find_package(PkgConfig) - -if(PKGCONFIG_FOUND) - pkg_check_modules(BULLET bullet) -endif() - -find_package_handle_standard_args(BULLET - REQUIRED_VARS BULLET_LIBRARIES BULLET_INCLUDE_DIRS - VERSION_VAR BULLET_VERSION) diff --git a/moveit_core/ConfigExtras.cmake b/moveit_core/ConfigExtras.cmake index f208f771f9..66d6e50b17 100644 --- a/moveit_core/ConfigExtras.cmake +++ b/moveit_core/ConfigExtras.cmake @@ -1,9 +1,5 @@ # Extras module needed for dependencies to find boost components -# boost::iostreams on Windows depends on boost::zlib -if(WIN32) - set(EXTRA_BOOST_COMPONENTS zlib) -endif() find_package(Boost REQUIRED chrono date_time @@ -14,5 +10,4 @@ find_package(Boost REQUIRED serialization system thread - ${EXTRA_BOOST_COMPONENTS} ) diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index a914eafb36..734d0b48a5 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -10,7 +10,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/world_diff.cpp src/collision_env.cpp ) - +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp @@ -51,3 +53,4 @@ if(BUILD_TESTING) endif() install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index fdc9aec03b..def3f3bc17 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -39,10 +39,12 @@ #include #include +#include "moveit_collision_detection_export.h" + namespace collision_detection { /** \brief An allocator for AllValid collision detectors */ -class CollisionDetectorAllocatorAllValid +class MOVEIT_COLLISION_DETECTION_EXPORT CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index 5d8e87d9a3..1918466bac 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -9,6 +9,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/bullet_integration/contact_checker_common.cpp src/bullet_integration/ros_bullet_utils.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} SYSTEM BULLET @@ -44,6 +47,7 @@ target_link_libraries(collision_detector_bullet_plugin ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} TARGETS collision_detector_bullet_plugin EXPORT collision_detector_bullet_plugin LIBRARY DESTINATION lib @@ -61,15 +65,21 @@ if(BUILD_TESTING) ament_add_gtest(test_bullet_collision_detection test/test_bullet_collision_detection_pr2.cpp) target_link_libraries(test_bullet_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_bullet_collision_detection PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_bullet_collision_detection PRIVATE -Wno-deprecated-declarations) + endif() ament_add_gtest(test_bullet_collision_detection_panda test/test_bullet_collision_detection_panda.cpp) target_link_libraries(test_bullet_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_bullet_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_bullet_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + endif() ament_add_gtest(test_bullet_continuous_collision_checking test/test_bullet_continuous_collision_checking.cpp) target_link_libraries(test_bullet_continuous_collision_checking moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations) + endif() endif() diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 8b3c11057e..c0cf1be7bf 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -39,10 +39,12 @@ #include #include +#include "moveit_collision_detection_bullet_export.h" + namespace collision_detection { /** \brief An allocator for Bullet collision detectors */ -class CollisionDetectorAllocatorBullet +class MOVEIT_COLLISION_DETECTION_BULLET_EXPORT CollisionDetectorAllocatorBullet : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index b6a6b839f6..32002955a7 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -4,6 +4,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/collision_common.cpp src/collision_env_fcl.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp @@ -34,6 +37,7 @@ target_link_libraries(collision_detector_fcl_plugin ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(BUILD_TESTING) if(WIN32) @@ -48,10 +52,14 @@ if(BUILD_TESTING) ament_add_gtest(test_fcl_collision_detection test/test_fcl_collision_detection_pr2.cpp) target_link_libraries(test_fcl_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_fcl_collision_detection PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_fcl_collision_detection PRIVATE -Wno-deprecated-declarations) + endif() ament_add_gtest(test_fcl_collision_detection_panda test/test_fcl_collision_detection_panda.cpp) target_link_libraries(test_fcl_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + endif() endif() diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index fde03c4cb5..56851f1679 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -39,10 +39,12 @@ #include #include +#include "moveit_collision_detection_fcl_export.h" + namespace collision_detection { /** \brief An allocator for FCL collision detectors */ -class CollisionDetectorAllocatorFCL +class MOVEIT_COLLISION_DETECTION_FCL_EXPORT CollisionDetectorAllocatorFCL : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp b/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp index 77080ee9ef..d172392822 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp @@ -789,6 +789,6 @@ bool PR2ArmIK::checkJointLimits(const double& joint_value, const int& joint_num) else jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]); - return not(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]); + return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]); } } // namespace pr2_arm_kinematics diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp index 5b2a7b6716..3ca4e0a7e9 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include "pr2_arm_kinematics_plugin.h" @@ -240,7 +241,7 @@ double computeEuclideanDistance(const std::vector& array_1, const KDL::J { distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i)); } - return sqrt(distance); + return std::sqrt(distance); } void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info) diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index ef52feff78..a588d259f8 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -2,7 +2,9 @@ cmake_minimum_required(VERSION 3.5) set(MOVEIT_LIB_NAME moveit_kinematics_base) add_library(${MOVEIT_LIB_NAME} SHARED src/kinematics_base.cpp) -set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) # This line is needed to ensure that messages are done being built before this is built ament_target_dependencies( @@ -17,3 +19,4 @@ ament_target_dependencies( ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 4966b017d9..1820513897 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -43,6 +43,8 @@ #include #include +#include "moveit_kinematics_base_export.h" + namespace moveit { namespace core @@ -140,7 +142,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, W * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class KinematicsBase +class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase { public: static const rclcpp::Logger LOGGER; diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index fc1f7d788f..bb62d2a351 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -1,6 +1,9 @@ set(MOVEIT_LIB_NAME moveit_planning_scene) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_scene.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) #TODO: Fix the versioning set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} @@ -26,6 +29,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 105fef02ae..9e367ef258 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -57,6 +57,8 @@ #include #include "rclcpp/rclcpp.hpp" +#include "moveit_planning_scene_export.h" + /** \brief This namespace includes the central class for representing planning contexts */ namespace planning_scene { @@ -85,7 +87,8 @@ using ObjectTypeMap = std::map +class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : private boost::noncopyable, + public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index eba749c23e..4e5117a1f5 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -45,6 +45,8 @@ #include #include +#undef near + namespace moveit { namespace core diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index e551b8e5c2..eae36d3403 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -37,9 +37,13 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/BenchmarkExecutor.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +if(WIN32) + set(EXTRA_LIB ws2_32.lib) +endif() ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS} ) +target_link_libraries(${MOVEIT_LIB_NAME} ${EXTRA_LIB}) add_executable(moveit_run_benchmark src/RunBenchmark.cpp) ament_target_dependencies(moveit_run_benchmark diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index bbd774a25c..58a90c714e 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -49,12 +49,15 @@ #include #include #include +#include #ifndef _WIN32 #include #else #include #endif +#undef max + using namespace moveit_ros_benchmarks; static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.benchmarks.BenchmarkExecutor"); diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h index 55e39dbf93..ea2724ceec 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h @@ -330,7 +330,7 @@ class ServoCalcs const int gazebo_redundant_message_count_ = 30; - uint num_joints_; + unsigned int num_joints_; // True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw] std::array drift_dimensions_ = { { false, false, false, false, false, false } }; diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt index 27ce4ca893..f2fef34935 100644 --- a/moveit_ros/perception/CMakeLists.txt +++ b/moveit_ros/perception/CMakeLists.txt @@ -28,7 +28,11 @@ if(WITH_OPENGL) set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLEW::GLEW FreeGLUT::freeglut) else() find_package(GLUT REQUIRED) - set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT) + if(WIN32) + set(SYSTEM_GL_LIBRARIES GLEW::glew GLUT::GLUT) + else() + set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT) + endif() endif() set(perception_GL_INCLUDE_DIRS "mesh_filter/include" "depth_image_octomap_updater/include") set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR}) diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp index 4edc9a3758..dc186f44e4 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -44,6 +44,7 @@ #include #include +#include namespace occupancy_map_monitor { diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 6a83af3974..54b973d317 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -7,6 +7,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/gl_renderer.cpp src/gl_mesh.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp @@ -40,3 +43,4 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) # endif() install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 6f4f9243fd..92e3441c4c 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -48,6 +48,9 @@ #include #include +#undef near +#undef far + namespace mesh_filter { MOVEIT_CLASS_FORWARD(GLRenderer); // Defines GLRendererPtr, ConstPtr, WeakPtr... etc diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 5ffd8174d3..cd4a0a7732 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -39,13 +39,15 @@ #include #include +#include "moveit_mesh_filter_export.h" + namespace mesh_filter { /** * \brief Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices * \author Suat Gedikli */ -class StereoCameraModel : public SensorModel +class MOVEIT_MESH_FILTER_EXPORT StereoCameraModel : public SensorModel { public: /** diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp index 4007b4da4f..cd163cb601 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp @@ -45,6 +45,7 @@ #include #include +#include namespace occupancy_map_monitor { diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index cf3c676457..2e8c7c925c 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -1,6 +1,9 @@ set(MOVEIT_LIB_NAME moveit_planning_pipeline) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_pipeline.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} @@ -12,3 +15,4 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index 77a1e47260..3c3527da32 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -45,6 +45,8 @@ #include +#include "moveit_planning_pipeline_export.h" + /** \brief Planning pipeline */ namespace planning_pipeline { @@ -54,7 +56,7 @@ namespace planning_pipeline planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. */ -class PlanningPipeline +class MOVEIT_PLANNING_PIPELINE_EXPORT PlanningPipeline { public: /** \brief When motion plans are computed and they are supposed to be automatically displayed, they are sent to this diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index c26781f1c1..42cdc37b1a 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -6,6 +6,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/current_state_monitor_middleware_handle.cpp src/trajectory_monitor.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_ros_occupancy_map_monitor @@ -37,6 +40,7 @@ install(TARGETS demo_scene ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index bff0dc56b0..c275e40d40 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -49,9 +49,12 @@ #include #include #include +#include #include #include +#include "moveit_planning_scene_monitor_export.h" + namespace planning_scene_monitor { MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, ConstPtr, WeakPtr... etc @@ -59,7 +62,7 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class PlanningSceneMonitor : private boost::noncopyable +class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost::noncopyable { public: enum SceneUpdateType diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index 2af090bf7d..ab64407cb8 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -192,7 +192,11 @@ bool RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& pa cmd += xacro_arg + " "; cmd += path; +#ifdef _WIN32 + FILE* pipe = _popen(cmd.c_str(), "r"); +#else FILE* pipe = popen(cmd.c_str(), "r"); +#endif if (!pipe) { RCLCPP_ERROR(LOGGER, "Unable to load path"); @@ -205,7 +209,11 @@ bool RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& pa if (fgets(pipe_buffer, 128, pipe) != nullptr) buffer += pipe_buffer; } +#ifdef _WIN32 + _pclose(pipe); +#else pclose(pipe); +#endif return true; } diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index d0e2b2acd0..95db3085ab 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -1,6 +1,9 @@ set(MOVEIT_LIB_NAME moveit_trajectory_execution_manager) add_library(${MOVEIT_LIB_NAME} SHARED src/trajectory_execution_manager.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core @@ -18,6 +21,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(CATKIN_ENABLE_TESTING) diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index bcba19818e..55e2b5b733 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -48,6 +48,9 @@ #include #include +#include + +#include "moveit_trajectory_execution_manager_export.h" namespace trajectory_execution_manager { @@ -56,7 +59,7 @@ MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager); // Defines TrajectoryExecutio // Two modes: // Managed controllers // Unmanaged controllers: given the trajectory, -class TrajectoryExecutionManager +class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager { public: static const std::string EXECUTION_EVENT_TOPIC; diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index 523d74f259..776286d927 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -1,6 +1,9 @@ set(MOVEIT_LIB_NAME moveit_move_group_interface) add_library(${MOVEIT_LIB_NAME} SHARED src/move_group_interface.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${Boost_THREAD_LIBRARY}) ament_target_dependencies(${MOVEIT_LIB_NAME} @@ -24,6 +27,7 @@ if(WIN32) endif() install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) #add_executable(demo src/demo.cpp) #target_link_libraries(demo ${MOVEIT_LIB_NAME} ${LIBS} ${Boost_LIBRARIES}) diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index e0cd026d63..6e725bac02 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -60,6 +60,8 @@ #include #include +#include "moveit_move_group_interface_export.h" + namespace moveit { /** \brief Simple interface to MoveIt components */ @@ -101,7 +103,7 @@ MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, Con \brief Client class to conveniently use the ROS interfaces provided by the move_group node. This class includes many default settings to make things easy to use. */ -class MoveGroupInterface +class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface { public: /** \brief Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description' */ diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index 9491f51480..c9298c2ca1 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -35,6 +35,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/interaction_handler.cpp src/robot_interaction.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) @@ -56,6 +59,7 @@ install( ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) install(DIRECTORY resources DESTINATION share/${PROJECT_NAME}) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 12a9c9203d..d00a29541a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -40,11 +40,13 @@ #include #include +#include "moveit_robot_interaction_export.h" + namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class KinematicOptionsMap +class MOVEIT_ROBOT_INTERACTION_EXPORT KinematicOptionsMap { public: /// Constructor - set all options to reasonable default values. diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 5b65ecdba6..b987a90b9e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -3,6 +3,9 @@ set(MOVEIT_LIB_NAME moveit_planning_scene_rviz_plugin) add_library(${MOVEIT_LIB_NAME}_core SHARED src/planning_scene_display.cpp include/moveit/planning_scene_rviz_plugin/planning_scene_display.h) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}_core) +target_include_directories(${MOVEIT_LIB_NAME}_core PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools) ament_target_dependencies(${MOVEIT_LIB_NAME}_core @@ -27,3 +30,4 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include") install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_core_export.h DESTINATION include) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 5e3ae0d488..7f0fd21c06 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -47,6 +47,8 @@ #include #endif +#include "moveit_planning_scene_rviz_plugin_core_export.h" + namespace Ogre { class SceneNode; @@ -66,7 +68,7 @@ class EnumProperty; namespace moveit_rviz_plugin { -class PlanningSceneDisplay : public rviz_common::Display +class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT PlanningSceneDisplay : public rviz_common::Display { Q_OBJECT diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index ccba905b88..6c72e53c6a 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -9,6 +9,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/state_storage.cpp src/warehouse_connector.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp Boost moveit_core warehouse_ros moveit_ros_planning) @@ -47,3 +50,4 @@ install( RUNTIME DESTINATION lib/${PROJECT_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h index bfab2a7f9d..e170bda5cd 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -40,6 +40,8 @@ #include #include +#include "moveit_warehouse_export.h" + namespace moveit_warehouse { typedef warehouse_ros::MessageWithMetadata::ConstPtr ConstraintsWithMetadata; @@ -47,7 +49,7 @@ typedef warehouse_ros::MessageCollection::Ptr Con MOVEIT_CLASS_FORWARD(ConstraintsStorage); // Defines ConstraintsStoragePtr, ConstPtr, WeakPtr... etc -class ConstraintsStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_EXPORT ConstraintsStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h index cea20282b6..6b6b633247 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -42,6 +42,8 @@ #include #include +#include "moveit_warehouse_export.h" + namespace moveit_warehouse { typedef warehouse_ros::MessageWithMetadata::ConstPtr PlanningSceneWithMetadata; @@ -54,7 +56,7 @@ typedef warehouse_ros::MessageCollection::Ptr MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc -class PlanningSceneStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_EXPORT PlanningSceneStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h index 5f6c66a3e0..952c549945 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -40,6 +40,8 @@ #include #include +#include "moveit_warehouse_export.h" + namespace moveit_warehouse { typedef warehouse_ros::MessageWithMetadata::ConstPtr RobotStateWithMetadata; @@ -47,7 +49,7 @@ typedef warehouse_ros::MessageCollection::Ptr Robo MOVEIT_CLASS_FORWARD(RobotStateStorage); // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc -class RobotStateStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_EXPORT RobotStateStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp index 17096723b3..6c4ffa6386 100644 --- a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp +++ b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp @@ -36,12 +36,25 @@ #include #include -#include #include #include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.warehouse_connector"); +#ifdef _WIN32 +void kill(int, int) +{ + RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); +} // Should never be called +int fork() +{ + RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); + return -1; +} +#else +#include +#endif + namespace moveit_warehouse { WarehouseConnector::WarehouseConnector(const std::string& dbexec) : dbexec_(dbexec), child_pid_(0)