diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 9e5fd8986e..672dfa31d0 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -1,6 +1,8 @@ cmake_minimum_required(VERSION 3.10.2) project(moveit_core VERSION 2.0.0 LANGUAGES CXX) +set(CMAKE_VERBOSE_MAKEFILE ON) + # Common cmake code applied to all moveit packages find_package(moveit_common REQUIRED) moveit_package() @@ -13,7 +15,9 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) +if(NOT MSVC) list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") +endif() # TODO: Move collision detection into separate packages find_package(Bullet 2.87 REQUIRED) @@ -25,6 +29,26 @@ pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") +if(WIN32) +pkg_check_modules(LIBCCD REQUIRED ccd) +find_library(LIBCCD_LIBRARIES_FULL ${LIBCCD_LIBRARIES} ${LIBCCD_LIBRARY_DIRS}) +set(LIBCCD_LIBRARIES "${LIBCCD_LIBRARIES_FULL}") +endif() + +find_package(ASSIMP QUIET) +if(NOT ASSIMP_FOUND) + find_package(PkgConfig REQUIRED) + # assimp is required, so REQUIRE the second attempt + pkg_check_modules(ASSIMP_PC REQUIRED assimp) + set(ASSIMP_INCLUDE_DIRS ${ASSIMP_PC_INCLUDE_DIRS}) +endif() + +# find *absolute* paths to ASSIMP_LIBRARIES +# Both, pkg-config and assimp's cmake-config don't provide an absolute library path. +# For, pkg-config the path is in ASSIMP_PC_LIBRARY_DIRS, for cmake in ASSIMP_LIBRARY_DIRS. +find_library(ASSIMP_ABS_LIBRARIES NAMES ${ASSIMP_LIBRARIES} assimp HINTS ${ASSIMP_LIBRARY_DIRS} ${ASSIMP_PC_LIBRARY_DIRS}) +set(ASSIMP_LIBRARIES "${ASSIMP_ABS_LIBRARIES}") + find_package(angles REQUIRED) find_package(OCTOMAP REQUIRED) find_package(urdfdom REQUIRED) diff --git a/moveit_core/ConfigExtras.cmake b/moveit_core/ConfigExtras.cmake index f208f771f9..28e8451f4f 100644 --- a/moveit_core/ConfigExtras.cmake +++ b/moveit_core/ConfigExtras.cmake @@ -2,7 +2,7 @@ # boost::iostreams on Windows depends on boost::zlib if(WIN32) - set(EXTRA_BOOST_COMPONENTS zlib) +# set(EXTRA_BOOST_COMPONENTS zlib) endif() find_package(Boost REQUIRED chrono diff --git a/moveit_core/background_processing/CMakeLists.txt b/moveit_core/background_processing/CMakeLists.txt index f341c44af0..23b757bd54 100644 --- a/moveit_core/background_processing/CMakeLists.txt +++ b/moveit_core/background_processing/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_background_processing) add_library(${MOVEIT_LIB_NAME} SHARED src/background_processing.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} Boost rclcpp diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index a914eafb36..66a0b7444a 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -12,6 +12,14 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "COLLISION_DETECTION_BUILDING_LIBRARY") + + ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation 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..a23bcb8afb 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 @@ -38,6 +38,7 @@ #include #include +#include namespace collision_detection { @@ -46,6 +47,6 @@ class CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_env_allvalid.cpp + COLLISION_DETECTION_PUBLIC static const std::string NAME; // defined in collision_env_allvalid.cpp }; } // namespace collision_detection diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 799d90cf10..10b115bc47 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -37,6 +37,7 @@ #include #include #include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.hpp new file mode 100644 index 0000000000..852437ab3f --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COLLISION_DETECTION__VISIBILITY_CONTROL_HPP_ +#define COLLISION_DETECTION__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define COLLISION_DETECTION_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_BUILDING_LIBRARY + #define COLLISION_DETECTION_PUBLIC COLLISION_DETECTION_EXPORT + #else + #define COLLISION_DETECTION_PUBLIC COLLISION_DETECTION_IMPORT + #endif + #define COLLISION_DETECTION_PUBLIC_TYPE COLLISION_DETECTION_PUBLIC + #define COLLISION_DETECTION_LOCAL +#else + #define COLLISION_DETECTION_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_PUBLIC + #define COLLISION_DETECTION_LOCAL + #endif + #define COLLISION_DETECTION_PUBLIC_TYPE +#endif + +#endif // COLLISION_DETECTION__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index 27fbd79504..a9373aeef9 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -10,6 +10,7 @@ add_library(${MOVEIT_LIB_NAME} src/bullet_integration/ros_bullet_utils.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp @@ -58,16 +59,25 @@ 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(NOT WIN32) + # 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) + 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(NOT WIN32) + # 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) + 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(NOT WIN32) + # 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) + endif() endif() diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index b6a6b839f6..49cebde599 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -5,6 +5,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/collision_env_fcl.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation @@ -12,6 +13,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdfdom urdfdom_headers LIBFCL + LIBCCD Boost visualization_msgs ) @@ -19,8 +21,20 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_collision_detection ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "COLLISION_DETECTION_FCL_BUILDING_LIBRARY") + add_library(collision_detector_fcl_plugin SHARED src/collision_detector_fcl_plugin_loader.cpp) set_target_properties(collision_detector_fcl_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(collision_detector_fcl_plugin PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(collision_detector_fcl_plugin + PRIVATE "COLLISION_DETECTION_FCL_PLUGIN_BUILDING_LIBRARY") + + ament_target_dependencies(collision_detector_fcl_plugin rclcpp urdf @@ -47,11 +61,16 @@ 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 (NOT WIN32) + # 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) + 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 (NOT WIN32) + # 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) + endif() endif() diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 06063332e5..dfb32834b8 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -41,6 +41,7 @@ #include #include #include +#include #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) #include 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..6c8389ef7f 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 @@ -38,11 +38,12 @@ #include #include +#include namespace collision_detection { /** \brief An allocator for FCL collision detectors */ -class CollisionDetectorAllocatorFCL +class COLLISION_DETECTION_FCL_PUBLIC CollisionDetectorAllocatorFCL : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 0a967b90fc..c1decc0041 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -38,10 +38,11 @@ #include #include +#include namespace collision_detection { -class CollisionDetectorFCLPluginLoader : public CollisionPlugin +class COLLISION_DETECTION_FCL_PLUGIN_PUBLIC CollisionDetectorFCLPluginLoader : public CollisionPlugin { public: bool initialize(const planning_scene::PlanningScenePtr& scene) const override; diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.hpp b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.hpp new file mode 100644 index 0000000000..28ca4870b7 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.hpp @@ -0,0 +1,98 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_HPP_ +#define COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define COLLISION_DETECTION_FCL_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_FCL_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_FCL_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_FCL_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_FCL_BUILDING_LIBRARY + #define COLLISION_DETECTION_FCL_PUBLIC COLLISION_DETECTION_FCL_EXPORT + #else + #define COLLISION_DETECTION_FCL_PUBLIC COLLISION_DETECTION_FCL_IMPORT + #endif + #define COLLISION_DETECTION_FCL_PUBLIC_TYPE COLLISION_DETECTION_FCL_PUBLIC + #define COLLISION_DETECTION_FCL_LOCAL +#else + #define COLLISION_DETECTION_FCL_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_FCL_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_FCL_PUBLIC + #define COLLISION_DETECTION_FCL_LOCAL + #endif + #define COLLISION_DETECTION_FCL_PUBLIC_TYPE +#endif + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define COLLISION_DETECTION_FCL_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_FCL_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_FCL_PLUGIN_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_FCL_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_FCL_PLUGIN_BUILDING_LIBRARY + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC COLLISION_DETECTION_FCL_PLUGIN_EXPORT + #else + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC COLLISION_DETECTION_FCL_PLUGIN_IMPORT + #endif + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC_TYPE COLLISION_DETECTION_FCL_PLUGIN_PUBLIC + #define COLLISION_DETECTION_FCL_PLUGIN_LOCAL +#else + #define COLLISION_DETECTION_FCL_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC + #define COLLISION_DETECTION_FCL_PLUGIN_LOCAL + #endif + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC_TYPE +#endif + +#endif // COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/collision_distance_field/CMakeLists.txt b/moveit_core/collision_distance_field/CMakeLists.txt index 5640978639..9f5f8be14d 100644 --- a/moveit_core/collision_distance_field/CMakeLists.txt +++ b/moveit_core/collision_distance_field/CMakeLists.txt @@ -7,6 +7,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/collision_env_hybrid.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} urdf diff --git a/moveit_core/constraint_samplers/CMakeLists.txt b/moveit_core/constraint_samplers/CMakeLists.txt index 370267389f..fdd5510622 100644 --- a/moveit_core/constraint_samplers/CMakeLists.txt +++ b/moveit_core/constraint_samplers/CMakeLists.txt @@ -8,6 +8,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/union_constraint_sampler.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom 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..5d2b716cc5 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,8 @@ #include #include #include +#include +#include #include #include "pr2_arm_kinematics_plugin.h" @@ -240,7 +242,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/distance_field/CMakeLists.txt b/moveit_core/distance_field/CMakeLists.txt index 0f4e5dd710..4fc58485d7 100644 --- a/moveit_core/distance_field/CMakeLists.txt +++ b/moveit_core/distance_field/CMakeLists.txt @@ -7,6 +7,8 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + ament_target_dependencies(${MOVEIT_LIB_NAME} Boost urdfdom diff --git a/moveit_core/dynamics_solver/CMakeLists.txt b/moveit_core/dynamics_solver/CMakeLists.txt index d8ac1f4ebb..eeb09b3aae 100644 --- a/moveit_core/dynamics_solver/CMakeLists.txt +++ b/moveit_core/dynamics_solver/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_dynamics_solver) add_library(${MOVEIT_LIB_NAME} SHARED src/dynamics_solver.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} urdf diff --git a/moveit_core/exceptions/CMakeLists.txt b/moveit_core/exceptions/CMakeLists.txt index 2976afd3f1..875a7ff02a 100644 --- a/moveit_core/exceptions/CMakeLists.txt +++ b/moveit_core/exceptions/CMakeLists.txt @@ -1,8 +1,15 @@ set(MOVEIT_LIB_NAME moveit_exceptions) add_library(${MOVEIT_LIB_NAME} SHARED src/exceptions.cpp) -set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -ament_target_dependencies(${MOVEIT_LIB_NAME} + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_CORE_BUILDING_LIBRARY") + + set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") + set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + ament_target_dependencies(${MOVEIT_LIB_NAME} Boost rclcpp urdfdom diff --git a/moveit_core/kinematic_constraints/CMakeLists.txt b/moveit_core/kinematic_constraints/CMakeLists.txt index 8d4a7201f3..b0efbe5c9c 100644 --- a/moveit_core/kinematic_constraints/CMakeLists.txt +++ b/moveit_core/kinematic_constraints/CMakeLists.txt @@ -12,6 +12,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} urdf @@ -33,14 +34,19 @@ target_link_libraries(${MOVEIT_LIB_NAME} install(DIRECTORY include/ DESTINATION include) +if(NOT MSVC) +# reenable once https://github.com/ros2/geometry2/pull/427 is in distribution + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(test_constraints test/test_constraints.cpp APPEND_LIBRARY_DIRS "${append_library_dirs}" ) + target_link_libraries(test_constraints moveit_test_utils ${MOVEIT_LIB_NAME}) ament_add_gtest(test_orientation_constraints test/test_orientation_constraints.cpp) target_link_libraries(test_orientation_constraints moveit_test_utils ${MOVEIT_LIB_NAME}) endif() +endif() \ No newline at end of file diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index ef52feff78..af68bd2de8 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -3,8 +3,14 @@ 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}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) -# This line is needed to ensure that messages are done being built before this is built +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "KINEMATICS_BASE_BUILDING_LIBRARY") + + # This line is needed to ensure that messages are done being built before this is built ament_target_dependencies( ${MOVEIT_LIB_NAME} rclcpp 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 9f55085f61..158e710d47 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 @@ -39,6 +39,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" #include #include @@ -140,7 +141,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase) // Defines KinematicsBasePtr, ConstPtr, We * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class KinematicsBase +class KINEMATICS_BASE_PUBLIC KinematicsBase { public: static const rclcpp::Logger LOGGER; diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.hpp b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.hpp new file mode 100644 index 0000000000..0624e858b7 --- /dev/null +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.hpp @@ -0,0 +1,98 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef KINEMATICS_BASE__VISIBILITY_CONTROL_HPP_ +#define KINEMATICS_BASE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define KINEMATICS_BASE_EXPORT __attribute__ ((dllexport)) + #define KINEMATICS_BASE_IMPORT __attribute__ ((dllimport)) + #else + #define KINEMATICS_BASE_EXPORT __declspec(dllexport) + #define KINEMATICS_BASE_IMPORT __declspec(dllimport) + #endif + #ifdef KINEMATICS_BASE_BUILDING_LIBRARY + #define KINEMATICS_BASE_PUBLIC KINEMATICS_BASE_EXPORT + #else + #define KINEMATICS_BASE_PUBLIC KINEMATICS_BASE_IMPORT + #endif + #define KINEMATICS_BASE_PUBLIC_TYPE KINEMATICS_BASE_PUBLIC + #define KINEMATICS_BASE_LOCAL +#else + #define KINEMATICS_BASE_EXPORT __attribute__ ((visibility("default"))) + #define KINEMATICS_BASE_IMPORT + #if __GNUC__ >= 4 + #define KINEMATICS_BASE_PUBLIC __attribute__ ((visibility("default"))) + #define KINEMATICS_BASE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define KINEMATICS_BASE_PUBLIC + #define KINEMATICS_BASE_LOCAL + #endif + #define KINEMATICS_BASE_PUBLIC_TYPE +#endif + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define KINEMATICS_BASE_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define KINEMATICS_BASE_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define KINEMATICS_BASE_PLUGIN_EXPORT __declspec(dllexport) + #define KINEMATICS_BASE_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef KINEMATICS_BASE_PLUGIN_BUILDING_LIBRARY + #define KINEMATICS_BASE_PLUGIN_PUBLIC KINEMATICS_BASE_PLUGIN_EXPORT + #else + #define KINEMATICS_BASE_PLUGIN_PUBLIC KINEMATICS_BASE_PLUGIN_IMPORT + #endif + #define KINEMATICS_BASE_PLUGIN_PUBLIC_TYPE KINEMATICS_BASE_PLUGIN_PUBLIC + #define KINEMATICS_BASE_PLUGIN_LOCAL +#else + #define KINEMATICS_BASE_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define KINEMATICS_BASE_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define KINEMATICS_BASE_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define KINEMATICS_BASE_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define KINEMATICS_BASE_PLUGIN_PUBLIC + #define KINEMATICS_BASE_PLUGIN_LOCAL + #endif + #define KINEMATICS_BASE_PLUGIN_PUBLIC_TYPE +#endif + +#endif // KINEMATICS_BASE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/kinematics_metrics/CMakeLists.txt b/moveit_core/kinematics_metrics/CMakeLists.txt index 8f23eef19c..f630eca11d 100644 --- a/moveit_core/kinematics_metrics/CMakeLists.txt +++ b/moveit_core/kinematics_metrics/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_kinematics_metrics) add_library(${MOVEIT_LIB_NAME} SHARED src/kinematics_metrics.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} urdf diff --git a/moveit_core/package.xml b/moveit_core/package.xml index b8e9456950..d820c74256 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -51,6 +51,7 @@ tf2_geometry_msgs trajectory_msgs visualization_msgs + pluginlib moveit_resources_panda_moveit_config moveit_resources_pr2_description diff --git a/moveit_core/planning_interface/CMakeLists.txt b/moveit_core/planning_interface/CMakeLists.txt index 46728f63b2..22bbb32ceb 100644 --- a/moveit_core/planning_interface/CMakeLists.txt +++ b/moveit_core/planning_interface/CMakeLists.txt @@ -5,6 +5,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/planning_response.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_msgs urdf diff --git a/moveit_core/planning_request_adapter/CMakeLists.txt b/moveit_core/planning_request_adapter/CMakeLists.txt index 2dbb50caa2..76427b91d3 100644 --- a/moveit_core/planning_request_adapter/CMakeLists.txt +++ b/moveit_core/planning_request_adapter/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_planning_request_adapter) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_request_adapter.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index fc1f7d788f..931b984ac4 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -3,7 +3,12 @@ set(MOVEIT_LIB_NAME moveit_planning_scene) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_scene.cpp) #TODO: Fix the versioning set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -ament_target_dependencies(${MOVEIT_LIB_NAME} +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "PLANNING_SCENE_BUILDING_LIBRARY") + + ament_target_dependencies(${MOVEIT_LIB_NAME} Boost rclcpp urdfdom @@ -12,6 +17,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} OCTOMAP ) +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_model moveit_robot_state 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 d499a6e7be..f6b37d06ae 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 @@ -46,6 +46,7 @@ #include #include #include +#include #include #include #include @@ -99,8 +100,8 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model, const collision_detection::WorldPtr& world = collision_detection::WorldPtr(new collision_detection::World())); - static const std::string OCTOMAP_NS; - static const std::string DEFAULT_SCENE_NAME; + PLANNING_SCENE_PUBLIC static const std::string OCTOMAP_NS; + PLANNING_SCENE_PUBLIC static const std::string DEFAULT_SCENE_NAME; ~PlanningScene(); @@ -233,6 +234,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from */ /**@{*/ + PLANNING_SCENE_PUBLIC const std::string getCollisionDetectorName() const { // If no collision detector is allocated, return an empty string diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.hpp new file mode 100644 index 0000000000..5294b1b6cd --- /dev/null +++ b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.hpp @@ -0,0 +1,98 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_SCENE__VISIBILITY_CONTROL_HPP_ +#define PLANNING_SCENE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_BUILDING_LIBRARY + #define PLANNING_SCENE_PUBLIC PLANNING_SCENE_EXPORT + #else + #define PLANNING_SCENE_PUBLIC PLANNING_SCENE_IMPORT + #endif + #define PLANNING_SCENE_PUBLIC_TYPE PLANNING_SCENE_PUBLIC + #define PLANNING_SCENE_LOCAL +#else + #define PLANNING_SCENE_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_PUBLIC + #define PLANNING_SCENE_LOCAL + #endif + #define PLANNING_SCENE_PUBLIC_TYPE +#endif + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_PLUGIN_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_PLUGIN_BUILDING_LIBRARY + #define PLANNING_SCENE_PLUGIN_PUBLIC PLANNING_SCENE_PLUGIN_EXPORT + #else + #define PLANNING_SCENE_PLUGIN_PUBLIC PLANNING_SCENE_PLUGIN_IMPORT + #endif + #define PLANNING_SCENE_PLUGIN_PUBLIC_TYPE PLANNING_SCENE_PLUGIN_PUBLIC + #define PLANNING_SCENE_PLUGIN_LOCAL +#else + #define PLANNING_SCENE_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_PLUGIN_PUBLIC + #define PLANNING_SCENE_PLUGIN_LOCAL + #endif + #define PLANNING_SCENE_PLUGIN_PUBLIC_TYPE +#endif + +#endif // PLANNING_SCENE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/profiler/CMakeLists.txt b/moveit_core/profiler/CMakeLists.txt index 2953acbf01..042dc5a1e4 100644 --- a/moveit_core/profiler/CMakeLists.txt +++ b/moveit_core/profiler/CMakeLists.txt @@ -2,6 +2,13 @@ set(MOVEIT_LIB_NAME moveit_profiler) add_library(${MOVEIT_LIB_NAME} SHARED src/profiler.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_CORE_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation diff --git a/moveit_core/robot_model/CMakeLists.txt b/moveit_core/robot_model/CMakeLists.txt index 2b0886fb07..b052500fdf 100644 --- a/moveit_core/robot_model/CMakeLists.txt +++ b/moveit_core/robot_model/CMakeLists.txt @@ -14,6 +14,13 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/robot_model.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_CORE_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} angles moveit_msgs @@ -30,6 +37,11 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_kinematics_base ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "ROBOT_MODEL_BUILDING_LIBRARY") + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(test_robot_model test/test.cpp) diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 6a1e6f2fb2..d5dce58622 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -39,6 +39,7 @@ #include #include +#include #include // joint types @@ -61,7 +62,7 @@ MOVEIT_CLASS_FORWARD(RobotModel) // Defines RobotModelPtr, ConstPtr, WeakPtr... /** \brief Definition of a kinematic model. This class is not thread safe, however multiple instances can be created */ -class RobotModel +class ROBOT_MODEL_PUBLIC RobotModel { public: /** \brief Construct a kinematic model from a parsed description and a list of planning groups */ diff --git a/moveit_core/robot_model/include/moveit/robot_model/visibility_control.hpp b/moveit_core/robot_model/include/moveit/robot_model/visibility_control.hpp new file mode 100644 index 0000000000..ada0f68260 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/visibility_control.hpp @@ -0,0 +1,98 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROBOT_MODEL__VISIBILITY_CONTROL_HPP_ +#define ROBOT_MODEL__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_MODEL_EXPORT __attribute__ ((dllexport)) + #define ROBOT_MODEL_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_MODEL_EXPORT __declspec(dllexport) + #define ROBOT_MODEL_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_MODEL_BUILDING_LIBRARY + #define ROBOT_MODEL_PUBLIC ROBOT_MODEL_EXPORT + #else + #define ROBOT_MODEL_PUBLIC ROBOT_MODEL_IMPORT + #endif + #define ROBOT_MODEL_PUBLIC_TYPE ROBOT_MODEL_PUBLIC + #define ROBOT_MODEL_LOCAL +#else + #define ROBOT_MODEL_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_MODEL_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_MODEL_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_MODEL_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_MODEL_PUBLIC + #define ROBOT_MODEL_LOCAL + #endif + #define ROBOT_MODEL_PUBLIC_TYPE +#endif + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_MODEL_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define ROBOT_MODEL_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_MODEL_PLUGIN_EXPORT __declspec(dllexport) + #define ROBOT_MODEL_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_MODEL_PLUGIN_BUILDING_LIBRARY + #define ROBOT_MODEL_PLUGIN_PUBLIC ROBOT_MODEL_PLUGIN_EXPORT + #else + #define ROBOT_MODEL_PLUGIN_PUBLIC ROBOT_MODEL_PLUGIN_IMPORT + #endif + #define ROBOT_MODEL_PLUGIN_PUBLIC_TYPE ROBOT_MODEL_PLUGIN_PUBLIC + #define ROBOT_MODEL_PLUGIN_LOCAL +#else + #define ROBOT_MODEL_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_MODEL_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_MODEL_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_MODEL_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_MODEL_PLUGIN_PUBLIC + #define ROBOT_MODEL_PLUGIN_LOCAL + #endif + #define ROBOT_MODEL_PLUGIN_PUBLIC_TYPE +#endif + +#endif // ROBOT_MODEL__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/robot_model/src/revolute_joint_model.cpp b/moveit_core/robot_model/src/revolute_joint_model.cpp index f3c066e0ba..11651cd597 100644 --- a/moveit_core/robot_model/src/revolute_joint_model.cpp +++ b/moveit_core/robot_model/src/revolute_joint_model.cpp @@ -34,6 +34,7 @@ *********************************************************************/ /* Author: Ioan Sucan */ +#define _USE_MATH_DEFINES #include #include diff --git a/moveit_core/robot_state/CMakeLists.txt b/moveit_core/robot_state/CMakeLists.txt index 789926e82f..892fa94637 100644 --- a/moveit_core/robot_state/CMakeLists.txt +++ b/moveit_core/robot_state/CMakeLists.txt @@ -12,6 +12,11 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/cartesian_interpolator.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "ROBOT_STATE_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} urdf tf2_geometry_msgs @@ -34,7 +39,7 @@ if(BUILD_TESTING) find_package(resource_retriever REQUIRED) if(WIN32) - # TODO add windows paths + add_compile_definitions(_USE_MATH_DEFINES /wd4251 /wd4068 /wd4275) else() set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../utils") endif() diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 84d2a070e7..f4cb64c293 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -86,7 +87,7 @@ typedef boost::function= 4 + #define ROBOT_STATE_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_STATE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_STATE_PUBLIC + #define ROBOT_STATE_LOCAL + #endif + #define ROBOT_STATE_PUBLIC_TYPE +#endif + +#endif // ROBOT_STATE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/robot_trajectory/CMakeLists.txt b/moveit_core/robot_trajectory/CMakeLists.txt index b0c07c0896..17208c3500 100644 --- a/moveit_core/robot_trajectory/CMakeLists.txt +++ b/moveit_core/robot_trajectory/CMakeLists.txt @@ -2,6 +2,11 @@ set(MOVEIT_LIB_NAME moveit_robot_trajectory) add_library(${MOVEIT_LIB_NAME} SHARED src/robot_trajectory.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "ROBOT_TRAJECTORY_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp urdfdom diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index f5168b7fe8..7a48ce0abe 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -37,6 +37,7 @@ #pragma once #include +#include #include #include #include @@ -55,7 +56,7 @@ MOVEIT_CLASS_FORWARD(RobotTrajectory) // Defines RobotTrajectoryPtr, ConstPtr, /** \brief Maintain a sequence of waypoints and the time durations between these waypoints */ -class RobotTrajectory +class ROBOT_TRAJECTORY_PUBLIC RobotTrajectory { public: RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group); diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/visibility_control.hpp b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/visibility_control.hpp new file mode 100644 index 0000000000..b1f1133032 --- /dev/null +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROBOT_TRAJECTORY__VISIBILITY_CONTROL_HPP_ +#define ROBOT_TRAJECTORY__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_TRAJECTORY_EXPORT __attribute__ ((dllexport)) + #define ROBOT_TRAJECTORY_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_TRAJECTORY_EXPORT __declspec(dllexport) + #define ROBOT_TRAJECTORY_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_TRAJECTORY_BUILDING_LIBRARY + #define ROBOT_TRAJECTORY_PUBLIC ROBOT_TRAJECTORY_EXPORT + #else + #define ROBOT_TRAJECTORY_PUBLIC ROBOT_TRAJECTORY_IMPORT + #endif + #define ROBOT_TRAJECTORY_PUBLIC_TYPE ROBOT_TRAJECTORY_PUBLIC + #define ROBOT_TRAJECTORY_LOCAL +#else + #define ROBOT_TRAJECTORY_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_TRAJECTORY_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_TRAJECTORY_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_TRAJECTORY_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_TRAJECTORY_PUBLIC + #define ROBOT_TRAJECTORY_LOCAL + #endif + #define ROBOT_TRAJECTORY_PUBLIC_TYPE +#endif + +#endif // ROBOT_TRAJECTORY__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/trajectory_processing/CMakeLists.txt b/moveit_core/trajectory_processing/CMakeLists.txt index 5a62f8d0ff..f7c03a1dc3 100644 --- a/moveit_core/trajectory_processing/CMakeLists.txt +++ b/moveit_core/trajectory_processing/CMakeLists.txt @@ -8,6 +8,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 0ee4d13f41..3a19de41aa 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -37,6 +37,7 @@ */ #pragma once +#define _USE_MATH_DEFINES #include #include diff --git a/moveit_core/transforms/CMakeLists.txt b/moveit_core/transforms/CMakeLists.txt index 028c9fee6a..52f23b2e42 100644 --- a/moveit_core/transforms/CMakeLists.txt +++ b/moveit_core/transforms/CMakeLists.txt @@ -2,6 +2,12 @@ set(MOVEIT_LIB_NAME moveit_transforms) add_library(${MOVEIT_LIB_NAME} SHARED src/transforms.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_CORE_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} geometric_shapes tf2_eigen diff --git a/moveit_core/utils/CMakeLists.txt b/moveit_core/utils/CMakeLists.txt index f94540da35..e936efd3a5 100644 --- a/moveit_core/utils/CMakeLists.txt +++ b/moveit_core/utils/CMakeLists.txt @@ -1,6 +1,6 @@ set(MOVEIT_LIB_NAME moveit_utils) -add_library(${MOVEIT_LIB_NAME} SHARED +add_library(${MOVEIT_LIB_NAME} src/lexical_casts.cpp src/message_checks.cpp src/rclcpp_utils.cpp @@ -10,7 +10,6 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V 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) diff --git a/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt b/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt index 3e79756021..c59f935966 100644 --- a/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt +++ b/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt @@ -9,13 +9,18 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wpedantic) endif() +if (WIN32) + add_compile_options(/wd4251 /wd4068 /wd4275) +endif() + + # find dependencies find_package(ament_cmake REQUIRED) find_package(moveit_common REQUIRED) find_package(moveit_ros_planning_interface REQUIRED) # This shouldn't be necessary (required by moveit_simple_controller_manager) find_package(rosidl_default_runtime REQUIRED) -find_package(Boost REQUIRED COMPONENTS system) +find_package(Boost REQUIRED COMPONENTS system thread) # uncomment the following section in order to fill in # further dependencies manually. # find_package( REQUIRED) diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt index 5500762e58..f50926a584 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt @@ -4,6 +4,7 @@ add_library(${MOVEIT_LIB_NAME} src/kinematics_cache.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) # This line is needed to ensure that messages are done being built before this is built add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) diff --git a/moveit_kinematics/CMakeLists.txt b/moveit_kinematics/CMakeLists.txt index 499c487387..63a934ae17 100644 --- a/moveit_kinematics/CMakeLists.txt +++ b/moveit_kinematics/CMakeLists.txt @@ -6,6 +6,7 @@ find_package(moveit_common REQUIRED) moveit_package() find_package(ament_cmake REQUIRED) +find_package(Boost REQUIRED program_options system filesystem regex) find_package(Eigen3 REQUIRED) find_package(orocos_kdl REQUIRED) find_package(tf2_kdl REQUIRED) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt index 9263b4aabc..c9957076d7 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt @@ -6,6 +6,7 @@ find_package(Boost COMPONENTS filesystem program_options REQUIRED) set(MOVEIT_LIB_NAME moveit_cached_ik_kinematics_base) add_library(${MOVEIT_LIB_NAME} SHARED src/ik_cache.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_core @@ -20,6 +21,7 @@ endif() set(MOVEIT_LIB_NAME moveit_cached_ik_kinematics_plugin) add_library(${MOVEIT_LIB_NAME} SHARED src/cached_ik_kinematics_plugin.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_core @@ -42,6 +44,7 @@ if(ur_kinematics_FOUND) set(MOVEIT_LIB_NAME moveit_cached_ur${UR}_kinematics_plugin) add_library(${MOVEIT_LIB_NAME} SHARED src/cached_ur_kinematics_plugin.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") + set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) find_library(ur${UR}_pluginlib ur${UR}_moveit_plugin PATHS ${ur_kinematics_LIBRARY_DIRS}) target_link_libraries(${MOVEIT_LIB_NAME} moveit_cached_ik_kinematics_base diff --git a/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt index 603c7db8dc..8b49bacd21 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt @@ -4,6 +4,8 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/kdl_kinematics_plugin.cpp src/chainiksolver_vel_mimic_svd.cpp) +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp random_numbers diff --git a/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt index b87660d903..4097ca177e 100644 --- a/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_lma_kinematics_plugin) add_library(${MOVEIT_LIB_NAME} SHARED src/lma_kinematics_plugin.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp diff --git a/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt index c790f343c1..a9e009036d 100644 --- a/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_srv_kinematics_plugin) add_library(${MOVEIT_LIB_NAME} SHARED src/srv_kinematics_plugin.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp diff --git a/moveit_planners/ompl/ompl_interface/CMakeLists.txt b/moveit_planners/ompl/ompl_interface/CMakeLists.txt index e545afaf9b..f145d9f567 100644 --- a/moveit_planners/ompl/ompl_interface/CMakeLists.txt +++ b/moveit_planners/ompl/ompl_interface/CMakeLists.txt @@ -23,6 +23,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/detail/constrained_goal_sampler.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) find_package(OpenMP REQUIRED) diff --git a/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp b/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp index ea8a551d7e..e0e315ad65 100644 --- a/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp +++ b/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp @@ -84,17 +84,17 @@ struct GenerateStateDatabaseParameters node->get_parameter_or("use_current_scene", use_current_scene, false); // number of states in joint space approximation - get_uint_parameter_or(node, "state_cnt", construction_opts.samples, 10000); + get_uint_parameter_or(node, "state_cnt", static_cast(construction_opts.samples), 10000); // generate edges together with states? - get_uint_parameter_or(node, "edges_per_sample", construction_opts.edges_per_sample, 0); + get_uint_parameter_or(node, "edges_per_sample", static_cast(construction_opts.edges_per_sample), 0); node->get_parameter_or("max_edge_length", construction_opts.max_edge_length, 0.2); // verify constraint validity on edges node->get_parameter_or("explicit_motions", construction_opts.explicit_motions, true); node->get_parameter_or("explicit_points_resolution", construction_opts.explicit_points_resolution, 0.05); - get_uint_parameter_or(node, "max_explicit_points", construction_opts.max_explicit_points, 200); + get_uint_parameter_or(node, "max_explicit_points", static_cast(construction_opts.max_explicit_points), 200); // local planning in JointModel state space node->get_parameter_or("state_space_parameterization", construction_opts.state_space_parameterization, diff --git a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt index fd62da5acf..603e20344f 100644 --- a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt +++ b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt @@ -33,6 +33,7 @@ add_library(${PROJECT_NAME} SHARED ) set_target_properties(${PROJECT_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${PROJECT_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS} diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index e551b8e5c2..70b853ace4 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -37,6 +37,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/BenchmarkExecutor.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS} ) diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index bbd774a25c..96d34fee3a 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -53,6 +53,7 @@ #include #else #include +#undef max #endif using namespace moveit_ros_benchmarks; diff --git a/moveit_ros/manipulation/pick_place/CMakeLists.txt b/moveit_ros/manipulation/pick_place/CMakeLists.txt index c2e8edc6ee..f08975db69 100644 --- a/moveit_ros/manipulation/pick_place/CMakeLists.txt +++ b/moveit_ros/manipulation/pick_place/CMakeLists.txt @@ -12,6 +12,11 @@ add_library(${MOVEIT_LIB_NAME} ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_PICK_PLACE_PLANNER_BUILDING_LIBRARY") + target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h index 1e171c8f8b..a5dcd35df2 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -113,11 +114,11 @@ class PlacePlan : public PickPlacePlanBase class PickPlace : private boost::noncopyable, public std::enable_shared_from_this { public: - static const std::string DISPLAY_PATH_TOPIC; - static const std::string DISPLAY_GRASP_TOPIC; + MOVEIT_PICK_PLACE_PLANNER_PUBLIC static const std::string DISPLAY_PATH_TOPIC; + MOVEIT_PICK_PLACE_PLANNER_PUBLIC static const std::string DISPLAY_GRASP_TOPIC; // the amount of time (maximum) to wait for achieving a grasp posture - static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION; // seconds + MOVEIT_PICK_PLACE_PLANNER_PUBLIC static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION; // seconds PickPlace(const planning_pipeline::PlanningPipelinePtr& planning_pipeline); diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/visibility_control.hpp b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/visibility_control.hpp new file mode 100644 index 0000000000..0e634a9c94 --- /dev/null +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVEIT_PICK_PLACE_PLANNER__VISIBILITY_CONTROL_HPP_ +#define MOVEIT_PICK_PLACE_PLANNER__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVEIT_PICK_PLACE_PLANNER_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_PICK_PLACE_PLANNER_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_PICK_PLACE_PLANNER_EXPORT __declspec(dllexport) + #define MOVEIT_PICK_PLACE_PLANNER_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_PICK_PLACE_PLANNER_BUILDING_LIBRARY + #define MOVEIT_PICK_PLACE_PLANNER_PUBLIC MOVEIT_PICK_PLACE_PLANNER_EXPORT + #else + #define MOVEIT_PICK_PLACE_PLANNER_PUBLIC MOVEIT_PICK_PLACE_PLANNER_IMPORT + #endif + #define MOVEIT_PICK_PLACE_PLANNER_PUBLIC_TYPE MOVEIT_PICK_PLACE_PLANNER_PUBLIC + #define MOVEIT_PICK_PLACE_PLANNER_LOCAL +#else + #define MOVEIT_PICK_PLACE_PLANNER_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_PICK_PLACE_PLANNER_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_PICK_PLACE_PLANNER_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_PICK_PLACE_PLANNER_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_PICK_PLACE_PLANNER_PUBLIC + #define MOVEIT_PICK_PLACE_PLANNER_LOCAL + #endif + #define MOVEIT_PICK_PLACE_PLANNER_PUBLIC_TYPE +#endif + +#endif // MOVEIT_PICK_PLACE_PLANNER__VISIBILITY_CONTROL_HPP_ \ No newline at end of file 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 c020749db9..98772d8fa5 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h @@ -321,7 +321,7 @@ class ServoCalcs const int gazebo_redundant_message_count_ = 30; - uint num_joints_; + uint32_t 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/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index 416145e2b4..753b8fb4e3 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -48,6 +48,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/occupancy_map_updater.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS} ) diff --git a/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt b/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt index 0146061207..fa3fb8b94d 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt +++ b/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_depth_image_octomap_updater) add_library(${MOVEIT_LIB_NAME}_core SHARED src/depth_image_octomap_updater.cpp) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME}_core rclcpp moveit_core @@ -17,6 +18,7 @@ target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_lazy_free_space_updater mov add_library(${MOVEIT_LIB_NAME} SHARED src/updater_plugin.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_core 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 4fb7b83ce2..b75ceda77d 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 @@ -120,7 +120,7 @@ bool DepthImageOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node) mesh_filter_->setShadowThreshold(shadow_threshold_); mesh_filter_->setPaddingOffset(padding_offset_); mesh_filter_->setPaddingScale(padding_scale_); - mesh_filter_->setTransformCallback(boost::bind(&DepthImageOctomapUpdater::getShapeTransform, this, _1, _2)); + mesh_filter_->setTransformCallback(boost::bind(&DepthImageOctomapUpdater::getShapeTransform, this, boost::placeholders::_1, boost::placeholders::_2)); // init rclcpp time default value last_update_time_ = node_->now(); @@ -141,7 +141,7 @@ void DepthImageOctomapUpdater::start() pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera("filtered_label", 1); sub_depth_image_ = image_transport::create_camera_subscription( - node_.get(), image_topic_, boost::bind(&DepthImageOctomapUpdater::depthImageCallback, this, _1, _2), "raw", + node_.get(), image_topic_, boost::bind(&DepthImageOctomapUpdater::depthImageCallback, this, boost::placeholders::_1, boost::placeholders::_2), "raw", custom_qos); } diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 0fcee736f9..b3ac3ae0a1 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -8,6 +8,13 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/gl_mesh.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MESH_FILTER_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_core @@ -15,7 +22,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} Eigen3 Boost ) -target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} GLUT::GLUT ${GLEW_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} GLUT::GLUT GLEW::glew) # TODO: enable testing # if(CATKIN_ENABLE_TESTING) 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..89ba6a721f 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 @@ -38,6 +38,7 @@ #include #include +#include namespace mesh_filter { @@ -45,7 +46,7 @@ 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 MESH_FILTER_PUBLIC StereoCameraModel : public SensorModel { public: /** diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.hpp b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.hpp new file mode 100644 index 0000000000..577895943c --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MESH_FILTER__VISIBILITY_CONTROL_HPP_ +#define MESH_FILTER__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MESH_FILTER_EXPORT __attribute__ ((dllexport)) + #define MESH_FILTER_IMPORT __attribute__ ((dllimport)) + #else + #define MESH_FILTER_EXPORT __declspec(dllexport) + #define MESH_FILTER_IMPORT __declspec(dllimport) + #endif + #ifdef MESH_FILTER_BUILDING_LIBRARY + #define MESH_FILTER_PUBLIC MESH_FILTER_EXPORT + #else + #define MESH_FILTER_PUBLIC MESH_FILTER_IMPORT + #endif + #define MESH_FILTER_PUBLIC_TYPE MESH_FILTER_PUBLIC + #define MESH_FILTER_LOCAL +#else + #define MESH_FILTER_EXPORT __attribute__ ((visibility("default"))) + #define MESH_FILTER_IMPORT + #if __GNUC__ >= 4 + #define MESH_FILTER_PUBLIC __attribute__ ((visibility("default"))) + #define MESH_FILTER_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MESH_FILTER_PUBLIC + #define MESH_FILTER_LOCAL + #endif + #define MESH_FILTER_PUBLIC_TYPE +#endif + +#endif // MESH_FILTER__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index 15d91e1366..ff8d8d60ae 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -49,6 +49,10 @@ #include #include #include +#ifdef _WIN32 +#undef near +#undef far +#endif using namespace std; 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 6edef43044..6703550216 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 @@ -43,7 +43,7 @@ #include #include #include - +#include #include namespace occupancy_map_monitor @@ -86,7 +86,7 @@ bool PointCloudOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node) tf_buffer_->setCreateTimerInterface(create_timer_interface); tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_)); shape_mask_.reset(new point_containment_filter::ShapeMask()); - shape_mask_->setTransformCallback(boost::bind(&PointCloudOctomapUpdater::getShapeTransform, this, _1, _2)); + shape_mask_->setTransformCallback(boost::bind(&PointCloudOctomapUpdater::getShapeTransform, this, boost::placeholders::_1, boost::placeholders::_2)); last_update_time_ = node_->now(); return true; } @@ -104,13 +104,13 @@ void PointCloudOctomapUpdater::start() { point_cloud_filter_ = new tf2_ros::MessageFilter( *point_cloud_subscriber_, *tf_buffer_, monitor_->getMapFrame(), 5, node_); - point_cloud_filter_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1)); + point_cloud_filter_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, boost::placeholders::_1)); RCLCPP_INFO(LOGGER, "Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(), point_cloud_filter_->getTargetFramesString().c_str()); } else { - point_cloud_subscriber_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1)); + point_cloud_subscriber_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, boost::placeholders::_1)); RCLCPP_INFO(LOGGER, "Listening to '%s'", point_cloud_topic_.c_str()); } } diff --git a/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt b/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt index 50cbd7864f..d0a024ef28 100644 --- a/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt +++ b/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_collision_plugin_loader) add_library(${MOVEIT_LIB_NAME} SHARED src/collision_plugin_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core rclcpp diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt b/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt index bdfffd2384..dba45f3116 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt +++ b/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt @@ -4,6 +4,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/constraint_sampler_manager_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core rclcpp diff --git a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt index ee1b58e883..3454d63aa0 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt +++ b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_kinematics_plugin_loader) add_library(${MOVEIT_LIB_NAME} SHARED src/kinematics_plugin_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp urdf diff --git a/moveit_ros/planning/plan_execution/CMakeLists.txt b/moveit_ros/planning/plan_execution/CMakeLists.txt index dd4b70a38c..3de93c540a 100644 --- a/moveit_ros/planning/plan_execution/CMakeLists.txt +++ b/moveit_ros/planning/plan_execution/CMakeLists.txt @@ -4,6 +4,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/plan_with_sensing.cpp src/plan_execution.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME} moveit_planning_pipeline moveit_planning_scene_monitor diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index cf3c676457..41ab2f398d 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -2,6 +2,12 @@ set(MOVEIT_LIB_NAME moveit_planning_pipeline) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_pipeline.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_PLANNING_PIPELINE_BUILDING_LIBRARY") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core 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 edf3bfa298..4533546346 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 @@ -42,6 +42,7 @@ #include #include #include +#include #include @@ -54,7 +55,7 @@ namespace planning_pipeline planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. */ -class PlanningPipeline +class MOVEIT_PLANNING_PIPELINE_PUBLIC 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_pipeline/include/moveit/planning_pipeline/visibility_control.hpp b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.hpp new file mode 100644 index 0000000000..e995ae2f6b --- /dev/null +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVEIT_PLANNING_PIPELINE__VISIBILITY_CONTROL_HPP_ +#define MOVEIT_PLANNING_PIPELINE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVEIT_PLANNING_PIPELINE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_PLANNING_PIPELINE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_PLANNING_PIPELINE_EXPORT __declspec(dllexport) + #define MOVEIT_PLANNING_PIPELINE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_PLANNING_PIPELINE_BUILDING_LIBRARY + #define MOVEIT_PLANNING_PIPELINE_PUBLIC MOVEIT_PLANNING_PIPELINE_EXPORT + #else + #define MOVEIT_PLANNING_PIPELINE_PUBLIC MOVEIT_PLANNING_PIPELINE_IMPORT + #endif + #define MOVEIT_PLANNING_PIPELINE_PUBLIC_TYPE MOVEIT_PLANNING_PIPELINE_PUBLIC + #define MOVEIT_PLANNING_PIPELINE_LOCAL +#else + #define MOVEIT_PLANNING_PIPELINE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_PIPELINE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_PLANNING_PIPELINE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_PIPELINE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_PLANNING_PIPELINE_PUBLIC + #define MOVEIT_PLANNING_PIPELINE_LOCAL + #endif + #define MOVEIT_PLANNING_PIPELINE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_PLANNING_PIPELINE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt b/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt index d1d66e10c5..d46f141118 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt +++ b/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt @@ -15,6 +15,7 @@ set(SOURCE_FILES add_library(${MOVEIT_LIB_NAME} SHARED ${SOURCE_FILES}) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} Boost moveit_core diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index b72df8876c..24e1ee7d7e 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -6,6 +6,12 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/trajectory_monitor.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "PLANNING_SCENE_MONITOR_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_ros_occupancy_map_monitor message_filters 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 d4a820418f..e73899f686 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 @@ -45,12 +45,15 @@ #include #include #include +#include #include +#include #include #include #include #include #include +#include "visibility_control.hpp" namespace planning_scene_monitor { @@ -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 PLANNING_SCENE_MONITOR_PUBLIC PlanningSceneMonitor : private boost::noncopyable { public: enum SceneUpdateType diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.hpp b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.hpp new file mode 100644 index 0000000000..fc95d46022 --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_HPP_ +#define PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_MONITOR_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_MONITOR_BUILDING_LIBRARY + #define PLANNING_SCENE_MONITOR_PUBLIC PLANNING_SCENE_MONITOR_EXPORT + #else + #define PLANNING_SCENE_MONITOR_PUBLIC PLANNING_SCENE_MONITOR_IMPORT + #endif + #define PLANNING_SCENE_MONITOR_PUBLIC_TYPE PLANNING_SCENE_MONITOR_PUBLIC + #define PLANNING_SCENE_MONITOR_LOCAL +#else + #define PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_MONITOR_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_MONITOR_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_MONITOR_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_MONITOR_PUBLIC + #define PLANNING_SCENE_MONITOR_LOCAL + #endif + #define PLANNING_SCENE_MONITOR_PUBLIC_TYPE +#endif + +#endif // PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning/rdf_loader/CMakeLists.txt b/moveit_ros/planning/rdf_loader/CMakeLists.txt index a78045621c..33046461c9 100644 --- a/moveit_ros/planning/rdf_loader/CMakeLists.txt +++ b/moveit_ros/planning/rdf_loader/CMakeLists.txt @@ -2,6 +2,7 @@ set(MOVEIT_LIB_NAME moveit_rdf_loader) add_library(${MOVEIT_LIB_NAME} SHARED src/rdf_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp ament_index_cpp 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/robot_model_loader/CMakeLists.txt b/moveit_ros/planning/robot_model_loader/CMakeLists.txt index 7ea0234fd2..775b5a6f83 100644 --- a/moveit_ros/planning/robot_model_loader/CMakeLists.txt +++ b/moveit_ros/planning/robot_model_loader/CMakeLists.txt @@ -6,6 +6,7 @@ endif() add_library(${MOVEIT_LIB_NAME} SHARED src/robot_model_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp urdf diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index baf0dca83e..fd2836e585 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -2,6 +2,13 @@ set(MOVEIT_LIB_NAME moveit_trajectory_execution_manager) add_library(${MOVEIT_LIB_NAME} SHARED src/trajectory_execution_manager.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_TRAJECTORY_EXECUTION_MANAGER_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_ros_occupancy_map_monitor 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 e35164c9be..f82ea25537 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 @@ -36,6 +36,7 @@ #pragma once +#include #include #include #include @@ -46,6 +47,7 @@ #include #include #include +#include #include @@ -56,7 +58,7 @@ MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager) // Defines TrajectoryExecution // Two modes: // Managed controllers // Unmanaged controllers: given the trajectory, -class TrajectoryExecutionManager +class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC TrajectoryExecutionManager { public: static const std::string EXECUTION_EVENT_TOPIC; diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.hpp b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.hpp new file mode 100644 index 0000000000..1647a35b4e --- /dev/null +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVEIT_TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_HPP_ +#define MOVEIT_TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT __declspec(dllexport) + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_TRAJECTORY_EXECUTION_MANAGER_BUILDING_LIBRARY + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT + #else + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC MOVEIT_TRAJECTORY_EXECUTION_MANAGER_IMPORT + #endif + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_LOCAL +#else + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_LOCAL + #endif + #define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE +#endif + +#endif // MOVEIT_TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt b/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt index dd0fd34d16..2d864c040c 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt +++ b/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt @@ -1,8 +1,17 @@ set(MOVEIT_LIB_NAME moveit_common_planning_interface_objects) +if (WIN32) + add_compile_options(/wd4251 /wd4068 /wd4275) +endif() + +find_package(Boost REQUIRED COMPONENTS thread) + add_library(${MOVEIT_LIB_NAME} SHARED src/common_objects.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + ament_target_dependencies(${MOVEIT_LIB_NAME} + Boost rclcpp moveit_ros_planning tf2_ros diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index 523d74f259..1f5e327441 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -2,6 +2,12 @@ set(MOVEIT_LIB_NAME moveit_move_group_interface) add_library(${MOVEIT_LIB_NAME} SHARED src/move_group_interface.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVE_GROUP_INTERFACE_BUILDING_LIBRARY") + target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${Boost_THREAD_LIBRARY}) ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core 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 2758f2099b..97e9fde291 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 @@ -56,6 +56,8 @@ #include +#include + #include #include #include @@ -101,7 +103,7 @@ MOVEIT_CLASS_FORWARD(MoveGroupInterface) // Defines MoveGroupInterfacePtr, Cons \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 MOVE_GROUP_INTERFACE_PUBLIC MoveGroupInterface { public: /** \brief Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description' */ diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.hpp b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.hpp new file mode 100644 index 0000000000..da5875e4c9 --- /dev/null +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_HPP_ +#define MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((dllexport)) + #define MOVE_GROUP_INTERFACE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) + #define MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVE_GROUP_INTERFACE_BUILDING_LIBRARY + #define MOVE_GROUP_INTERFACE_PUBLIC MOVE_GROUP_INTERFACE_EXPORT + #else + #define MOVE_GROUP_INTERFACE_PUBLIC MOVE_GROUP_INTERFACE_IMPORT + #endif + #define MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVE_GROUP_INTERFACE_PUBLIC + #define MOVE_GROUP_INTERFACE_LOCAL +#else + #define MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((visibility("default"))) + #define MOVE_GROUP_INTERFACE_IMPORT + #if __GNUC__ >= 4 + #define MOVE_GROUP_INTERFACE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVE_GROUP_INTERFACE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVE_GROUP_INTERFACE_PUBLIC + #define MOVE_GROUP_INTERFACE_LOCAL + #endif + #define MOVE_GROUP_INTERFACE_PUBLIC_TYPE +#endif + +#endif // MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning_interface/moveit_cpp/CMakeLists.txt b/moveit_ros/planning_interface/moveit_cpp/CMakeLists.txt index c2158c0b0a..419a28d023 100644 --- a/moveit_ros/planning_interface/moveit_cpp/CMakeLists.txt +++ b/moveit_ros/planning_interface/moveit_cpp/CMakeLists.txt @@ -1,11 +1,16 @@ set(MOVEIT_LIB_NAME moveit_cpp) +find_package(Boost REQUIRED COMPONENTS thread) + add_library(${MOVEIT_LIB_NAME} SHARED src/moveit_cpp.cpp src/planning_component.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + ament_target_dependencies(${MOVEIT_LIB_NAME} + Boost rclcpp moveit_core moveit_ros_planning diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index 9491f51480..7f3a66fd00 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -36,6 +36,12 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/robot_interaction.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "ROBOT_INTERACTION_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) if(BUILD_TESTING) 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..5674d46e3d 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 @@ -37,6 +37,7 @@ #pragma once #include +#include #include #include @@ -44,7 +45,7 @@ namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class KinematicOptionsMap +class ROBOT_INTERACTION_PUBLIC KinematicOptionsMap { public: /// Constructor - set all options to reasonable default values. diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.hpp b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.hpp new file mode 100644 index 0000000000..8a8f5a099a --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROBOT_INTERACTION__VISIBILITY_CONTROL_HPP_ +#define ROBOT_INTERACTION__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_INTERACTION_EXPORT __attribute__ ((dllexport)) + #define ROBOT_INTERACTION_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_INTERACTION_EXPORT __declspec(dllexport) + #define ROBOT_INTERACTION_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_INTERACTION_BUILDING_LIBRARY + #define ROBOT_INTERACTION_PUBLIC ROBOT_INTERACTION_EXPORT + #else + #define ROBOT_INTERACTION_PUBLIC ROBOT_INTERACTION_IMPORT + #endif + #define ROBOT_INTERACTION_PUBLIC_TYPE ROBOT_INTERACTION_PUBLIC + #define ROBOT_INTERACTION_LOCAL +#else + #define ROBOT_INTERACTION_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_INTERACTION_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_INTERACTION_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_INTERACTION_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_INTERACTION_PUBLIC + #define ROBOT_INTERACTION_LOCAL + #endif + #define ROBOT_INTERACTION_PUBLIC_TYPE +#endif + +#endif // ROBOT_INTERACTION__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt index d93996d6af..73035b769b 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt @@ -31,6 +31,7 @@ set(SOURCE_FILES set(MOVEIT_LIB_NAME moveit_motion_planning_rviz_plugin) add_library(${MOVEIT_LIB_NAME}_core SHARED ${SOURCE_FILES} ${HEADERS} ${UIC_FILES}) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools moveit_planning_scene_rviz_plugin) ament_target_dependencies(${MOVEIT_LIB_NAME}_core Boost @@ -47,6 +48,7 @@ target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/i add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core) ament_target_dependencies(${MOVEIT_LIB_NAME} Boost diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 5b65ecdba6..b5e256e8f7 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -4,6 +4,13 @@ add_library(${MOVEIT_LIB_NAME}_core SHARED src/planning_scene_display.cpp include/moveit/planning_scene_rviz_plugin/planning_scene_display.h) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME}_core + PRIVATE "PLANNING_SCENE_RVIZ_PLUGIN_CORE_BUILDING_LIBRARY") + target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools) ament_target_dependencies(${MOVEIT_LIB_NAME}_core rclcpp @@ -19,6 +26,13 @@ target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/i add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_LIBRARY") + target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core Qt5::Widgets) ament_target_dependencies(${MOVEIT_LIB_NAME} pluginlib 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 7447ab81bb..c8a539e9c7 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 @@ -45,6 +45,7 @@ #include #include #include +#include #endif namespace Ogre @@ -66,7 +67,7 @@ class EnumProperty; namespace moveit_rviz_plugin { -class PlanningSceneDisplay : public rviz_common::Display +class PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC PlanningSceneDisplay : public rviz_common::Display { Q_OBJECT diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.hpp new file mode 100644 index 0000000000..9542fd2430 --- /dev/null +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.hpp @@ -0,0 +1,98 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ +#define PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_LIBRARY + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_EXPORT + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_IMPORT + #endif + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC + #define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#else + #define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC + #define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL + #endif + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE +#endif + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_RVIZ_PLUGIN_CORE_BUILDING_LIBRARY + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_CORE_IMPORT + #endif + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC_TYPE PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_LOCAL +#else + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_LOCAL + #endif + #define PLANNING_SCENE_RVIZ_PLUGIN_CORE_PUBLIC_TYPE +#endif + +#endif // PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt index f94c9b65ba..4bad296b4c 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt @@ -3,6 +3,7 @@ add_library(${MOVEIT_LIB_NAME}_core SHARED src/robot_state_display.cpp include/moveit/robot_state_rviz_plugin/robot_state_display.h) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools ) @@ -19,6 +20,7 @@ target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/i add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt b/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt index fc5d381e5f..2ab5d8b546 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt +++ b/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt @@ -25,6 +25,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED ${HEADERS} ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME} Qt5::Widgets diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt index eff468f987..e072f20501 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt @@ -13,6 +13,7 @@ add_library(${MOVEIT_LIB_NAME}_core SHARED ${HEADERS} ) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools moveit_planning_scene_rviz_plugin_core @@ -32,6 +33,7 @@ target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/i # Plugin Initializer add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index b407850d35..7d875d1856 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -10,6 +10,12 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/warehouse_connector.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} + PRIVATE "MOVEIT_WAREHOUSE_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp Boost moveit_core warehouse_ros moveit_ros_planning) target_link_libraries(${MOVEIT_LIB_NAME} ${OPENSSL_CRYPTO_LIBRARY}) 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 29e25095ea..070d1e92e4 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -37,6 +37,7 @@ #pragma once #include "moveit/warehouse/moveit_message_storage.h" +#include "moveit/warehouse/visibility_control.hpp" #include #include @@ -50,11 +51,11 @@ MOVEIT_CLASS_FORWARD(ConstraintsStorage) // Defines ConstraintsStoragePtr, Cons class ConstraintsStorage : public MoveItMessageStorage { public: - static const std::string DATABASE_NAME; + MOVEIT_WAREHOUSE_PUBLIC static const std::string DATABASE_NAME; - static const std::string CONSTRAINTS_ID_NAME; - static const std::string CONSTRAINTS_GROUP_NAME; - static const std::string ROBOT_NAME; + MOVEIT_WAREHOUSE_PUBLIC static const std::string CONSTRAINTS_ID_NAME; + MOVEIT_WAREHOUSE_PUBLIC static const std::string CONSTRAINTS_GROUP_NAME; + MOVEIT_WAREHOUSE_PUBLIC static const std::string ROBOT_NAME; ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn); 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 cde1593eed..7106474639 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 @@ -37,6 +37,7 @@ #pragma once #include "moveit/warehouse/moveit_message_storage.h" +#include "moveit/warehouse/visibility_control.hpp" #include #include #include @@ -54,7 +55,7 @@ typedef warehouse_ros::MessageCollection::Ptr MOVEIT_CLASS_FORWARD(PlanningSceneStorage) // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc -class PlanningSceneStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_PUBLIC 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 f97da7974d..230cadb337 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -39,6 +39,7 @@ #include #include #include +#include "moveit/warehouse/visibility_control.hpp" namespace moveit_warehouse { @@ -47,7 +48,7 @@ typedef warehouse_ros::MessageCollection::Ptr Robo MOVEIT_CLASS_FORWARD(RobotStateStorage) // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc -class RobotStateStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_PUBLIC RobotStateStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.hpp b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.hpp new file mode 100644 index 0000000000..e298255b95 --- /dev/null +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVEIT_WAREHOUSE__VISIBILITY_CONTROL_HPP_ +#define MOVEIT_WAREHOUSE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVEIT_WAREHOUSE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_WAREHOUSE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_WAREHOUSE_EXPORT __declspec(dllexport) + #define MOVEIT_WAREHOUSE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_WAREHOUSE_BUILDING_LIBRARY + #define MOVEIT_WAREHOUSE_PUBLIC MOVEIT_WAREHOUSE_EXPORT + #else + #define MOVEIT_WAREHOUSE_PUBLIC MOVEIT_WAREHOUSE_IMPORT + #endif + #define MOVEIT_WAREHOUSE_PUBLIC_TYPE MOVEIT_WAREHOUSE_PUBLIC + #define MOVEIT_WAREHOUSE_LOCAL +#else + #define MOVEIT_WAREHOUSE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_WAREHOUSE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_WAREHOUSE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_WAREHOUSE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_WAREHOUSE_PUBLIC + #define MOVEIT_WAREHOUSE_LOCAL + #endif + #define MOVEIT_WAREHOUSE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_WAREHOUSE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp index 17096723b3..369c4fda36 100644 --- a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp +++ b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp @@ -36,7 +36,9 @@ #include #include +#ifndef _WIN32 #include +#endif #include #include @@ -50,12 +52,15 @@ WarehouseConnector::WarehouseConnector(const std::string& dbexec) : dbexec_(dbex WarehouseConnector::~WarehouseConnector() { + #ifndef _WIN32 if (child_pid_ != 0) kill(child_pid_, SIGTERM); + #endif } bool WarehouseConnector::connectToDatabase(const std::string& dirname) { + #ifndef _WIN32 if (child_pid_ != 0) kill(child_pid_, SIGTERM); @@ -102,5 +107,9 @@ bool WarehouseConnector::connectToDatabase(const std::string& dirname) rclcpp::sleep_for(1s); } return true; + #else + return false; + #endif + } } // namespace moveit_warehouse