From f7bcbf455062eaf6b9824a02f72ff1a92ad4fb65 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:28:17 -0700 Subject: [PATCH 01/54] Attempt to find FCL using find_package as well --- moveit_core/CMakeLists.txt | 20 +++++++++++++------ .../collision_detection_fcl/CMakeLists.txt | 2 +- 2 files changed, 15 insertions(+), 7 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 36d58c1829..393f8f865b 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(moveit_core VERSION 2.1.4 LANGUAGES CXX) +project(moveit_core VERSION 2.1.3 LANGUAGES CXX) # Common cmake code applied to all moveit packages find_package(moveit_common REQUIRED) @@ -18,12 +18,19 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") # TODO: Move collision detection into separate packages find_package(Bullet 2.87 REQUIRED) -find_package(PkgConfig REQUIRED) +find_package(PkgConfig) -pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") -# replace LIBFCL_LIBRARIES with full path to the library -find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) -set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") +if(PkgConfig_FOUND) + pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") + # replace LIBFCL_LIBRARIES with full path to the library + find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) + set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") + set(FCL_NAME "LIBFCL") +else() + find_package(FCL 0.5.0 QUIET) + set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") + set(FCL_NAME "FCL") +endif() find_package(angles REQUIRED) find_package(OCTOMAP REQUIRED) @@ -129,6 +136,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS eigen3_cmake_module OCTOMAP ${BULLET_ENABLE} + ${FCL_NAME} ) pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index b6a6b839f6..2111a8acd0 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -11,7 +11,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom urdfdom_headers - LIBFCL + ${FCL_NAME} Boost visualization_msgs ) From b052b20ce2c92b7e031be0c8627f9f3174ee8116 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:28:52 -0700 Subject: [PATCH 02/54] Add visibility control to collision detection fcl --- .../collision_detection_fcl/CMakeLists.txt | 1 + .../collision_detector_allocator_fcl.h | 4 ++- .../visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 2111a8acd0..b8429df288 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}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE COLLISION_DETECTION_FCL_BUILDING_DLL) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation 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..501de43166 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -39,10 +39,12 @@ #include #include +#include "visibility_control.h" + 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/visibility_control.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h new file mode 100644 index 0000000000..e142f2ecc2 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ +#define COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ + +// 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_DLL + #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 + +#endif // COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ From 1f7364f0e877816309f5ac956cd3766069eb5dd2 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:29:15 -0700 Subject: [PATCH 03/54] Add visibility control to kinematics base --- moveit_core/kinematics_base/CMakeLists.txt | 1 + .../moveit/kinematics_base/kinematics_base.h | 4 ++- .../kinematics_base/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index ef52feff78..082f17f453 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -3,6 +3,7 @@ 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}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_KINEMATICS_BASE_BUILDING_DLL") # This line is needed to ensure that messages are done being built before this is built ament_target_dependencies( 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..a2dfeb148f 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -43,6 +43,8 @@ #include #include +#include "visibility_control.h" + namespace moveit { namespace core @@ -140,7 +142,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase) // Defines KinematicsBasePtr, ConstPtr, We * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class KinematicsBase +class MOVEIT_KINEMATICS_BASE_PUBLIC KinematicsBase { public: static const rclcpp::Logger LOGGER; diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h new file mode 100644 index 0000000000..3e58fe78f3 --- /dev/null +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ +#define MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ + +// 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_KINEMATICS_BASE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_KINEMATICS_BASE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_KINEMATICS_BASE_EXPORT __declspec(dllexport) + #define MOVEIT_KINEMATICS_BASE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_KINEMATICS_BASE_BUILDING_DLL + #define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_EXPORT + #else + #define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_IMPORT + #endif + #define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE MOVEIT_KINEMATICS_BASE_PUBLIC + #define MOVEIT_KINEMATICS_BASE_LOCAL +#else + #define MOVEIT_KINEMATICS_BASE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_KINEMATICS_BASE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_KINEMATICS_BASE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_KINEMATICS_BASE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_KINEMATICS_BASE_PUBLIC + #define MOVEIT_KINEMATICS_BASE_LOCAL + #endif + #define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ From 76fd1819d0bcc596cac6d022ebd12c845370353f Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:29:32 -0700 Subject: [PATCH 04/54] Fix linking boost for core --- moveit_core/ConfigExtras.cmake | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_core/ConfigExtras.cmake b/moveit_core/ConfigExtras.cmake index f208f771f9..4a9fc2c75f 100644 --- a/moveit_core/ConfigExtras.cmake +++ b/moveit_core/ConfigExtras.cmake @@ -1,8 +1,9 @@ # Extras module needed for dependencies to find boost components -# boost::iostreams on Windows depends on boost::zlib if(WIN32) - set(EXTRA_BOOST_COMPONENTS zlib) + # Fix linking errors on windows + add_definitions(-DBOOST_ALL_NO_LIB) + add_definitions(-DBOOST_ALL_DYN_LINK) endif() find_package(Boost REQUIRED chrono @@ -14,5 +15,4 @@ find_package(Boost REQUIRED serialization system thread - ${EXTRA_BOOST_COMPONENTS} ) From 96970437f16253d0bb7314b5d18b25430620cf22 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:29:56 -0700 Subject: [PATCH 05/54] Add visibility control to planning scene --- moveit_core/planning_scene/CMakeLists.txt | 1 + .../moveit/planning_scene/planning_scene.h | 4 ++- .../planning_scene/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index fc1f7d788f..70c6b8654d 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -3,6 +3,7 @@ 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}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_PLANNING_SCENE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} Boost rclcpp 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 7d0a532d0e..96bdd8f3dc 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -57,6 +57,8 @@ #include #include "rclcpp/rclcpp.hpp" +#include "visibility_control.h" + /** \brief This namespace includes the central class for representing planning contexts */ namespace planning_scene { @@ -85,7 +87,7 @@ using ObjectTypeMap = std::map +class MOVEIT_PLANNING_SCENE_PUBLIC PlanningScene : private boost::noncopyable, public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h new file mode 100644 index 0000000000..cb52d5b029 --- /dev/null +++ b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ +#define MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ + +// 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_SCENE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_PLANNING_SCENE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_PLANNING_SCENE_EXPORT __declspec(dllexport) + #define MOVEIT_PLANNING_SCENE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_PLANNING_SCENE_BUILDING_DLL + #define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_EXPORT + #else + #define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_IMPORT + #endif + #define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_PUBLIC + #define MOVEIT_PLANNING_SCENE_LOCAL +#else + #define MOVEIT_PLANNING_SCENE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_SCENE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_PLANNING_SCENE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_SCENE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_PLANNING_SCENE_PUBLIC + #define MOVEIT_PLANNING_SCENE_LOCAL + #endif + #define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ From 8b3fab6ada8e0235c4711f2414053b49de660c8b Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:30:48 -0700 Subject: [PATCH 06/54] Add visibility control to perception mesh filter --- .../perception/mesh_filter/CMakeLists.txt | 1 + .../moveit/mesh_filter/stereo_camera_model.h | 4 ++- .../moveit/mesh_filter/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 0fcee736f9..26243fbff5 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -16,6 +16,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} Boost ) target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} GLUT::GLUT ${GLEW_LIBRARIES}) +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_MESH_FILTER_BUILDING_DLL") # 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..7b48cf4380 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -39,13 +39,15 @@ #include #include +#include "visibility_control.h" + namespace mesh_filter { /** * \brief Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices * \author Suat Gedikli */ -class StereoCameraModel : public SensorModel +class MOVEIT_MESH_FILTER_PUBLIC StereoCameraModel : public SensorModel { public: /** diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h new file mode 100644 index 0000000000..cba7504324 --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ +#define MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ + +// 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_MESH_FILTER_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_MESH_FILTER_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_MESH_FILTER_EXPORT __declspec(dllexport) + #define MOVEIT_MESH_FILTER_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_MESH_FILTER_BUILDING_DLL + #define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_EXPORT + #else + #define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_IMPORT + #endif + #define MOVEIT_MESH_FILTER_PUBLIC_TYPE MOVEIT_MESH_FILTER_PUBLIC + #define MOVEIT_MESH_FILTER_LOCAL +#else + #define MOVEIT_MESH_FILTER_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_MESH_FILTER_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_MESH_FILTER_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_MESH_FILTER_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_MESH_FILTER_PUBLIC + #define MOVEIT_MESH_FILTER_LOCAL + #endif + #define MOVEIT_MESH_FILTER_PUBLIC_TYPE +#endif + +#endif // MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ From bf9b4f89ef078473647cf0e05a8fdfe76700e428 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:31:09 -0700 Subject: [PATCH 07/54] Undefine near and far for mesh filter --- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 2bf464dd54..392fe31291 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -46,6 +46,9 @@ #include #include +#undef near +#undef far + namespace mesh_filter { MOVEIT_CLASS_FORWARD(GLRenderer) // Defines GLRendererPtr, ConstPtr, WeakPtr... etc From c2b6ff5a4ecb011b0c7b9de41f186a5d76417fec Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:31:26 -0700 Subject: [PATCH 08/54] Add visibility control to planning scene monitor --- .../planning_scene_monitor/CMakeLists.txt | 1 + .../planning_scene_monitor.h | 5 ++- .../visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 40 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index b72df8876c..e8c1b30a29 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -6,6 +6,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/trajectory_monitor.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_PLANNING_SCENE_MONITOR_BUILDING_DLL") 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..b4b2c39160 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -49,9 +49,12 @@ #include #include #include +#include #include #include +#include "visibility_control.h" + namespace planning_scene_monitor { MOVEIT_CLASS_FORWARD(PlanningSceneMonitor) // Defines PlanningSceneMonitorPtr, ConstPtr, WeakPtr... etc @@ -59,7 +62,7 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor) // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class PlanningSceneMonitor : private boost::noncopyable +class MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC PlanningSceneMonitor : private boost::noncopyable { public: enum SceneUpdateType diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h new file mode 100644 index 0000000000..7c94033d1a --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ +#define MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ + +// 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_SCENE_MONITOR_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) + #define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_PLANNING_SCENE_MONITOR_BUILDING_DLL + #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_EXPORT + #else + #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_IMPORT + #endif + #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC + #define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL +#else + #define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC + #define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL + #endif + #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE +#endif + +#endif // MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ From a58a8f4793454b649e90201f1f860e0ce7053355 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 13:31:51 -0700 Subject: [PATCH 09/54] Use _popen in rdf loader on windows --- moveit_ros/planning/rdf_loader/src/rdf_loader.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) 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; } From 456510da2b3e9adb3bc8c2793030c69838e9800d Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 16:00:25 -0700 Subject: [PATCH 10/54] Include boost.bind where missing --- .../src/depth_image_octomap_updater.cpp | 1 + .../src/pointcloud_octomap_updater.cpp | 1 + 2 files changed, 2 insertions(+) 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..31a000e8ed 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -44,6 +44,7 @@ #include #include +#include namespace occupancy_map_monitor { diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp index 6edef43044..2f4d202762 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp @@ -45,6 +45,7 @@ #include #include +#include namespace occupancy_map_monitor { From aab23110291873ebae52e87b122ba106cf016bd7 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 16:00:37 -0700 Subject: [PATCH 11/54] Include deque in trajectory execution manager --- .../trajectory_execution_manager/trajectory_execution_manager.h | 1 + 1 file changed, 1 insertion(+) 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..1c3f54c7b3 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -48,6 +48,7 @@ #include #include +#include namespace trajectory_execution_manager { From db222ea4bb0a8877fd51bca04dd021a2a527a880 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 16:15:17 -0700 Subject: [PATCH 12/54] Build build error for moveit ros warehouse connector fork and kill aren't available on windows, so just warn when they are trying to be used for now --- .../warehouse/warehouse/src/warehouse_connector.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp index 17096723b3..4ce33daefe 100644 --- a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp +++ b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp @@ -36,12 +36,18 @@ #include #include -#include #include #include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.warehouse_connector"); +#ifdef _WIN32 + void kill(int, int) { RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); } // Should never be called + int fork() { RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); return -1; } +#else + #include +#endif + namespace moveit_warehouse { WarehouseConnector::WarehouseConnector(const std::string& dbexec) : dbexec_(dbexec), child_pid_(0) From 854b59c47468cb4fa3af6c85c5d796ba73ba6074 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 31 May 2021 16:15:42 -0700 Subject: [PATCH 13/54] Add visibility control to moveit ros warehouse --- moveit_ros/warehouse/warehouse/CMakeLists.txt | 1 + .../moveit/warehouse/constraints_storage.h | 4 ++- .../moveit/warehouse/planning_scene_storage.h | 4 ++- .../include/moveit/warehouse/state_storage.h | 4 ++- .../moveit/warehouse/visibility_control.h | 35 +++++++++++++++++++ 5 files changed, 45 insertions(+), 3 deletions(-) create mode 100644 moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index b407850d35..785cbc5bbe 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -12,6 +12,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp Boost moveit_core warehouse_ros moveit_ros_planning) target_link_libraries(${MOVEIT_LIB_NAME} ${OPENSSL_CRYPTO_LIBRARY}) +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE MOVEIT_ROS_WAREHOUSE_BUILDING_DLL) add_executable(moveit_warehouse_broadcast src/broadcast.cpp) ament_target_dependencies(moveit_warehouse_broadcast rclcpp Boost warehouse_ros moveit_ros_planning) 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..97f39f7f43 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -40,6 +40,8 @@ #include #include +#include "visibility_control.h" + namespace moveit_warehouse { typedef warehouse_ros::MessageWithMetadata::ConstPtr ConstraintsWithMetadata; @@ -47,7 +49,7 @@ typedef warehouse_ros::MessageCollection::Ptr Con MOVEIT_CLASS_FORWARD(ConstraintsStorage) // Defines ConstraintsStoragePtr, ConstPtr, WeakPtr... etc -class ConstraintsStorage : public MoveItMessageStorage +class MOVEIT_ROS_WAREHOUSE_PUBLIC ConstraintsStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h index cde1593eed..3fc356ad3a 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -42,6 +42,8 @@ #include #include +#include "visibility_control.h" + namespace moveit_warehouse { typedef warehouse_ros::MessageWithMetadata::ConstPtr PlanningSceneWithMetadata; @@ -54,7 +56,7 @@ typedef warehouse_ros::MessageCollection::Ptr MOVEIT_CLASS_FORWARD(PlanningSceneStorage) // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc -class PlanningSceneStorage : public MoveItMessageStorage +class MOVEIT_ROS_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..16381a2d02 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -40,6 +40,8 @@ #include #include +#include "visibility_control.h" + namespace moveit_warehouse { typedef warehouse_ros::MessageWithMetadata::ConstPtr RobotStateWithMetadata; @@ -47,7 +49,7 @@ typedef warehouse_ros::MessageCollection::Ptr Robo MOVEIT_CLASS_FORWARD(RobotStateStorage) // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc -class RobotStateStorage : public MoveItMessageStorage +class MOVEIT_ROS_WAREHOUSE_PUBLIC RobotStateStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h new file mode 100644 index 0000000000..6360cb2452 --- /dev/null +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ +#define MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ + +// 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_ROS_WAREHOUSE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_ROS_WAREHOUSE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_ROS_WAREHOUSE_EXPORT __declspec(dllexport) + #define MOVEIT_ROS_WAREHOUSE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_ROS_WAREHOUSE_BUILDING_DLL + #define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_EXPORT + #else + #define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_IMPORT + #endif + #define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE MOVEIT_ROS_WAREHOUSE_PUBLIC + #define MOVEIT_ROS_WAREHOUSE_LOCAL +#else + #define MOVEIT_ROS_WAREHOUSE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_ROS_WAREHOUSE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_ROS_WAREHOUSE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_ROS_WAREHOUSE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_ROS_WAREHOUSE_PUBLIC + #define MOVEIT_ROS_WAREHOUSE_LOCAL + #endif + #define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ From f45b55bc2441de831f768c7252fb240f558c6f06 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 3 Jun 2021 00:29:52 -0700 Subject: [PATCH 14/54] Fix includes for BenchmarkExecutor --- moveit_ros/benchmarks/src/BenchmarkExecutor.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index bbd774a25c..58a90c714e 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -49,12 +49,15 @@ #include #include #include +#include #ifndef _WIN32 #include #else #include #endif +#undef max + using namespace moveit_ros_benchmarks; static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.benchmarks.BenchmarkExecutor"); From dacbc6bd30f3f8ae9d2366be890b9a21c9b19934 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 3 Jun 2021 00:30:06 -0700 Subject: [PATCH 15/54] Link to ws2_32.lib on windows in moveit ros benchmarks --- moveit_ros/benchmarks/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index e551b8e5c2..eae36d3403 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -37,9 +37,13 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/BenchmarkExecutor.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +if(WIN32) + set(EXTRA_LIB ws2_32.lib) +endif() ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS} ) +target_link_libraries(${MOVEIT_LIB_NAME} ${EXTRA_LIB}) add_executable(moveit_run_benchmark src/RunBenchmark.cpp) ament_target_dependencies(moveit_run_benchmark From cec69c612ff48d3118d3364434e1140ecf2585ff Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 3 Jun 2021 00:30:29 -0700 Subject: [PATCH 16/54] Add visibility control to moveit ros planning pipeline --- .../planning/planning_pipeline/CMakeLists.txt | 1 + .../planning_pipeline/planning_pipeline.h | 4 ++- .../planning_pipeline/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index cf3c676457..b5272a604f 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -2,6 +2,7 @@ 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}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_ROS_PLANNING_PIPELINE_BUILDING_DLL") 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..33e9f1d1cd 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -45,6 +45,8 @@ #include +#include "visibility_control.h" + /** \brief Planning pipeline */ namespace planning_pipeline { @@ -54,7 +56,7 @@ namespace planning_pipeline planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. */ -class PlanningPipeline +class MOVEIT_ROS_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.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h new file mode 100644 index 0000000000..4ea9db4580 --- /dev/null +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ +#define MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ + +// 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_ROS_PLANNING_PIPELINE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __declspec(dllexport) + #define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_ROS_PLANNING_PIPELINE_BUILDING_DLL + #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_EXPORT + #else + #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_IMPORT + #endif + #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC + #define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL +#else + #define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC + #define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL + #endif + #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ From da953f5712a2aea49eea0d710b107f8c450456e1 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Fri, 4 Jun 2021 22:50:49 -0700 Subject: [PATCH 17/54] Add visibility control to trajectory execution manager --- .../CMakeLists.txt | 1 + .../trajectory_execution_manager.h | 4 ++- .../visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index baf0dca83e..a93d3ed87a 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -2,6 +2,7 @@ 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}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "TRAJECTORY_EXECUTION_MANAGER_BUILDING_DLL") 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 1c3f54c7b3..609b8b0679 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 @@ -50,6 +50,8 @@ #include #include +#include "visibility_control.h" + namespace trajectory_execution_manager { MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager) // Defines TrajectoryExecutionManagerPtr, ConstPtr, WeakPtr... etc @@ -57,7 +59,7 @@ MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager) // Defines TrajectoryExecution // Two modes: // Managed controllers // Unmanaged controllers: given the trajectory, -class TrajectoryExecutionManager +class 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.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h new file mode 100644 index 0000000000..5bd95a9bb0 --- /dev/null +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ +#define TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ + +// 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 TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__ ((dllexport)) + #define TRAJECTORY_EXECUTION_MANAGER_IMPORT __attribute__ ((dllimport)) + #else + #define TRAJECTORY_EXECUTION_MANAGER_EXPORT __declspec(dllexport) + #define TRAJECTORY_EXECUTION_MANAGER_IMPORT __declspec(dllimport) + #endif + #ifdef TRAJECTORY_EXECUTION_MANAGER_BUILDING_DLL + #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_EXPORT + #else + #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_IMPORT + #endif + #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE TRAJECTORY_EXECUTION_MANAGER_PUBLIC + #define TRAJECTORY_EXECUTION_MANAGER_LOCAL +#else + #define TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__ ((visibility("default"))) + #define TRAJECTORY_EXECUTION_MANAGER_IMPORT + #if __GNUC__ >= 4 + #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC __attribute__ ((visibility("default"))) + #define TRAJECTORY_EXECUTION_MANAGER_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC + #define TRAJECTORY_EXECUTION_MANAGER_LOCAL + #endif + #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE +#endif + +#endif // TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ From 44fb70ad83d47157a9b93493f9e0f95f9f341a58 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Fri, 4 Jun 2021 22:56:35 -0700 Subject: [PATCH 18/54] Attempt to find FCL using find_package first --- moveit_core/CMakeLists.txt | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 393f8f865b..78de246e77 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(moveit_core VERSION 2.1.3 LANGUAGES CXX) +project(moveit_core VERSION 2.1.4 LANGUAGES CXX) # Common cmake code applied to all moveit packages find_package(moveit_common REQUIRED) @@ -18,18 +18,18 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") # TODO: Move collision detection into separate packages find_package(Bullet 2.87 REQUIRED) -find_package(PkgConfig) +find_package(FCL 0.5.0) -if(PkgConfig_FOUND) +if(FCL_FOUND) + set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") + set(FCL_NAME "FCL") +else() + find_package(PkgConfig REQUIRED) pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") # replace LIBFCL_LIBRARIES with full path to the library find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") set(FCL_NAME "LIBFCL") -else() - find_package(FCL 0.5.0 QUIET) - set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") - set(FCL_NAME "FCL") endif() find_package(angles REQUIRED) From 373ebec13a0827d40b9551663c3e6874639887b5 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Tue, 8 Jun 2021 21:57:33 -0700 Subject: [PATCH 19/54] Add visibility control to moveit move group interface --- .../move_group_interface/CMakeLists.txt | 1 + .../move_group_interface.h | 4 ++- .../move_group_interface/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index 523d74f259..b1676a5793 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -3,6 +3,7 @@ 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}") target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${Boost_THREAD_LIBRARY}) +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_MOVE_GROUP_INTERFACE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_msgs 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..1c133294cd 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -60,6 +60,8 @@ #include #include +#include "visibility_control.h" + namespace moveit { /** \brief Simple interface to MoveIt components */ @@ -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 MOVEIT_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.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h new file mode 100644 index 0000000000..a81098cdb9 --- /dev/null +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ +#define MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ + +// 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_MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) + #define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_MOVE_GROUP_INTERFACE_BUILDING_DLL + #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_EXPORT + #else + #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_IMPORT + #endif + #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC + #define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL +#else + #define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC + #define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL + #endif + #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE +#endif + +#endif // MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ From bc47f0d6117efb5164f7dea4cda98a16a3db722c Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Tue, 8 Jun 2021 21:58:17 -0700 Subject: [PATCH 20/54] Add visibility control to moveit ros robot interaction --- moveit_ros/robot_interaction/CMakeLists.txt | 1 + .../robot_interaction/kinematic_options_map.h | 4 ++- .../robot_interaction/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index 9491f51480..ab8675b81c 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -36,6 +36,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/robot_interaction.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_ROS_ROBOT_INTERACTION_BUILDING_DLL") 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..2ce6e9fb25 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -40,11 +40,13 @@ #include #include +#include "visibility_control.h" + namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class KinematicOptionsMap +class MOVEIT_ROS_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.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h new file mode 100644 index 0000000000..bc7d9e9c10 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ +#define MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ + +// 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_ROS_ROBOT_INTERACTION_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __declspec(dllexport) + #define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_ROS_ROBOT_INTERACTION_BUILDING_DLL + #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_EXPORT + #else + #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_IMPORT + #endif + #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC + #define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL +#else + #define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC + #define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL + #endif + #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE +#endif + +#endif // MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ From bc6ca7a4ca33ec14faaa715840b1d8795e225316 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Tue, 8 Jun 2021 21:59:22 -0700 Subject: [PATCH 21/54] Add visibility control to moveit planning scene rviz plugin --- .../planning_scene_rviz_plugin/CMakeLists.txt | 1 + .../planning_scene_display.h | 4 ++- .../visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 5b65ecdba6..0f57e4f824 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -4,6 +4,7 @@ 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}") +target_compile_definitions(${MOVEIT_LIB_NAME}_core PRIVATE "MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL") target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools) ament_target_dependencies(${MOVEIT_LIB_NAME}_core rclcpp 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..29dc358f09 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -47,6 +47,8 @@ #include #endif +#include "visibility_control.h" + namespace Ogre { class SceneNode; @@ -66,7 +68,7 @@ class EnumProperty; namespace moveit_rviz_plugin { -class PlanningSceneDisplay : public rviz_common::Display +class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_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.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h new file mode 100644 index 0000000000..d034ebdb2b --- /dev/null +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ + +// 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_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT + #else + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT + #endif + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#else + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL + #endif + #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE +#endif + +#endif // MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ From 12bc306871ca8cee126f94462724cb696de4bb27 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Tue, 8 Jun 2021 22:00:27 -0700 Subject: [PATCH 22/54] Replace uint with unsigned int uint is not defined on MSVC --- moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 3e8de2af91..dc2d07221b 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_; + unsigned int num_joints_; // True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw] std::array drift_dimensions_ = { { false, false, false, false, false, false } }; From 317e3b8527672b15d71559a687ad6c35510eb1b5 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 10 Jun 2021 19:45:30 -0700 Subject: [PATCH 23/54] Add visibility control to collision detection --- .../collision_detection/CMakeLists.txt | 1 + .../collision_detector_allocator_allvalid.h | 3 +- .../collision_detection/visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 38 insertions(+), 1 deletion(-) create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index a914eafb36..08cb94b116 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -12,6 +12,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE MOVEIT_COLLISION_DETECTION_BUILDING_DLL) 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..08345b4035 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,11 +38,12 @@ #include #include +#include "../visibility_control.h" namespace collision_detection { /** \brief An allocator for AllValid collision detectors */ -class CollisionDetectorAllocatorAllValid +class MOVEIT_COLLISION_DETECTION_PUBLIC CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h new file mode 100644 index 0000000000..79266a2584 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ +#define MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ + +// 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_COLLISION_DETECTION_EXPORT __attribute__ ((dllexport)) + #define MOVEIT_COLLISION_DETECTION_IMPORT __attribute__ ((dllimport)) + #else + #define MOVEIT_COLLISION_DETECTION_EXPORT __declspec(dllexport) + #define MOVEIT_COLLISION_DETECTION_IMPORT __declspec(dllimport) + #endif + #ifdef MOVEIT_COLLISION_DETECTION_BUILDING_DLL + #define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_EXPORT + #else + #define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_IMPORT + #endif + #define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE MOVEIT_COLLISION_DETECTION_PUBLIC + #define MOVEIT_COLLISION_DETECTION_LOCAL +#else + #define MOVEIT_COLLISION_DETECTION_EXPORT __attribute__ ((visibility("default"))) + #define MOVEIT_COLLISION_DETECTION_IMPORT + #if __GNUC__ >= 4 + #define MOVEIT_COLLISION_DETECTION_PUBLIC __attribute__ ((visibility("default"))) + #define MOVEIT_COLLISION_DETECTION_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVEIT_COLLISION_DETECTION_PUBLIC + #define MOVEIT_COLLISION_DETECTION_LOCAL + #endif + #define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE +#endif + +#endif // MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ From f8f6c0746be8df9dd528747c3517f3acecec327e Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 10 Jun 2021 19:49:25 -0700 Subject: [PATCH 24/54] Fix errors in p2_arm_kinematics_plugin --- moveit_core/constraint_samplers/test/pr2_arm_ik.cpp | 2 +- .../constraint_samplers/test/pr2_arm_kinematics_plugin.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp b/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp index 77080ee9ef..d172392822 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp @@ -789,6 +789,6 @@ bool PR2ArmIK::checkJointLimits(const double& joint_value, const int& joint_num) else jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]); - return not(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]); + return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]); } } // namespace pr2_arm_kinematics diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp index 5b2a7b6716..3ca4e0a7e9 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include "pr2_arm_kinematics_plugin.h" @@ -240,7 +241,7 @@ double computeEuclideanDistance(const std::vector& array_1, const KDL::J { distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i)); } - return sqrt(distance); + return std::sqrt(distance); } void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info) From 68219a9c99855753d5c5f415ab805c9de77c6999 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 10 Jun 2021 19:56:27 -0700 Subject: [PATCH 25/54] Fix MSVC build in collision detection fcl tests --- moveit_core/collision_detection_fcl/CMakeLists.txt | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index b8429df288..082ffe56e4 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -49,10 +49,14 @@ if(BUILD_TESTING) ament_add_gtest(test_fcl_collision_detection test/test_fcl_collision_detection_pr2.cpp) target_link_libraries(test_fcl_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_fcl_collision_detection PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_fcl_collision_detection PRIVATE -Wno-deprecated-declarations) + endif() ament_add_gtest(test_fcl_collision_detection_panda test/test_fcl_collision_detection_panda.cpp) target_link_libraries(test_fcl_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + endif() endif() From 7cc99c4fc4ccedff3d4e777b41a5058fe29c333a Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Sat, 26 Jun 2021 16:45:01 -0500 Subject: [PATCH 26/54] Remove extra args for boost linking --- moveit_core/ConfigExtras.cmake | 5 ----- 1 file changed, 5 deletions(-) diff --git a/moveit_core/ConfigExtras.cmake b/moveit_core/ConfigExtras.cmake index 4a9fc2c75f..66d6e50b17 100644 --- a/moveit_core/ConfigExtras.cmake +++ b/moveit_core/ConfigExtras.cmake @@ -1,10 +1,5 @@ # Extras module needed for dependencies to find boost components -if(WIN32) - # Fix linking errors on windows - add_definitions(-DBOOST_ALL_NO_LIB) - add_definitions(-DBOOST_ALL_DYN_LINK) -endif() find_package(Boost REQUIRED chrono date_time From 4a210bc6b28cd8063b3c692ba0b252c36f4dc69b Mon Sep 17 00:00:00 2001 From: Nisala Kalupahana Date: Mon, 28 Jun 2021 15:26:41 -0700 Subject: [PATCH 27/54] Compilation fixes for MoveIt on macOS (#498) * Fixed location of GLUT,GLEW framework on macOS * Use explicit boost namespace for bind placeholders --- moveit_ros/perception/CMakeLists.txt | 9 ++++++++- .../src/depth_image_octomap_updater.cpp | 11 +++++++---- .../perception/lazy_free_space_updater/CMakeLists.txt | 3 +++ moveit_ros/perception/mesh_filter/CMakeLists.txt | 3 ++- moveit_ros/perception/mesh_filter/src/gl_renderer.cpp | 2 +- .../src/pointcloud_octomap_updater.cpp | 9 ++++++--- 6 files changed, 27 insertions(+), 10 deletions(-) diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt index b656319b8f..27ce4ca893 100644 --- a/moveit_ros/perception/CMakeLists.txt +++ b/moveit_ros/perception/CMakeLists.txt @@ -21,8 +21,15 @@ if(WITH_OPENGL) endif() find_package(OpenGL REQUIRED) find_package(GLEW REQUIRED) - find_package(GLUT REQUIRED) + set(gl_LIBS ${gl_LIBS} ${OPENGL_LIBRARIES}) + if(APPLE) + find_package(FreeGLUT REQUIRED) + set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLEW::GLEW FreeGLUT::freeglut) + else() + find_package(GLUT REQUIRED) + set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT) + endif() set(perception_GL_INCLUDE_DIRS "mesh_filter/include" "depth_image_octomap_updater/include") set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR}) endif() 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 f637c59b63..4edc9a3758 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,8 @@ 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(); @@ -140,9 +141,11 @@ 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", - custom_qos); + sub_depth_image_ = + image_transport::create_camera_subscription(node_.get(), image_topic_, + boost::bind(&DepthImageOctomapUpdater::depthImageCallback, this, + boost::placeholders::_1, boost::placeholders::_2), + "raw", custom_qos); } void DepthImageOctomapUpdater::stop() diff --git a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt index ae38c52cf0..98dbb81058 100644 --- a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt +++ b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt @@ -4,6 +4,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/lazy_free_space_updater.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES LINK_FLAGS "${OpenMP_CXX_FLAGS}") +if(APPLE) + target_link_libraries(${MOVEIT_LIB_NAME} OpenMP::OpenMP_CXX) +endif() ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_ros_occupancy_map_monitor diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 5f5b7f1865..6a83af3974 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -15,7 +15,8 @@ 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} ${SYSTEM_GL_LIBRARIES}) # TODO: Port to ROS2 # add_library(moveit_depth_self_filter SHARED diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index 92f01b44af..fec53a26e5 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -39,8 +39,8 @@ #include #else #include -#endif #include +#endif #include #include #include 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 fbddf61674..4007b4da4f 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 @@ -86,7 +86,8 @@ 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 +105,15 @@ 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()); } } From b1d1de4b56fdc09bc54fdbb13231999cc9c5d9c3 Mon Sep 17 00:00:00 2001 From: Jorge Nicho Date: Mon, 28 Jun 2021 17:28:14 -0500 Subject: [PATCH 28/54] Enable Bullet and fix plugin configuration (#489) Co-authored-by: Henning Kayser --- moveit_core/CMakeLists.txt | 17 +++++++---------- .../collision_detection_bullet/CMakeLists.txt | 16 +++++++++------- .../collision_detector_bullet_description.xml | 2 +- 3 files changed, 17 insertions(+), 18 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 6b1f2debb8..490ee8f531 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -15,7 +15,6 @@ include(ConfigExtras.cmake) list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") -# TODO: Move collision detection into separate packages find_package(Bullet 2.87 REQUIRED) find_package(PkgConfig REQUIRED) @@ -61,7 +60,7 @@ set(THIS_PACKAGE_INCLUDE_DIRS backtrace/include collision_detection/include collision_detection_fcl/include - ${BULLET_INC} + collision_detection_bullet/include constraint_samplers/include controller_manager/include distance_field/include @@ -97,7 +96,7 @@ set(THIS_PACKAGE_LIBRARIES moveit_planning_interface moveit_collision_detection moveit_collision_detection_fcl - ${BULLET_LIB} + moveit_collision_detection_bullet moveit_kinematic_constraints moveit_planning_scene moveit_constraint_samplers @@ -134,13 +133,14 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS Eigen3 eigen3_cmake_module OCTOMAP - ${BULLET_ENABLE} + Bullet ) + pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) +pluginlib_export_plugin_description_file(moveit_core collision_detector_bullet_description.xml) include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS} ${LIBFCL_INCLUDE_DIRS} - ${BULLET_INCLUDE_DIRS} ) include_directories(${THIS_PACKAGE_INCLUDE_DIRS} @@ -182,12 +182,9 @@ add_subdirectory(distance_field) add_subdirectory(collision_distance_field) add_subdirectory(kinematics_metrics) add_subdirectory(dynamics_solver) -# TODO(henningkayser): enable bullet once the library is migrated to ROS2 -if(BULLET_ENABLE) add_subdirectory(collision_detection_bullet) -else() -install(FILES collision_detection_bullet/empty_description.xml DESTINATION share/${PROJECT_NAME} RENAME collision_detector_bullet_description.xml) -endif() + +pluginlib_export_plugin_description_file(moveit_core collision_detector_bullet_description.xml) # TODO: Port python bindings # add_subdirectory(python) diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index 27fbd79504..5d8e87d9a3 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -1,6 +1,6 @@ set(MOVEIT_LIB_NAME moveit_collision_detection_bullet) -add_library(${MOVEIT_LIB_NAME} +add_library(${MOVEIT_LIB_NAME} SHARED src/bullet_integration/bullet_utils.cpp src/bullet_integration/bullet_discrete_bvh_manager.cpp src/bullet_integration/bullet_cast_bvh_manager.cpp @@ -10,7 +10,9 @@ add_library(${MOVEIT_LIB_NAME} src/bullet_integration/ros_bullet_utils.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") - +ament_target_dependencies(${MOVEIT_LIB_NAME} SYSTEM + BULLET +) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation @@ -22,11 +24,13 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} ) target_link_libraries(${MOVEIT_LIB_NAME} moveit_collision_detection - ${BULLET_LIBRARIES} ) -add_library(collision_detector_bullet_plugin src/collision_detector_bullet_plugin_loader.cpp) +add_library(collision_detector_bullet_plugin SHARED src/collision_detector_bullet_plugin_loader.cpp) set_target_properties(collision_detector_bullet_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +ament_target_dependencies(collision_detector_bullet_plugin SYSTEM + BULLET +) ament_target_dependencies(collision_detector_bullet_plugin rclcpp urdf @@ -39,15 +43,13 @@ target_link_libraries(collision_detector_bullet_plugin moveit_planning_scene ) +install(DIRECTORY include/ DESTINATION include) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} TARGETS collision_detector_bullet_plugin EXPORT collision_detector_bullet_plugin LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin ) -install(DIRECTORY include/ DESTINATION include) - -install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) if(BUILD_TESTING) if(WIN32) diff --git a/moveit_core/collision_detector_bullet_description.xml b/moveit_core/collision_detector_bullet_description.xml index 4065ee048d..1f85a88322 100644 --- a/moveit_core/collision_detector_bullet_description.xml +++ b/moveit_core/collision_detector_bullet_description.xml @@ -1,4 +1,4 @@ - + From e660ec97cf721076c6d601f5266740234d6d9b11 Mon Sep 17 00:00:00 2001 From: Vatan Aksoy Tezer Date: Tue, 29 Jun 2021 01:35:35 +0300 Subject: [PATCH 29/54] Add prerelease tests (#502) Co-authored-by: Tyler Weaver --- .github/workflows/prerelease.yaml | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100644 .github/workflows/prerelease.yaml diff --git a/.github/workflows/prerelease.yaml b/.github/workflows/prerelease.yaml new file mode 100644 index 0000000000..8b860855cf --- /dev/null +++ b/.github/workflows/prerelease.yaml @@ -0,0 +1,26 @@ +# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git). +# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst) + +name: pre-release + +on: + workflow_dispatch: + +jobs: + default: + strategy: + fail-fast: false + matrix: + distro: [foxy, galactic, rolling] + + env: + ROS_DISTRO: ${{ matrix.distro }} + PRERELEASE: true + BASEDIR: ${{ github.workspace }}/.work + + name: "${{ matrix.distro }}" + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - name: industrial_ci + uses: ros-industrial/industrial_ci@master From 53d0a3e2dc8d83cae6c1849c350a62dd33cf0d25 Mon Sep 17 00:00:00 2001 From: Vatan Aksoy Tezer Date: Tue, 29 Jun 2021 01:50:39 +0300 Subject: [PATCH 30/54] Clean warehouse_ros OpenSSL depend (#514) Co-authored-by: Henning Kayser --- moveit_ros/warehouse/CMakeLists.txt | 3 +-- moveit_ros/warehouse/warehouse/CMakeLists.txt | 1 - 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/moveit_ros/warehouse/CMakeLists.txt b/moveit_ros/warehouse/CMakeLists.txt index b80a56c098..eeb3dd3e01 100644 --- a/moveit_ros/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/CMakeLists.txt @@ -16,12 +16,11 @@ find_package(warehouse_ros REQUIRED) find_package(moveit_ros_planning REQUIRED) find_package(tf2_eigen REQUIRED) find_package(tf2_ros REQUIRED) -find_package(OpenSSL) # Finds Boost Components include(ConfigExtras.cmake) -include_directories(warehouse/include ${OPENSSL_INCLUDE_DIR}) +include_directories(warehouse/include) add_subdirectory(warehouse) diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index b407850d35..ccba905b88 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -11,7 +11,6 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp Boost moveit_core warehouse_ros moveit_ros_planning) -target_link_libraries(${MOVEIT_LIB_NAME} ${OPENSSL_CRYPTO_LIBRARY}) add_executable(moveit_warehouse_broadcast src/broadcast.cpp) ament_target_dependencies(moveit_warehouse_broadcast rclcpp Boost warehouse_ros moveit_ros_planning) From 604c9748c2bf782bd76548911a277f8b5c3a0783 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 28 Jun 2021 21:07:52 -0500 Subject: [PATCH 31/54] Fix finding bullet on windows --- moveit_core/CMakeLists.txt | 21 ++++++++++++--------- moveit_core/CMakeModules/FindBULLET.cmake | 10 ---------- 2 files changed, 12 insertions(+), 19 deletions(-) delete mode 100644 moveit_core/CMakeModules/FindBULLET.cmake diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index d9ec82b147..8073d23407 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -13,22 +13,25 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") +find_package(PkgConfig) +set(BULLET_VERSION 2.87) -find_package(Bullet 2.87 REQUIRED) +if(PKGCONFIG_FOUND) + pkg_check_modules(BULLET bullet) + find_package_handle_standard_args(BULLET + REQUIRED_VARS BULLET_LIBRARIES BULLET_INCLUDE_DIRS + VERSION_VAR ${BULLET_VERSION}) -find_package(FCL 0.5.0) - -if(FCL_FOUND) - set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") - set(FCL_NAME "FCL") -else() - find_package(PkgConfig REQUIRED) pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") # replace LIBFCL_LIBRARIES with full path to the library find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") set(FCL_NAME "LIBFCL") +else() + find_package(FCL 0.5.0) + set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") + set(FCL_NAME "FCL") + find_package(Bullet ${BULLET_VERSION} REQUIRED) endif() find_package(angles REQUIRED) diff --git a/moveit_core/CMakeModules/FindBULLET.cmake b/moveit_core/CMakeModules/FindBULLET.cmake deleted file mode 100644 index bfe4056a14..0000000000 --- a/moveit_core/CMakeModules/FindBULLET.cmake +++ /dev/null @@ -1,10 +0,0 @@ -include(FindPackageHandleStandardArgs) -find_package(PkgConfig) - -if(PKGCONFIG_FOUND) - pkg_check_modules(BULLET bullet) -endif() - -find_package_handle_standard_args(BULLET - REQUIRED_VARS BULLET_LIBRARIES BULLET_INCLUDE_DIRS - VERSION_VAR BULLET_VERSION) From 6ee637e4caa6e8219fc96efa3be563ecb9afc4cb Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 28 Jun 2021 21:23:40 -0500 Subject: [PATCH 32/54] Fix MSVC build in collision detection bullet tests --- .../collision_detection_bullet/CMakeLists.txt | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index 5d8e87d9a3..7f1dfc1620 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -61,15 +61,21 @@ if(BUILD_TESTING) ament_add_gtest(test_bullet_collision_detection test/test_bullet_collision_detection_pr2.cpp) target_link_libraries(test_bullet_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_bullet_collision_detection PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_bullet_collision_detection PRIVATE -Wno-deprecated-declarations) + endif() ament_add_gtest(test_bullet_collision_detection_panda test/test_bullet_collision_detection_panda.cpp) target_link_libraries(test_bullet_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_bullet_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_bullet_collision_detection_panda PRIVATE -Wno-deprecated-declarations) + endif() ament_add_gtest(test_bullet_continuous_collision_checking test/test_bullet_continuous_collision_checking.cpp) target_link_libraries(test_bullet_continuous_collision_checking moveit_test_utils ${MOVEIT_LIB_NAME}) # TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished - target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations) + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations) + endif() endif() From 7c2953e7c0ed03c3ae70a342ef5609a954153005 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 28 Jun 2021 21:33:56 -0500 Subject: [PATCH 33/54] Add visibility control to collision detection bullet --- .../collision_detection_bullet/CMakeLists.txt | 1 + .../collision_detector_allocator_bullet.h | 4 ++- .../visibility_control.h | 35 +++++++++++++++++++ 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index 7f1dfc1620..2db5f2306e 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} SHARED src/bullet_integration/ros_bullet_utils.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE COLLISION_DETECTION_BULLET_BUILDING_DLL) ament_target_dependencies(${MOVEIT_LIB_NAME} SYSTEM BULLET ) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 8b3c11057e..30c69e7d4a 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -39,10 +39,12 @@ #include #include +#include "visibility_control.h" + namespace collision_detection { /** \brief An allocator for Bullet collision detectors */ -class CollisionDetectorAllocatorBullet +class COLLISION_DETECTION_BULLET_PUBLIC CollisionDetectorAllocatorBullet : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h new file mode 100644 index 0000000000..e13435e160 --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ +#define COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ + +// 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_BULLET_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_BULLET_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_BULLET_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_BULLET_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_BULLET_BUILDING_DLL + #define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_EXPORT + #else + #define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_IMPORT + #endif + #define COLLISION_DETECTION_BULLET_PUBLIC_TYPE COLLISION_DETECTION_BULLET_PUBLIC + #define COLLISION_DETECTION_BULLET_LOCAL +#else + #define COLLISION_DETECTION_BULLET_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_BULLET_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_BULLET_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_BULLET_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_BULLET_PUBLIC + #define COLLISION_DETECTION_BULLET_LOCAL + #endif + #define COLLISION_DETECTION_BULLET_PUBLIC_TYPE +#endif + +#endif // COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ From 1ac25deba2ab4fe046ad748dec17d3e802eb20a7 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 28 Jun 2021 21:35:42 -0500 Subject: [PATCH 34/54] Fix include deprecation warning #warning isn't supported on MSVC, so this deprecation warning actually causes a compiler error --- .../src/collision_detector_bullet_plugin_loader.cpp | 2 +- moveit_kinematics/cached_ik_kinematics_plugin/README.md | 2 +- .../src/move_group_sequence_action.cpp | 2 +- .../src/move_group_sequence_service.cpp | 2 +- .../src/pilz_industrial_motion_planner.cpp | 2 +- .../src/planning_context_loader_circ.cpp | 2 +- .../src/planning_context_loader_lin.cpp | 2 +- .../src/planning_context_loader_ptp.cpp | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) diff --git a/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp b/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp index 5363805e1e..5e319499f5 100644 --- a/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp +++ b/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp @@ -35,7 +35,7 @@ /* Author: Jens Petit */ #include -#include +#include namespace collision_detection { diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/README.md b/moveit_kinematics/cached_ik_kinematics_plugin/README.md index 77aa5697cd..993c906852 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/README.md +++ b/moveit_kinematics/cached_ik_kinematics_plugin/README.md @@ -58,7 +58,7 @@ The Cached IK Kinematics Plugin is implemented as a wrapper around classed deriv #include "cached_ik_kinematics_plugin.h" #include - #include + #include PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin, kinematics::KinematicsBase); In the catkin `package.xml` file for your plugin, you add these lines just before ``: diff --git a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp index 7b8fbe0c82..17793df063 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp @@ -300,5 +300,5 @@ void MoveGroupSequenceAction::setMoveState(move_group::MoveGroupState state) } // namespace pilz_industrial_motion_planner -#include +#include PLUGINLIB_EXPORT_CLASS(pilz_industrial_motion_planner::MoveGroupSequenceAction, move_group::MoveGroupCapability) diff --git a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp index ce6f789eb4..3ed94eb762 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp @@ -101,5 +101,5 @@ bool MoveGroupSequenceService::plan(moveit_msgs::GetMotionSequence::Request& req } // namespace pilz_industrial_motion_planner -#include +#include PLUGINLIB_EXPORT_CLASS(pilz_industrial_motion_planner::MoveGroupSequenceService, move_group::MoveGroupCapability) diff --git a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp index a7e592b204..219b0d908f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp @@ -44,7 +44,7 @@ // Boost includes #include -#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp index 0234b989dc..4564961299 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp @@ -37,7 +37,7 @@ #include "pilz_industrial_motion_planner/planning_context_base.h" #include "pilz_industrial_motion_planner/planning_context_circ.h" -#include +#include pilz_industrial_motion_planner::PlanningContextLoaderCIRC::PlanningContextLoaderCIRC() { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp index 85cf3b6fe9..cb230ee76a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp @@ -37,7 +37,7 @@ #include "pilz_industrial_motion_planner/planning_context_base.h" #include "pilz_industrial_motion_planner/planning_context_lin.h" -#include +#include pilz_industrial_motion_planner::PlanningContextLoaderLIN::PlanningContextLoaderLIN() { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp index 5c72e69cec..52a0df4ddd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp @@ -36,7 +36,7 @@ #include "moveit/planning_scene/planning_scene.h" #include "pilz_industrial_motion_planner/planning_context_ptp.h" -#include +#include pilz_industrial_motion_planner::PlanningContextLoaderPTP::PlanningContextLoaderPTP() { From 571885bc13e02f6a5e5e0e97f90233d664a36034 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Tue, 29 Jun 2021 20:15:27 -0500 Subject: [PATCH 35/54] Fix building moveit_servo Remove unnecessary gtest --- moveit_ros/moveit_servo/include/moveit_servo/servo.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index 7bed0f61cb..68d5467f6f 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -46,9 +46,6 @@ #include #include -// testing -#include - namespace moveit_servo { /** From 285a21440b6534a2a257394b71e27eb0aa52a29d Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Wed, 30 Jun 2021 22:24:48 -0500 Subject: [PATCH 36/54] Run pre-commit --- moveit_core/CMakeLists.txt | 2 +- .../collision_detection/visibility_control.h | 48 +++++++++---------- .../visibility_control.h | 48 +++++++++---------- .../visibility_control.h | 48 +++++++++---------- .../kinematics_base/visibility_control.h | 48 +++++++++---------- .../moveit/planning_scene/planning_scene.h | 3 +- .../planning_scene/visibility_control.h | 48 +++++++++---------- .../moveit/mesh_filter/visibility_control.h | 48 +++++++++---------- .../planning_pipeline/visibility_control.h | 48 +++++++++---------- .../visibility_control.h | 48 +++++++++---------- .../visibility_control.h | 48 +++++++++---------- .../move_group_interface/visibility_control.h | 48 +++++++++---------- .../robot_interaction/visibility_control.h | 48 +++++++++---------- .../visibility_control.h | 48 +++++++++---------- .../moveit/warehouse/visibility_control.h | 48 +++++++++---------- .../warehouse/src/warehouse_connector.cpp | 13 +++-- 16 files changed, 325 insertions(+), 317 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index abd7bdb559..4433c105c5 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -142,7 +142,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS visualization_msgs Eigen3 eigen3_cmake_module - OCTOMAP + OCTOMAP Bullet ${FCL_NAME} ) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h index 79266a2584..214e627fe8 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_COLLISION_DETECTION_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_COLLISION_DETECTION_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_COLLISION_DETECTION_EXPORT __declspec(dllexport) - #define MOVEIT_COLLISION_DETECTION_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_COLLISION_DETECTION_BUILDING_DLL - #define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_EXPORT - #else - #define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_IMPORT - #endif - #define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE MOVEIT_COLLISION_DETECTION_PUBLIC - #define MOVEIT_COLLISION_DETECTION_LOCAL +#ifdef __GNUC__ +#define MOVEIT_COLLISION_DETECTION_EXPORT __attribute__((dllexport)) +#define MOVEIT_COLLISION_DETECTION_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_COLLISION_DETECTION_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_COLLISION_DETECTION_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_COLLISION_DETECTION_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_COLLISION_DETECTION_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_COLLISION_DETECTION_PUBLIC - #define MOVEIT_COLLISION_DETECTION_LOCAL - #endif - #define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE +#define MOVEIT_COLLISION_DETECTION_EXPORT __declspec(dllexport) +#define MOVEIT_COLLISION_DETECTION_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_COLLISION_DETECTION_BUILDING_DLL +#define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_EXPORT +#else +#define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_IMPORT +#endif +#define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE MOVEIT_COLLISION_DETECTION_PUBLIC +#define MOVEIT_COLLISION_DETECTION_LOCAL +#else +#define MOVEIT_COLLISION_DETECTION_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_COLLISION_DETECTION_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_COLLISION_DETECTION_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_COLLISION_DETECTION_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_COLLISION_DETECTION_PUBLIC +#define MOVEIT_COLLISION_DETECTION_LOCAL +#endif +#define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE #endif #endif // MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h index e13435e160..191cdd5821 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define COLLISION_DETECTION_BULLET_EXPORT __attribute__ ((dllexport)) - #define COLLISION_DETECTION_BULLET_IMPORT __attribute__ ((dllimport)) - #else - #define COLLISION_DETECTION_BULLET_EXPORT __declspec(dllexport) - #define COLLISION_DETECTION_BULLET_IMPORT __declspec(dllimport) - #endif - #ifdef COLLISION_DETECTION_BULLET_BUILDING_DLL - #define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_EXPORT - #else - #define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_IMPORT - #endif - #define COLLISION_DETECTION_BULLET_PUBLIC_TYPE COLLISION_DETECTION_BULLET_PUBLIC - #define COLLISION_DETECTION_BULLET_LOCAL +#ifdef __GNUC__ +#define COLLISION_DETECTION_BULLET_EXPORT __attribute__((dllexport)) +#define COLLISION_DETECTION_BULLET_IMPORT __attribute__((dllimport)) #else - #define COLLISION_DETECTION_BULLET_EXPORT __attribute__ ((visibility("default"))) - #define COLLISION_DETECTION_BULLET_IMPORT - #if __GNUC__ >= 4 - #define COLLISION_DETECTION_BULLET_PUBLIC __attribute__ ((visibility("default"))) - #define COLLISION_DETECTION_BULLET_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define COLLISION_DETECTION_BULLET_PUBLIC - #define COLLISION_DETECTION_BULLET_LOCAL - #endif - #define COLLISION_DETECTION_BULLET_PUBLIC_TYPE +#define COLLISION_DETECTION_BULLET_EXPORT __declspec(dllexport) +#define COLLISION_DETECTION_BULLET_IMPORT __declspec(dllimport) +#endif +#ifdef COLLISION_DETECTION_BULLET_BUILDING_DLL +#define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_EXPORT +#else +#define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_IMPORT +#endif +#define COLLISION_DETECTION_BULLET_PUBLIC_TYPE COLLISION_DETECTION_BULLET_PUBLIC +#define COLLISION_DETECTION_BULLET_LOCAL +#else +#define COLLISION_DETECTION_BULLET_EXPORT __attribute__((visibility("default"))) +#define COLLISION_DETECTION_BULLET_IMPORT +#if __GNUC__ >= 4 +#define COLLISION_DETECTION_BULLET_PUBLIC __attribute__((visibility("default"))) +#define COLLISION_DETECTION_BULLET_LOCAL __attribute__((visibility("hidden"))) +#else +#define COLLISION_DETECTION_BULLET_PUBLIC +#define COLLISION_DETECTION_BULLET_LOCAL +#endif +#define COLLISION_DETECTION_BULLET_PUBLIC_TYPE #endif #endif // COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h index e142f2ecc2..1ff3885274 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h @@ -5,31 +5,31 @@ // 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_DLL - #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 +#ifdef __GNUC__ +#define COLLISION_DETECTION_FCL_EXPORT __attribute__((dllexport)) +#define COLLISION_DETECTION_FCL_IMPORT __attribute__((dllimport)) #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 +#define COLLISION_DETECTION_FCL_EXPORT __declspec(dllexport) +#define COLLISION_DETECTION_FCL_IMPORT __declspec(dllimport) +#endif +#ifdef COLLISION_DETECTION_FCL_BUILDING_DLL +#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 #endif // COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h index 3e58fe78f3..e7a8206cfa 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_KINEMATICS_BASE_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_KINEMATICS_BASE_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_KINEMATICS_BASE_EXPORT __declspec(dllexport) - #define MOVEIT_KINEMATICS_BASE_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_KINEMATICS_BASE_BUILDING_DLL - #define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_EXPORT - #else - #define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_IMPORT - #endif - #define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE MOVEIT_KINEMATICS_BASE_PUBLIC - #define MOVEIT_KINEMATICS_BASE_LOCAL +#ifdef __GNUC__ +#define MOVEIT_KINEMATICS_BASE_EXPORT __attribute__((dllexport)) +#define MOVEIT_KINEMATICS_BASE_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_KINEMATICS_BASE_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_KINEMATICS_BASE_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_KINEMATICS_BASE_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_KINEMATICS_BASE_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_KINEMATICS_BASE_PUBLIC - #define MOVEIT_KINEMATICS_BASE_LOCAL - #endif - #define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE +#define MOVEIT_KINEMATICS_BASE_EXPORT __declspec(dllexport) +#define MOVEIT_KINEMATICS_BASE_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_KINEMATICS_BASE_BUILDING_DLL +#define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_EXPORT +#else +#define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_IMPORT +#endif +#define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE MOVEIT_KINEMATICS_BASE_PUBLIC +#define MOVEIT_KINEMATICS_BASE_LOCAL +#else +#define MOVEIT_KINEMATICS_BASE_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_KINEMATICS_BASE_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_KINEMATICS_BASE_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_KINEMATICS_BASE_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_KINEMATICS_BASE_PUBLIC +#define MOVEIT_KINEMATICS_BASE_LOCAL +#endif +#define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE #endif #endif // MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ 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 85c225bd8b..e8e46b9dc5 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 @@ -87,7 +87,8 @@ using ObjectTypeMap = std::map +class MOVEIT_PLANNING_SCENE_PUBLIC PlanningScene : private boost::noncopyable, + public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h index cb52d5b029..d87f4c07dc 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_PLANNING_SCENE_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_PLANNING_SCENE_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_PLANNING_SCENE_EXPORT __declspec(dllexport) - #define MOVEIT_PLANNING_SCENE_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_PLANNING_SCENE_BUILDING_DLL - #define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_EXPORT - #else - #define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_IMPORT - #endif - #define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_PUBLIC - #define MOVEIT_PLANNING_SCENE_LOCAL +#ifdef __GNUC__ +#define MOVEIT_PLANNING_SCENE_EXPORT __attribute__((dllexport)) +#define MOVEIT_PLANNING_SCENE_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_PLANNING_SCENE_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_PLANNING_SCENE_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_PLANNING_SCENE_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_PLANNING_SCENE_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_PLANNING_SCENE_PUBLIC - #define MOVEIT_PLANNING_SCENE_LOCAL - #endif - #define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE +#define MOVEIT_PLANNING_SCENE_EXPORT __declspec(dllexport) +#define MOVEIT_PLANNING_SCENE_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_PLANNING_SCENE_BUILDING_DLL +#define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_EXPORT +#else +#define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_IMPORT +#endif +#define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_PUBLIC +#define MOVEIT_PLANNING_SCENE_LOCAL +#else +#define MOVEIT_PLANNING_SCENE_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_PLANNING_SCENE_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_PLANNING_SCENE_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_PLANNING_SCENE_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_PLANNING_SCENE_PUBLIC +#define MOVEIT_PLANNING_SCENE_LOCAL +#endif +#define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE #endif #endif // MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h index cba7504324..54f8f2900e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_MESH_FILTER_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_MESH_FILTER_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_MESH_FILTER_EXPORT __declspec(dllexport) - #define MOVEIT_MESH_FILTER_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_MESH_FILTER_BUILDING_DLL - #define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_EXPORT - #else - #define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_IMPORT - #endif - #define MOVEIT_MESH_FILTER_PUBLIC_TYPE MOVEIT_MESH_FILTER_PUBLIC - #define MOVEIT_MESH_FILTER_LOCAL +#ifdef __GNUC__ +#define MOVEIT_MESH_FILTER_EXPORT __attribute__((dllexport)) +#define MOVEIT_MESH_FILTER_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_MESH_FILTER_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_MESH_FILTER_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_MESH_FILTER_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_MESH_FILTER_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_MESH_FILTER_PUBLIC - #define MOVEIT_MESH_FILTER_LOCAL - #endif - #define MOVEIT_MESH_FILTER_PUBLIC_TYPE +#define MOVEIT_MESH_FILTER_EXPORT __declspec(dllexport) +#define MOVEIT_MESH_FILTER_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_MESH_FILTER_BUILDING_DLL +#define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_EXPORT +#else +#define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_IMPORT +#endif +#define MOVEIT_MESH_FILTER_PUBLIC_TYPE MOVEIT_MESH_FILTER_PUBLIC +#define MOVEIT_MESH_FILTER_LOCAL +#else +#define MOVEIT_MESH_FILTER_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_MESH_FILTER_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_MESH_FILTER_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_MESH_FILTER_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_MESH_FILTER_PUBLIC +#define MOVEIT_MESH_FILTER_LOCAL +#endif +#define MOVEIT_MESH_FILTER_PUBLIC_TYPE #endif #endif // MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h index 4ea9db4580..2857db6a18 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __declspec(dllexport) - #define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_ROS_PLANNING_PIPELINE_BUILDING_DLL - #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_EXPORT - #else - #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_IMPORT - #endif - #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC - #define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL +#ifdef __GNUC__ +#define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __attribute__((dllexport)) +#define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC - #define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL - #endif - #define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE +#define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __declspec(dllexport) +#define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_ROS_PLANNING_PIPELINE_BUILDING_DLL +#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_EXPORT +#else +#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_IMPORT +#endif +#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC +#define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL +#else +#define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC +#define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL +#endif +#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE #endif #endif // MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h index 7c94033d1a..959534c68e 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) - #define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_PLANNING_SCENE_MONITOR_BUILDING_DLL - #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_EXPORT - #else - #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_IMPORT - #endif - #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC - #define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL +#ifdef __GNUC__ +#define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __attribute__((dllexport)) +#define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC - #define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL - #endif - #define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE +#define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) +#define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_PLANNING_SCENE_MONITOR_BUILDING_DLL +#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_EXPORT +#else +#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_IMPORT +#endif +#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC +#define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL +#else +#define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC +#define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL +#endif +#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE #endif #endif // MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h index 5bd95a9bb0..266b2cb944 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__ ((dllexport)) - #define TRAJECTORY_EXECUTION_MANAGER_IMPORT __attribute__ ((dllimport)) - #else - #define TRAJECTORY_EXECUTION_MANAGER_EXPORT __declspec(dllexport) - #define TRAJECTORY_EXECUTION_MANAGER_IMPORT __declspec(dllimport) - #endif - #ifdef TRAJECTORY_EXECUTION_MANAGER_BUILDING_DLL - #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_EXPORT - #else - #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_IMPORT - #endif - #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE TRAJECTORY_EXECUTION_MANAGER_PUBLIC - #define TRAJECTORY_EXECUTION_MANAGER_LOCAL +#ifdef __GNUC__ +#define TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__((dllexport)) +#define TRAJECTORY_EXECUTION_MANAGER_IMPORT __attribute__((dllimport)) #else - #define TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__ ((visibility("default"))) - #define TRAJECTORY_EXECUTION_MANAGER_IMPORT - #if __GNUC__ >= 4 - #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC __attribute__ ((visibility("default"))) - #define TRAJECTORY_EXECUTION_MANAGER_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC - #define TRAJECTORY_EXECUTION_MANAGER_LOCAL - #endif - #define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE +#define TRAJECTORY_EXECUTION_MANAGER_EXPORT __declspec(dllexport) +#define TRAJECTORY_EXECUTION_MANAGER_IMPORT __declspec(dllimport) +#endif +#ifdef TRAJECTORY_EXECUTION_MANAGER_BUILDING_DLL +#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_EXPORT +#else +#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_IMPORT +#endif +#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE TRAJECTORY_EXECUTION_MANAGER_PUBLIC +#define TRAJECTORY_EXECUTION_MANAGER_LOCAL +#else +#define TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__((visibility("default"))) +#define TRAJECTORY_EXECUTION_MANAGER_IMPORT +#if __GNUC__ >= 4 +#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC __attribute__((visibility("default"))) +#define TRAJECTORY_EXECUTION_MANAGER_LOCAL __attribute__((visibility("hidden"))) +#else +#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC +#define TRAJECTORY_EXECUTION_MANAGER_LOCAL +#endif +#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE #endif #endif // TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h index a81098cdb9..22b8af3ecf 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) - #define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_MOVE_GROUP_INTERFACE_BUILDING_DLL - #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_EXPORT - #else - #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_IMPORT - #endif - #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC - #define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL +#ifdef __GNUC__ +#define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __attribute__((dllexport)) +#define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC - #define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL - #endif - #define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE +#define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) +#define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_MOVE_GROUP_INTERFACE_BUILDING_DLL +#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_EXPORT +#else +#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_IMPORT +#endif +#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC +#define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL +#else +#define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC +#define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL +#endif +#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE #endif #endif // MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h index bc7d9e9c10..24f5793359 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __declspec(dllexport) - #define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_ROS_ROBOT_INTERACTION_BUILDING_DLL - #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_EXPORT - #else - #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_IMPORT - #endif - #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC - #define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL +#ifdef __GNUC__ +#define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __attribute__((dllexport)) +#define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC - #define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL - #endif - #define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE +#define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __declspec(dllexport) +#define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_ROS_ROBOT_INTERACTION_BUILDING_DLL +#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_EXPORT +#else +#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_IMPORT +#endif +#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC +#define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL +#else +#define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC +#define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL +#endif +#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE #endif #endif // MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h index d034ebdb2b..f3c500e13a 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT - #else - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT - #endif - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#ifdef __GNUC__ +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__((dllexport)) +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL - #endif - #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT +#else +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT +#endif +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#else +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#endif +#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE #endif #endif // MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h index 6360cb2452..ca29ac7103 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h @@ -5,31 +5,31 @@ // https://gcc.gnu.org/wiki/Visibility #if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define MOVEIT_ROS_WAREHOUSE_EXPORT __attribute__ ((dllexport)) - #define MOVEIT_ROS_WAREHOUSE_IMPORT __attribute__ ((dllimport)) - #else - #define MOVEIT_ROS_WAREHOUSE_EXPORT __declspec(dllexport) - #define MOVEIT_ROS_WAREHOUSE_IMPORT __declspec(dllimport) - #endif - #ifdef MOVEIT_ROS_WAREHOUSE_BUILDING_DLL - #define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_EXPORT - #else - #define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_IMPORT - #endif - #define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE MOVEIT_ROS_WAREHOUSE_PUBLIC - #define MOVEIT_ROS_WAREHOUSE_LOCAL +#ifdef __GNUC__ +#define MOVEIT_ROS_WAREHOUSE_EXPORT __attribute__((dllexport)) +#define MOVEIT_ROS_WAREHOUSE_IMPORT __attribute__((dllimport)) #else - #define MOVEIT_ROS_WAREHOUSE_EXPORT __attribute__ ((visibility("default"))) - #define MOVEIT_ROS_WAREHOUSE_IMPORT - #if __GNUC__ >= 4 - #define MOVEIT_ROS_WAREHOUSE_PUBLIC __attribute__ ((visibility("default"))) - #define MOVEIT_ROS_WAREHOUSE_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define MOVEIT_ROS_WAREHOUSE_PUBLIC - #define MOVEIT_ROS_WAREHOUSE_LOCAL - #endif - #define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE +#define MOVEIT_ROS_WAREHOUSE_EXPORT __declspec(dllexport) +#define MOVEIT_ROS_WAREHOUSE_IMPORT __declspec(dllimport) +#endif +#ifdef MOVEIT_ROS_WAREHOUSE_BUILDING_DLL +#define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_EXPORT +#else +#define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_IMPORT +#endif +#define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE MOVEIT_ROS_WAREHOUSE_PUBLIC +#define MOVEIT_ROS_WAREHOUSE_LOCAL +#else +#define MOVEIT_ROS_WAREHOUSE_EXPORT __attribute__((visibility("default"))) +#define MOVEIT_ROS_WAREHOUSE_IMPORT +#if __GNUC__ >= 4 +#define MOVEIT_ROS_WAREHOUSE_PUBLIC __attribute__((visibility("default"))) +#define MOVEIT_ROS_WAREHOUSE_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOVEIT_ROS_WAREHOUSE_PUBLIC +#define MOVEIT_ROS_WAREHOUSE_LOCAL +#endif +#define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE #endif #endif // MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp index 4ce33daefe..6c4ffa6386 100644 --- a/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp +++ b/moveit_ros/warehouse/warehouse/src/warehouse_connector.cpp @@ -42,10 +42,17 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.warehouse_connector"); #ifdef _WIN32 - void kill(int, int) { RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); } // Should never be called - int fork() { RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); return -1; } +void kill(int, int) +{ + RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); +} // Should never be called +int fork() +{ + RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows"); + return -1; +} #else - #include +#include #endif namespace moveit_warehouse From de9bd9c0dc53e6c63e621159820bd0b09e58d50a Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 1 Jul 2021 10:20:55 -0500 Subject: [PATCH 37/54] Fix CI --- moveit_core/CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 4433c105c5..326c48ccaa 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -31,6 +31,7 @@ else() find_package(FCL 0.5.0) set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") set(FCL_NAME "FCL") + set(EXTRA_INCLUDE "FCL") find_package(Bullet ${BULLET_VERSION} REQUIRED) endif() @@ -144,7 +145,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS eigen3_cmake_module OCTOMAP Bullet - ${FCL_NAME} + ${EXTRA_INCLUDE} ) pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) From 112c92634c2335e2c4aebe75ae1cf671b49c3839 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 1 Jul 2021 20:13:33 -0500 Subject: [PATCH 38/54] Fix visibility control includes --- .../allvalid/collision_detector_allocator_allvalid.h | 3 ++- .../collision_detector_allocator_bullet.h | 2 +- .../collision_detection_fcl/collision_detector_allocator_fcl.h | 2 +- .../include/moveit/kinematics_base/kinematics_base.h | 2 +- .../include/moveit/planning_scene/planning_scene.h | 2 +- .../include/moveit/mesh_filter/stereo_camera_model.h | 2 +- .../include/moveit/planning_pipeline/planning_pipeline.h | 2 +- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 2 +- .../trajectory_execution_manager.h | 2 +- .../include/moveit/move_group_interface/move_group_interface.h | 2 +- .../include/moveit/robot_interaction/kinematic_options_map.h | 2 +- .../moveit/planning_scene_rviz_plugin/planning_scene_display.h | 2 +- .../warehouse/include/moveit/warehouse/constraints_storage.h | 2 +- .../include/moveit/warehouse/planning_scene_storage.h | 2 +- .../warehouse/include/moveit/warehouse/state_storage.h | 2 +- 15 files changed, 16 insertions(+), 15 deletions(-) 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 08345b4035..7c560b85e7 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,7 +38,8 @@ #include #include -#include "../visibility_control.h" + +#include namespace collision_detection { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 30c69e7d4a..ccb53accf7 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -39,7 +39,7 @@ #include #include -#include "visibility_control.h" +#include namespace collision_detection { 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 501de43166..d6cda534f5 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -39,7 +39,7 @@ #include #include -#include "visibility_control.h" +#include namespace collision_detection { 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 f7f72202de..fbc3dcb66b 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -43,7 +43,7 @@ #include #include -#include "visibility_control.h" +#include namespace moveit { 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 e8e46b9dc5..6bee762d87 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -57,7 +57,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "visibility_control.h" +#include /** \brief This namespace includes the central class for representing planning contexts */ namespace planning_scene 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 7b48cf4380..f9e796a7ff 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -39,7 +39,7 @@ #include #include -#include "visibility_control.h" +#include namespace mesh_filter { 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 e3320768da..c77f7921db 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -45,7 +45,7 @@ #include -#include "visibility_control.h" +#include /** \brief Planning pipeline */ namespace planning_pipeline 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 478d7b6aac..c13dda28f0 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 @@ -53,7 +53,7 @@ #include #include -#include "visibility_control.h" +#include namespace planning_scene_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 7a615513c4..6d71e18a44 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 @@ -50,7 +50,7 @@ #include #include -#include "visibility_control.h" +#include namespace trajectory_execution_manager { 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 2287f1a376..b71569014d 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -60,7 +60,7 @@ #include #include -#include "visibility_control.h" +#include namespace moveit { 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 2ce6e9fb25..f6034548ec 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -40,7 +40,7 @@ #include #include -#include "visibility_control.h" +#include namespace robot_interaction { 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 54026859ab..cc432b8a76 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -47,7 +47,7 @@ #include #endif -#include "visibility_control.h" +#include namespace Ogre { 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 891a11357d..fb1c0c5c08 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -40,7 +40,7 @@ #include #include -#include "visibility_control.h" +#include namespace moveit_warehouse { 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 611f58f022..463e74562d 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -42,7 +42,7 @@ #include #include -#include "visibility_control.h" +#include namespace moveit_warehouse { 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 bc1f172224..698e296d42 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -40,7 +40,7 @@ #include #include -#include "visibility_control.h" +#include namespace moveit_warehouse { From 6407d140beb908a03f52d2140afaedc3d3b49317 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 1 Jul 2021 20:23:36 -0500 Subject: [PATCH 39/54] Add license to visibility control --- .../collision_detection/visibility_control.h | 35 +++++++++++++++++++ .../visibility_control.h | 35 +++++++++++++++++++ .../visibility_control.h | 35 +++++++++++++++++++ .../kinematics_base/visibility_control.h | 35 +++++++++++++++++++ .../planning_scene/visibility_control.h | 35 +++++++++++++++++++ .../moveit/mesh_filter/visibility_control.h | 35 +++++++++++++++++++ .../planning_pipeline/visibility_control.h | 35 +++++++++++++++++++ .../visibility_control.h | 35 +++++++++++++++++++ .../visibility_control.h | 35 +++++++++++++++++++ .../move_group_interface/visibility_control.h | 35 +++++++++++++++++++ .../robot_interaction/visibility_control.h | 35 +++++++++++++++++++ .../visibility_control.h | 35 +++++++++++++++++++ .../moveit/warehouse/visibility_control.h | 35 +++++++++++++++++++ 13 files changed, 455 insertions(+) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h index 214e627fe8..4b33d196be 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ #define MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h index 191cdd5821..53515a4eb6 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_BULLET__VISIBILITY_CONTROL_H_ #define COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h index 1ff3885274..e4b92ba53d 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_H_ #define COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h index e7a8206cfa..7465e60250 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ #define MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h index d87f4c07dc..f948862ed4 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_SCENE__VISIBILITY_CONTROL_H_ #define MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h index 54f8f2900e..df01917fff 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_MESH_FILTER__VISIBILITY_CONTROL_H_ #define MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h index 2857db6a18..c3838b7305 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ #define MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h index 959534c68e..546348c74a 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_SCENE_MONITOR__VISIBILITY_CONTROL_H_ #define MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h index 266b2cb944..1e3fd548f5 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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 TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ #define TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h index 22b8af3ecf..8376e4c889 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ #define MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h index 24f5793359..9d4d5e9119 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ #define MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h index f3c500e13a..8df739c4ac 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h index ca29ac7103..11dc0f8591 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h @@ -1,3 +1,38 @@ +// Copyright (c) 2021, 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_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ #define MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ From 6d14df0268c441baa14dfb156b49e85d1ea0c237 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 1 Jul 2021 21:43:44 -0500 Subject: [PATCH 40/54] Use same naming convention for visibility control --- .../collision_detection/CMakeLists.txt | 2 +- .../collision_detector_allocator_allvalid.h | 2 +- .../collision_detection/visibility_control.h | 38 +++++++++---------- moveit_core/kinematics_base/CMakeLists.txt | 2 +- .../moveit/kinematics_base/kinematics_base.h | 2 +- .../kinematics_base/visibility_control.h | 38 +++++++++---------- moveit_core/planning_scene/CMakeLists.txt | 2 +- .../moveit/planning_scene/planning_scene.h | 2 +- .../planning_scene/visibility_control.h | 38 +++++++++---------- .../perception/mesh_filter/CMakeLists.txt | 2 +- .../moveit/mesh_filter/stereo_camera_model.h | 2 +- .../moveit/mesh_filter/visibility_control.h | 38 +++++++++---------- .../planning/planning_pipeline/CMakeLists.txt | 2 +- .../planning_pipeline/planning_pipeline.h | 2 +- .../planning_pipeline/visibility_control.h | 38 +++++++++---------- .../planning_scene_monitor/CMakeLists.txt | 2 +- .../planning_scene_monitor.h | 2 +- .../visibility_control.h | 38 +++++++++---------- .../move_group_interface/CMakeLists.txt | 2 +- .../move_group_interface.h | 2 +- .../move_group_interface/visibility_control.h | 38 +++++++++---------- moveit_ros/robot_interaction/CMakeLists.txt | 2 +- .../robot_interaction/kinematic_options_map.h | 2 +- .../robot_interaction/visibility_control.h | 38 +++++++++---------- .../planning_scene_rviz_plugin/CMakeLists.txt | 2 +- .../planning_scene_display.h | 2 +- .../visibility_control.h | 38 +++++++++---------- moveit_ros/warehouse/warehouse/CMakeLists.txt | 2 +- .../moveit/warehouse/constraints_storage.h | 2 +- .../moveit/warehouse/planning_scene_storage.h | 2 +- .../include/moveit/warehouse/state_storage.h | 2 +- .../moveit/warehouse/visibility_control.h | 38 +++++++++---------- 32 files changed, 212 insertions(+), 212 deletions(-) diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index 08cb94b116..d68979186a 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -12,7 +12,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE MOVEIT_COLLISION_DETECTION_BUILDING_DLL) +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE COLLISION_DETECTION_BUILDING_DLL) 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 7c560b85e7..e14f587f4d 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 @@ -44,7 +44,7 @@ namespace collision_detection { /** \brief An allocator for AllValid collision detectors */ -class MOVEIT_COLLISION_DETECTION_PUBLIC CollisionDetectorAllocatorAllValid +class COLLISION_DETECTION_PUBLIC CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h index 4b33d196be..33e2c7fd54 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ -#define MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ +#ifndef COLLISION_DETECTION__VISIBILITY_CONTROL_H_ +#define COLLISION_DETECTION__VISIBILITY_CONTROL_H_ // 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_COLLISION_DETECTION_EXPORT __attribute__((dllexport)) -#define MOVEIT_COLLISION_DETECTION_IMPORT __attribute__((dllimport)) +#define COLLISION_DETECTION_EXPORT __attribute__((dllexport)) +#define COLLISION_DETECTION_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_COLLISION_DETECTION_EXPORT __declspec(dllexport) -#define MOVEIT_COLLISION_DETECTION_IMPORT __declspec(dllimport) +#define COLLISION_DETECTION_EXPORT __declspec(dllexport) +#define COLLISION_DETECTION_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_COLLISION_DETECTION_BUILDING_DLL -#define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_EXPORT +#ifdef COLLISION_DETECTION_BUILDING_DLL +#define COLLISION_DETECTION_PUBLIC COLLISION_DETECTION_EXPORT #else -#define MOVEIT_COLLISION_DETECTION_PUBLIC MOVEIT_COLLISION_DETECTION_IMPORT +#define COLLISION_DETECTION_PUBLIC COLLISION_DETECTION_IMPORT #endif -#define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE MOVEIT_COLLISION_DETECTION_PUBLIC -#define MOVEIT_COLLISION_DETECTION_LOCAL +#define COLLISION_DETECTION_PUBLIC_TYPE COLLISION_DETECTION_PUBLIC +#define COLLISION_DETECTION_LOCAL #else -#define MOVEIT_COLLISION_DETECTION_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_COLLISION_DETECTION_IMPORT +#define COLLISION_DETECTION_EXPORT __attribute__((visibility("default"))) +#define COLLISION_DETECTION_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_COLLISION_DETECTION_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_COLLISION_DETECTION_LOCAL __attribute__((visibility("hidden"))) +#define COLLISION_DETECTION_PUBLIC __attribute__((visibility("default"))) +#define COLLISION_DETECTION_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_COLLISION_DETECTION_PUBLIC -#define MOVEIT_COLLISION_DETECTION_LOCAL +#define COLLISION_DETECTION_PUBLIC +#define COLLISION_DETECTION_LOCAL #endif -#define MOVEIT_COLLISION_DETECTION_PUBLIC_TYPE +#define COLLISION_DETECTION_PUBLIC_TYPE #endif -#endif // MOVEIT_COLLISION_DETECTION__VISIBILITY_CONTROL_H_ +#endif // COLLISION_DETECTION__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index 082f17f453..d9e447dd1e 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -3,7 +3,7 @@ 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}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_KINEMATICS_BASE_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "KINEMATICS_BASE_BUILDING_DLL") # This line is needed to ensure that messages are done being built before this is built ament_target_dependencies( 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 fbc3dcb66b..f1674dc33a 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 @@ -142,7 +142,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, W * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class MOVEIT_KINEMATICS_BASE_PUBLIC 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.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h index 7465e60250..be4e7f45dc 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ -#define MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ +#ifndef KINEMATICS_BASE__VISIBILITY_CONTROL_H_ +#define KINEMATICS_BASE__VISIBILITY_CONTROL_H_ // 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_KINEMATICS_BASE_EXPORT __attribute__((dllexport)) -#define MOVEIT_KINEMATICS_BASE_IMPORT __attribute__((dllimport)) +#define KINEMATICS_BASE_EXPORT __attribute__((dllexport)) +#define KINEMATICS_BASE_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_KINEMATICS_BASE_EXPORT __declspec(dllexport) -#define MOVEIT_KINEMATICS_BASE_IMPORT __declspec(dllimport) +#define KINEMATICS_BASE_EXPORT __declspec(dllexport) +#define KINEMATICS_BASE_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_KINEMATICS_BASE_BUILDING_DLL -#define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_EXPORT +#ifdef KINEMATICS_BASE_BUILDING_DLL +#define KINEMATICS_BASE_PUBLIC KINEMATICS_BASE_EXPORT #else -#define MOVEIT_KINEMATICS_BASE_PUBLIC MOVEIT_KINEMATICS_BASE_IMPORT +#define KINEMATICS_BASE_PUBLIC KINEMATICS_BASE_IMPORT #endif -#define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE MOVEIT_KINEMATICS_BASE_PUBLIC -#define MOVEIT_KINEMATICS_BASE_LOCAL +#define KINEMATICS_BASE_PUBLIC_TYPE KINEMATICS_BASE_PUBLIC +#define KINEMATICS_BASE_LOCAL #else -#define MOVEIT_KINEMATICS_BASE_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_KINEMATICS_BASE_IMPORT +#define KINEMATICS_BASE_EXPORT __attribute__((visibility("default"))) +#define KINEMATICS_BASE_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_KINEMATICS_BASE_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_KINEMATICS_BASE_LOCAL __attribute__((visibility("hidden"))) +#define KINEMATICS_BASE_PUBLIC __attribute__((visibility("default"))) +#define KINEMATICS_BASE_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_KINEMATICS_BASE_PUBLIC -#define MOVEIT_KINEMATICS_BASE_LOCAL +#define KINEMATICS_BASE_PUBLIC +#define KINEMATICS_BASE_LOCAL #endif -#define MOVEIT_KINEMATICS_BASE_PUBLIC_TYPE +#define KINEMATICS_BASE_PUBLIC_TYPE #endif -#endif // MOVEIT_KINEMATICS_BASE__VISIBILITY_CONTROL_H_ +#endif // KINEMATICS_BASE__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index 70c6b8654d..0628361dac 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -3,7 +3,7 @@ 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}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_PLANNING_SCENE_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_SCENE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} Boost rclcpp 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 6bee762d87..99f6164d6f 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 @@ -87,7 +87,7 @@ using ObjectTypeMap = std::map { public: diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h index f948862ed4..a481f3d47f 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ -#define MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ +#ifndef PLANNING_SCENE__VISIBILITY_CONTROL_H_ +#define PLANNING_SCENE__VISIBILITY_CONTROL_H_ // 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_SCENE_EXPORT __attribute__((dllexport)) -#define MOVEIT_PLANNING_SCENE_IMPORT __attribute__((dllimport)) +#define PLANNING_SCENE_EXPORT __attribute__((dllexport)) +#define PLANNING_SCENE_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_PLANNING_SCENE_EXPORT __declspec(dllexport) -#define MOVEIT_PLANNING_SCENE_IMPORT __declspec(dllimport) +#define PLANNING_SCENE_EXPORT __declspec(dllexport) +#define PLANNING_SCENE_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_PLANNING_SCENE_BUILDING_DLL -#define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_EXPORT +#ifdef PLANNING_SCENE_BUILDING_DLL +#define PLANNING_SCENE_PUBLIC PLANNING_SCENE_EXPORT #else -#define MOVEIT_PLANNING_SCENE_PUBLIC MOVEIT_PLANNING_SCENE_IMPORT +#define PLANNING_SCENE_PUBLIC PLANNING_SCENE_IMPORT #endif -#define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_PUBLIC -#define MOVEIT_PLANNING_SCENE_LOCAL +#define PLANNING_SCENE_PUBLIC_TYPE PLANNING_SCENE_PUBLIC +#define PLANNING_SCENE_LOCAL #else -#define MOVEIT_PLANNING_SCENE_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_PLANNING_SCENE_IMPORT +#define PLANNING_SCENE_EXPORT __attribute__((visibility("default"))) +#define PLANNING_SCENE_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_PLANNING_SCENE_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_PLANNING_SCENE_LOCAL __attribute__((visibility("hidden"))) +#define PLANNING_SCENE_PUBLIC __attribute__((visibility("default"))) +#define PLANNING_SCENE_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_PLANNING_SCENE_PUBLIC -#define MOVEIT_PLANNING_SCENE_LOCAL +#define PLANNING_SCENE_PUBLIC +#define PLANNING_SCENE_LOCAL #endif -#define MOVEIT_PLANNING_SCENE_PUBLIC_TYPE +#define PLANNING_SCENE_PUBLIC_TYPE #endif -#endif // MOVEIT_PLANNING_SCENE__VISIBILITY_CONTROL_H_ +#endif // PLANNING_SCENE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 541e562e24..b796a17f61 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -16,7 +16,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} Boost ) target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} GLUT::GLUT ${GLEW_LIBRARIES}) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_MESH_FILTER_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MESH_FILTER_BUILDING_DLL") target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) 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 f9e796a7ff..cc82a187cb 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 @@ -47,7 +47,7 @@ namespace mesh_filter * \brief Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices * \author Suat Gedikli */ -class MOVEIT_MESH_FILTER_PUBLIC 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.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h index df01917fff..d2920a4a42 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ -#define MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ +#ifndef MESH_FILTER__VISIBILITY_CONTROL_H_ +#define MESH_FILTER__VISIBILITY_CONTROL_H_ // 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_MESH_FILTER_EXPORT __attribute__((dllexport)) -#define MOVEIT_MESH_FILTER_IMPORT __attribute__((dllimport)) +#define MESH_FILTER_EXPORT __attribute__((dllexport)) +#define MESH_FILTER_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_MESH_FILTER_EXPORT __declspec(dllexport) -#define MOVEIT_MESH_FILTER_IMPORT __declspec(dllimport) +#define MESH_FILTER_EXPORT __declspec(dllexport) +#define MESH_FILTER_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_MESH_FILTER_BUILDING_DLL -#define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_EXPORT +#ifdef MESH_FILTER_BUILDING_DLL +#define MESH_FILTER_PUBLIC MESH_FILTER_EXPORT #else -#define MOVEIT_MESH_FILTER_PUBLIC MOVEIT_MESH_FILTER_IMPORT +#define MESH_FILTER_PUBLIC MESH_FILTER_IMPORT #endif -#define MOVEIT_MESH_FILTER_PUBLIC_TYPE MOVEIT_MESH_FILTER_PUBLIC -#define MOVEIT_MESH_FILTER_LOCAL +#define MESH_FILTER_PUBLIC_TYPE MESH_FILTER_PUBLIC +#define MESH_FILTER_LOCAL #else -#define MOVEIT_MESH_FILTER_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_MESH_FILTER_IMPORT +#define MESH_FILTER_EXPORT __attribute__((visibility("default"))) +#define MESH_FILTER_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_MESH_FILTER_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_MESH_FILTER_LOCAL __attribute__((visibility("hidden"))) +#define MESH_FILTER_PUBLIC __attribute__((visibility("default"))) +#define MESH_FILTER_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_MESH_FILTER_PUBLIC -#define MOVEIT_MESH_FILTER_LOCAL +#define MESH_FILTER_PUBLIC +#define MESH_FILTER_LOCAL #endif -#define MOVEIT_MESH_FILTER_PUBLIC_TYPE +#define MESH_FILTER_PUBLIC_TYPE #endif -#endif // MOVEIT_MESH_FILTER__VISIBILITY_CONTROL_H_ +#endif // MESH_FILTER__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index b5272a604f..e65bfa4b29 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -2,7 +2,7 @@ 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}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_ROS_PLANNING_PIPELINE_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_PIPELINE_BUILDING_DLL") 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 c77f7921db..c00164b691 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 @@ -56,7 +56,7 @@ namespace planning_pipeline planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. */ -class MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC PlanningPipeline +class 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.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h index c3838b7305..bbb24f4894 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ -#define MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ +#ifndef PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ +#define PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ // 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_ROS_PLANNING_PIPELINE_EXPORT __attribute__((dllexport)) -#define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __attribute__((dllimport)) +#define PLANNING_PIPELINE_EXPORT __attribute__((dllexport)) +#define PLANNING_PIPELINE_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __declspec(dllexport) -#define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT __declspec(dllimport) +#define PLANNING_PIPELINE_EXPORT __declspec(dllexport) +#define PLANNING_PIPELINE_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_ROS_PLANNING_PIPELINE_BUILDING_DLL -#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_EXPORT +#ifdef PLANNING_PIPELINE_BUILDING_DLL +#define PLANNING_PIPELINE_PUBLIC PLANNING_PIPELINE_EXPORT #else -#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC MOVEIT_ROS_PLANNING_PIPELINE_IMPORT +#define PLANNING_PIPELINE_PUBLIC PLANNING_PIPELINE_IMPORT #endif -#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC -#define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL +#define PLANNING_PIPELINE_PUBLIC_TYPE PLANNING_PIPELINE_PUBLIC +#define PLANNING_PIPELINE_LOCAL #else -#define MOVEIT_ROS_PLANNING_PIPELINE_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_ROS_PLANNING_PIPELINE_IMPORT +#define PLANNING_PIPELINE_EXPORT __attribute__((visibility("default"))) +#define PLANNING_PIPELINE_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL __attribute__((visibility("hidden"))) +#define PLANNING_PIPELINE_PUBLIC __attribute__((visibility("default"))) +#define PLANNING_PIPELINE_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC -#define MOVEIT_ROS_PLANNING_PIPELINE_LOCAL +#define PLANNING_PIPELINE_PUBLIC +#define PLANNING_PIPELINE_LOCAL #endif -#define MOVEIT_ROS_PLANNING_PIPELINE_PUBLIC_TYPE +#define PLANNING_PIPELINE_PUBLIC_TYPE #endif -#endif // MOVEIT_ROS_PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ +#endif // PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index e8c1b30a29..3665647e19 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/trajectory_monitor.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_PLANNING_SCENE_MONITOR_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_SCENE_MONITOR_BUILDING_DLL") 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 c13dda28f0..d00148f3d4 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 @@ -62,7 +62,7 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC 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.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h index 546348c74a..ac38d807d3 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ -#define MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ +#ifndef PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ +#define PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ // 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_SCENE_MONITOR_EXPORT __attribute__((dllexport)) -#define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __attribute__((dllimport)) +#define PLANNING_SCENE_MONITOR_EXPORT __attribute__((dllexport)) +#define PLANNING_SCENE_MONITOR_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) -#define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) +#define PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) +#define PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_PLANNING_SCENE_MONITOR_BUILDING_DLL -#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_EXPORT +#ifdef PLANNING_SCENE_MONITOR_BUILDING_DLL +#define PLANNING_SCENE_MONITOR_PUBLIC PLANNING_SCENE_MONITOR_EXPORT #else -#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC MOVEIT_PLANNING_SCENE_MONITOR_IMPORT +#define PLANNING_SCENE_MONITOR_PUBLIC PLANNING_SCENE_MONITOR_IMPORT #endif -#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC -#define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL +#define PLANNING_SCENE_MONITOR_PUBLIC_TYPE PLANNING_SCENE_MONITOR_PUBLIC +#define PLANNING_SCENE_MONITOR_LOCAL #else -#define MOVEIT_PLANNING_SCENE_MONITOR_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_PLANNING_SCENE_MONITOR_IMPORT +#define PLANNING_SCENE_MONITOR_EXPORT __attribute__((visibility("default"))) +#define PLANNING_SCENE_MONITOR_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL __attribute__((visibility("hidden"))) +#define PLANNING_SCENE_MONITOR_PUBLIC __attribute__((visibility("default"))) +#define PLANNING_SCENE_MONITOR_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC -#define MOVEIT_PLANNING_SCENE_MONITOR_LOCAL +#define PLANNING_SCENE_MONITOR_PUBLIC +#define PLANNING_SCENE_MONITOR_LOCAL #endif -#define MOVEIT_PLANNING_SCENE_MONITOR_PUBLIC_TYPE +#define PLANNING_SCENE_MONITOR_PUBLIC_TYPE #endif -#endif // MOVEIT_PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ +#endif // PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index b1676a5793..1e63a2be04 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -3,7 +3,7 @@ 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}") target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${Boost_THREAD_LIBRARY}) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_MOVE_GROUP_INTERFACE_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVE_GROUP_INTERFACE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_msgs 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 b71569014d..619c889401 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 @@ -103,7 +103,7 @@ MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, Con \brief Client class to conveniently use the ROS interfaces provided by the move_group node. This class includes many default settings to make things easy to use. */ -class MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC 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.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h index 8376e4c889..f96e025439 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ -#define MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ +#ifndef MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ +#define MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ // 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_MOVE_GROUP_INTERFACE_EXPORT __attribute__((dllexport)) -#define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __attribute__((dllimport)) +#define MOVE_GROUP_INTERFACE_EXPORT __attribute__((dllexport)) +#define MOVE_GROUP_INTERFACE_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) -#define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) +#define MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) +#define MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_MOVE_GROUP_INTERFACE_BUILDING_DLL -#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_EXPORT +#ifdef MOVE_GROUP_INTERFACE_BUILDING_DLL +#define MOVE_GROUP_INTERFACE_PUBLIC MOVE_GROUP_INTERFACE_EXPORT #else -#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC MOVEIT_MOVE_GROUP_INTERFACE_IMPORT +#define MOVE_GROUP_INTERFACE_PUBLIC MOVE_GROUP_INTERFACE_IMPORT #endif -#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC -#define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL +#define MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVE_GROUP_INTERFACE_PUBLIC +#define MOVE_GROUP_INTERFACE_LOCAL #else -#define MOVEIT_MOVE_GROUP_INTERFACE_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_MOVE_GROUP_INTERFACE_IMPORT +#define MOVE_GROUP_INTERFACE_EXPORT __attribute__((visibility("default"))) +#define MOVE_GROUP_INTERFACE_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) +#define MOVE_GROUP_INTERFACE_PUBLIC __attribute__((visibility("default"))) +#define MOVE_GROUP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC -#define MOVEIT_MOVE_GROUP_INTERFACE_LOCAL +#define MOVE_GROUP_INTERFACE_PUBLIC +#define MOVE_GROUP_INTERFACE_LOCAL #endif -#define MOVEIT_MOVE_GROUP_INTERFACE_PUBLIC_TYPE +#define MOVE_GROUP_INTERFACE_PUBLIC_TYPE #endif -#endif // MOVEIT_MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ +#endif // MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index ab8675b81c..5edbb52c90 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -36,7 +36,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/robot_interaction.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVEIT_ROS_ROBOT_INTERACTION_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "ROBOT_INTERACTION_BUILDING_DLL") 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 f6034548ec..807a66e5b9 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 @@ -46,7 +46,7 @@ namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC 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.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h index 9d4d5e9119..956d411039 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ -#define MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ +#ifndef ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ +#define ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ // 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_ROS_ROBOT_INTERACTION_EXPORT __attribute__((dllexport)) -#define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __attribute__((dllimport)) +#define ROBOT_INTERACTION_EXPORT __attribute__((dllexport)) +#define ROBOT_INTERACTION_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __declspec(dllexport) -#define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT __declspec(dllimport) +#define ROBOT_INTERACTION_EXPORT __declspec(dllexport) +#define ROBOT_INTERACTION_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_ROS_ROBOT_INTERACTION_BUILDING_DLL -#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_EXPORT +#ifdef ROBOT_INTERACTION_BUILDING_DLL +#define ROBOT_INTERACTION_PUBLIC ROBOT_INTERACTION_EXPORT #else -#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC MOVEIT_ROS_ROBOT_INTERACTION_IMPORT +#define ROBOT_INTERACTION_PUBLIC ROBOT_INTERACTION_IMPORT #endif -#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC -#define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL +#define ROBOT_INTERACTION_PUBLIC_TYPE ROBOT_INTERACTION_PUBLIC +#define ROBOT_INTERACTION_LOCAL #else -#define MOVEIT_ROS_ROBOT_INTERACTION_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_ROS_ROBOT_INTERACTION_IMPORT +#define ROBOT_INTERACTION_EXPORT __attribute__((visibility("default"))) +#define ROBOT_INTERACTION_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL __attribute__((visibility("hidden"))) +#define ROBOT_INTERACTION_PUBLIC __attribute__((visibility("default"))) +#define ROBOT_INTERACTION_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC -#define MOVEIT_ROS_ROBOT_INTERACTION_LOCAL +#define ROBOT_INTERACTION_PUBLIC +#define ROBOT_INTERACTION_LOCAL #endif -#define MOVEIT_ROS_ROBOT_INTERACTION_PUBLIC_TYPE +#define ROBOT_INTERACTION_PUBLIC_TYPE #endif -#endif // MOVEIT_ROS_ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ +#endif // ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 0f57e4f824..fe84f5c710 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -4,7 +4,7 @@ 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}") -target_compile_definitions(${MOVEIT_LIB_NAME}_core PRIVATE "MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL") +target_compile_definitions(${MOVEIT_LIB_NAME}_core PRIVATE "PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL") target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools) ament_target_dependencies(${MOVEIT_LIB_NAME}_core rclcpp 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 cc432b8a76..f54fd880cf 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 @@ -68,7 +68,7 @@ class EnumProperty; namespace moveit_rviz_plugin { -class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PlanningSceneDisplay : public rviz_common::Display +class PLANNING_SCENE_RVIZ_PLUGIN_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.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h index 8df739c4ac..0fe3b83058 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ +#ifndef PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ +#define PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ // 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_SCENE_RVIZ_PLUGIN_EXPORT __attribute__((dllexport)) -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__((dllimport)) +#define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__((dllexport)) +#define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) +#define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) +#define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT +#ifdef PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL +#define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_EXPORT #else -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT +#define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_IMPORT #endif -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC +#define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL #else -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_IMPORT +#define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__((visibility("default"))) +#define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__((visibility("hidden"))) +#define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__((visibility("default"))) +#define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC +#define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL #endif -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE +#define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE #endif -#endif // MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ +#endif // PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index b7735182d0..4faa64a9de 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -11,7 +11,7 @@ add_library(${MOVEIT_LIB_NAME} SHARED ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp Boost moveit_core warehouse_ros moveit_ros_planning) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE MOVEIT_ROS_WAREHOUSE_BUILDING_DLL) +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE WAREHOUSE_BUILDING_DLL) add_executable(moveit_warehouse_broadcast src/broadcast.cpp) ament_target_dependencies(moveit_warehouse_broadcast rclcpp Boost warehouse_ros moveit_ros_planning) 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 fb1c0c5c08..f5c2353af3 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -49,7 +49,7 @@ typedef warehouse_ros::MessageCollection::Ptr Con MOVEIT_CLASS_FORWARD(ConstraintsStorage); // Defines ConstraintsStoragePtr, ConstPtr, WeakPtr... etc -class MOVEIT_ROS_WAREHOUSE_PUBLIC ConstraintsStorage : public MoveItMessageStorage +class WAREHOUSE_PUBLIC ConstraintsStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h index 463e74562d..befa4ecef9 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 @@ -56,7 +56,7 @@ typedef warehouse_ros::MessageCollection::Ptr MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc -class MOVEIT_ROS_WAREHOUSE_PUBLIC PlanningSceneStorage : public MoveItMessageStorage +class 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 698e296d42..de80cb753d 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -49,7 +49,7 @@ typedef warehouse_ros::MessageCollection::Ptr Robo MOVEIT_CLASS_FORWARD(RobotStateStorage); // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc -class MOVEIT_ROS_WAREHOUSE_PUBLIC RobotStateStorage : public MoveItMessageStorage +class WAREHOUSE_PUBLIC RobotStateStorage : public MoveItMessageStorage { public: static const std::string DATABASE_NAME; diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h index 11dc0f8591..b9c3d42a70 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h @@ -33,38 +33,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ -#define MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ +#ifndef WAREHOUSE__VISIBILITY_CONTROL_H_ +#define WAREHOUSE__VISIBILITY_CONTROL_H_ // 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_ROS_WAREHOUSE_EXPORT __attribute__((dllexport)) -#define MOVEIT_ROS_WAREHOUSE_IMPORT __attribute__((dllimport)) +#define WAREHOUSE_EXPORT __attribute__((dllexport)) +#define WAREHOUSE_IMPORT __attribute__((dllimport)) #else -#define MOVEIT_ROS_WAREHOUSE_EXPORT __declspec(dllexport) -#define MOVEIT_ROS_WAREHOUSE_IMPORT __declspec(dllimport) +#define WAREHOUSE_EXPORT __declspec(dllexport) +#define WAREHOUSE_IMPORT __declspec(dllimport) #endif -#ifdef MOVEIT_ROS_WAREHOUSE_BUILDING_DLL -#define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_EXPORT +#ifdef WAREHOUSE_BUILDING_DLL +#define WAREHOUSE_PUBLIC WAREHOUSE_EXPORT #else -#define MOVEIT_ROS_WAREHOUSE_PUBLIC MOVEIT_ROS_WAREHOUSE_IMPORT +#define WAREHOUSE_PUBLIC WAREHOUSE_IMPORT #endif -#define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE MOVEIT_ROS_WAREHOUSE_PUBLIC -#define MOVEIT_ROS_WAREHOUSE_LOCAL +#define WAREHOUSE_PUBLIC_TYPE WAREHOUSE_PUBLIC +#define WAREHOUSE_LOCAL #else -#define MOVEIT_ROS_WAREHOUSE_EXPORT __attribute__((visibility("default"))) -#define MOVEIT_ROS_WAREHOUSE_IMPORT +#define WAREHOUSE_EXPORT __attribute__((visibility("default"))) +#define WAREHOUSE_IMPORT #if __GNUC__ >= 4 -#define MOVEIT_ROS_WAREHOUSE_PUBLIC __attribute__((visibility("default"))) -#define MOVEIT_ROS_WAREHOUSE_LOCAL __attribute__((visibility("hidden"))) +#define WAREHOUSE_PUBLIC __attribute__((visibility("default"))) +#define WAREHOUSE_LOCAL __attribute__((visibility("hidden"))) #else -#define MOVEIT_ROS_WAREHOUSE_PUBLIC -#define MOVEIT_ROS_WAREHOUSE_LOCAL +#define WAREHOUSE_PUBLIC +#define WAREHOUSE_LOCAL #endif -#define MOVEIT_ROS_WAREHOUSE_PUBLIC_TYPE +#define WAREHOUSE_PUBLIC_TYPE #endif -#endif // MOVEIT_ROS_WAREHOUSE__VISIBILITY_CONTROL_H_ +#endif // WAREHOUSE__VISIBILITY_CONTROL_H_ From 2eeb5e0f34fef1cd20d38ceb09b855378ce5e4bc Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 1 Jul 2021 23:26:45 -0500 Subject: [PATCH 41/54] Fix merge issues --- .../moveit/robot_model/joint_model_group.h | 2 +- .../include/moveit_servo/servo_calcs.h | 3 +- moveit_ros/moveit_servo/src/servo_calcs.cpp | 36 +++++++++++-------- .../perception/mesh_filter/CMakeLists.txt | 1 - .../src/trajectory_execution_manager.cpp | 9 ++++- .../src/motion_planning_display.cpp | 8 +++++ 6 files changed, 40 insertions(+), 19 deletions(-) diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 256370877b..fc1faa5a60 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -136,7 +136,7 @@ class JointModelGroup /** \brief Get a joint by its name. Throw an exception if the joint is not part of this group. */ const JointModel* getJointModel(const std::string& joint) const; - /** \brief Get a joint by its name. Throw an exception if the joint is not part of this group. */ + /** \brief Get a link by its name. Throw an exception if the link is not part of this group. */ const LinkModel* getLinkModel(const std::string& link) const; /** \brief Get all the joints in this group (including fixed and mimic joints). */ 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 e6285ff744..0ea8c144e9 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h @@ -152,12 +152,13 @@ class ServoCalcs * Is handled differently for position vs. velocity control. */ void suddenHalt(trajectory_msgs::msg::JointTrajectory& joint_trajectory) const; + void suddenHalt(sensor_msgs::msg::JointState& joint_state) const; /** \brief Scale the delta theta to match joint velocity/acceleration limits */ void enforceVelLimits(Eigen::ArrayXd& delta_theta); /** \brief Avoid overshooting joint limits */ - bool enforcePositionLimits(trajectory_msgs::msg::JointTrajectory& joint_trajectory) const; + bool enforcePositionLimits(sensor_msgs::msg::JointState& joint_state) const; /** \brief Possibly calculate a velocity scaling factor, due to proximity of * singularity and direction of motion diff --git a/moveit_ros/moveit_servo/src/servo_calcs.cpp b/moveit_ros/moveit_servo/src/servo_calcs.cpp index a7aeaaff5f..3151ed02a1 100644 --- a/moveit_ros/moveit_servo/src/servo_calcs.cpp +++ b/moveit_ros/moveit_servo/src/servo_calcs.cpp @@ -578,17 +578,17 @@ bool ServoCalcs::internalServoUpdate(Eigen::ArrayXd& delta_theta, // Mark the lowpass filters as updated for this cycle updated_filters_ = true; - // compose outgoing message - composeJointTrajMessage(internal_joint_state_, joint_trajectory); - // Enforce SRDF position limits, might halt if needed, set prev_vel to 0 - if (!enforcePositionLimits(joint_trajectory)) + if (!enforcePositionLimits(internal_joint_state_)) { - suddenHalt(joint_trajectory); + suddenHalt(internal_joint_state_); status_ = StatusCode::JOINT_BOUND; prev_joint_velocity_.setZero(); } + // compose outgoing message + composeJointTrajMessage(internal_joint_state_, joint_trajectory); + // Modify the output message if we are using gazebo if (parameters_->use_gazebo) { @@ -777,7 +777,7 @@ void ServoCalcs::enforceVelLimits(Eigen::ArrayXd& delta_theta) delta_theta = velocity_scaling_factor * velocity * parameters_->publish_period; } -bool ServoCalcs::enforcePositionLimits(trajectory_msgs::msg::JointTrajectory& joint_trajectory) const +bool ServoCalcs::enforcePositionLimits(sensor_msgs::msg::JointState& joint_state) const { // Halt if we're past a joint margin and joint velocity is moving even farther past bool halting = false; @@ -785,17 +785,17 @@ bool ServoCalcs::enforcePositionLimits(trajectory_msgs::msg::JointTrajectory& jo for (auto joint : joint_model_group_->getActiveJointModels()) { - for (std::size_t c = 0; c < original_joint_state_.name.size(); ++c) + for (std::size_t c = 0; c < joint_state.name.size(); ++c) { // Use the most recent robot joint state - if (original_joint_state_.name[c] == joint->getName()) + if (joint_state.name[c] == joint->getName()) { - joint_angle = original_joint_state_.position.at(c); + joint_angle = joint_state.position.at(c); break; } } - if (!current_state_->satisfiesPositionBounds(joint, -parameters_->joint_limit_margin)) + if (!joint->satisfiesPositionBounds(&joint_angle, -parameters_->joint_limit_margin)) { const std::vector limits = joint->getVariableBoundsMsg(); @@ -803,13 +803,12 @@ bool ServoCalcs::enforcePositionLimits(trajectory_msgs::msg::JointTrajectory& jo if (!limits.empty()) { // Check if pending velocity command is moving in the right direction - auto joint_itr = - std::find(joint_trajectory.joint_names.begin(), joint_trajectory.joint_names.end(), joint->getName()); - auto joint_idx = std::distance(joint_trajectory.joint_names.begin(), joint_itr); + auto joint_itr = std::find(joint_state.name.begin(), joint_state.name.end(), joint->getName()); + auto joint_idx = std::distance(joint_state.name.begin(), joint_itr); - if ((joint_trajectory.points[0].velocities[joint_idx] < 0 && + if ((joint_state.velocity.at(joint_idx) < 0 && (joint_angle < (limits[0].min_position + parameters_->joint_limit_margin))) || - (joint_trajectory.points[0].velocities[joint_idx] > 0 && + (joint_state.velocity.at(joint_idx) > 0 && (joint_angle > (limits[0].max_position - parameters_->joint_limit_margin)))) { rclcpp::Clock& clock = *node_->get_clock(); @@ -862,6 +861,13 @@ void ServoCalcs::suddenHalt(trajectory_msgs::msg::JointTrajectory& joint_traject } } +void ServoCalcs::suddenHalt(sensor_msgs::msg::JointState& joint_state) const +{ + // Set the position to the original position, and velocity to 0 + joint_state.position = original_joint_state_.position; + joint_state.velocity.assign(joint_state.position.size(), 0.0); +} + // Parse the incoming joint msg for the joints of our MoveGroup void ServoCalcs::updateJoints() { diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index b796a17f61..000ffb9d15 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -15,7 +15,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} Eigen3 Boost ) -target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} GLUT::GLUT ${GLEW_LIBRARIES}) target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MESH_FILTER_BUILDING_DLL") target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index c4e104f56a..3900c90081 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -166,8 +166,15 @@ void TrajectoryExecutionManager::initialize() // other configuration steps reloadControllerInformation(); + // The default callback group for rclcpp::Node is MutuallyExclusive which means we cannot call + // receiveEvent while processing a different callback. To fix this we create a new callback group (the type is not + // important since we only use it to process one callback) and associate event_topic_subscriber_ with this callback group + auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto options = rclcpp::SubscriptionOptions(); + options.callback_group = callback_group; event_topic_subscriber_ = node_->create_subscription( - EXECUTION_EVENT_TOPIC, 100, std::bind(&TrajectoryExecutionManager::receiveEvent, this, std::placeholders::_1)); + EXECUTION_EVENT_TOPIC, 100, std::bind(&TrajectoryExecutionManager::receiveEvent, this, std::placeholders::_1), + options); controller_mgr_node_->get_parameter("trajectory_execution.allowed_execution_duration_scaling", allowed_execution_duration_scaling_); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index fc145fe77e..118804b0d1 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -207,6 +207,14 @@ void MotionPlanningDisplay::onInitialize() { PlanningSceneDisplay::onInitialize(); + // Prepare database parameters + if (!node_->has_parameter("warehouse_host")) + node_->declare_parameter("warehouse_host", "127.0.0.1"); + if (!node_->has_parameter("warehouse_plugin")) + node_->declare_parameter("warehouse_plugin", "warehouse_ros_mongo::MongoDatabaseConnection"); + if (!node_->has_parameter("warehouse_port")) + node_->declare_parameter("warehouse_port", 33829); + // Planned Path Display trajectory_visual_->onInitialize(node_, planning_scene_node_, context_); QColor qcolor = attached_body_color_property_->getColor(); From 6c14a3de5c49e8936e067b4ab40346f557715646 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 1 Jul 2021 23:50:04 -0500 Subject: [PATCH 42/54] Run pre-commit --- .../include/moveit/planning_scene/planning_scene.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 99f6164d6f..6ecc87cc78 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 @@ -88,7 +88,7 @@ using ObjectTypeMap = std::map + public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ From fb40705a01f1d5a1024f3fa61617f6af8b6cfe9d Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 8 Jul 2021 13:35:13 -0500 Subject: [PATCH 43/54] Always use find_package for bullet and FCL --- moveit_core/CMakeLists.txt | 30 +++---------------- .../collision_detection_fcl/CMakeLists.txt | 2 +- 2 files changed, 5 insertions(+), 27 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 326c48ccaa..bb7f411bea 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -13,28 +13,8 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) -find_package(PkgConfig) -set(BULLET_VERSION 2.87) - -if(PKGCONFIG_FOUND) - pkg_check_modules(BULLET bullet) - find_package_handle_standard_args(BULLET - REQUIRED_VARS BULLET_LIBRARIES BULLET_INCLUDE_DIRS - VERSION_VAR ${BULLET_VERSION}) - - pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") - # replace LIBFCL_LIBRARIES with full path to the library - find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) - set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") - set(FCL_NAME "LIBFCL") -else() - find_package(FCL 0.5.0) - set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") - set(FCL_NAME "FCL") - set(EXTRA_INCLUDE "FCL") - find_package(Bullet ${BULLET_VERSION} REQUIRED) -endif() - +find_package(BULLET 2.87 REQUIRED) +find_package(FCL 0.5.0 REQUIRED) find_package(angles REQUIRED) find_package(OCTOMAP REQUIRED) find_package(urdfdom REQUIRED) @@ -145,15 +125,13 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS eigen3_cmake_module OCTOMAP Bullet - ${EXTRA_INCLUDE} + FCL ) pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) pluginlib_export_plugin_description_file(moveit_core collision_detector_bullet_description.xml) -include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS} - ${LIBFCL_INCLUDE_DIRS} -) +include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS}) include_directories(${THIS_PACKAGE_INCLUDE_DIRS} ${VERSION_FILE_PATH}) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 082ffe56e4..76850a86a4 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -12,7 +12,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom urdfdom_headers - ${FCL_NAME} + FCL Boost visualization_msgs ) From e7d402aa749746ce33c7514296369fd18aa9a715 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 8 Jul 2021 13:50:22 -0500 Subject: [PATCH 44/54] Use Bullet instead of BULLET --- moveit_core/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index bb7f411bea..215508f1ba 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -13,7 +13,7 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) -find_package(BULLET 2.87 REQUIRED) +find_package(Bullet 2.87 REQUIRED) find_package(FCL 0.5.0 REQUIRED) find_package(angles REQUIRED) find_package(OCTOMAP REQUIRED) From d08411340d0a3bfee21011fbbcca7d119c1ef199 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 8 Jul 2021 13:57:07 -0500 Subject: [PATCH 45/54] Use fcl instead of FCL --- moveit_core/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 215508f1ba..267702535d 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -14,7 +14,7 @@ find_package(Eigen3 REQUIRED) include(ConfigExtras.cmake) find_package(Bullet 2.87 REQUIRED) -find_package(FCL 0.5.0 REQUIRED) +find_package(fcl 0.5.0 REQUIRED) find_package(angles REQUIRED) find_package(OCTOMAP REQUIRED) find_package(urdfdom REQUIRED) From e16ab21fee8c1e7dff8a47a9e48513291bcc97ed Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 8 Jul 2021 14:13:35 -0500 Subject: [PATCH 46/54] Use pkg-config for FCL --- moveit_core/CMakeLists.txt | 20 +++++++++++++++++-- .../collision_detection_fcl/CMakeLists.txt | 2 +- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 267702535d..a5ba35736b 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -13,6 +13,20 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) +find_package(FCL 0.5.0) +if(FCL_FOUND) + set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") + set(FCL_NAME "FCL") + set(EXTRA_INCLUDE "FCL") +else() + find_package(PkgConfig REQUIRED) + pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") + # replace LIBFCL_LIBRARIES with full path to the library + find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) + set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") + set(FCL_NAME "LIBFCL") +endif() + find_package(Bullet 2.87 REQUIRED) find_package(fcl 0.5.0 REQUIRED) find_package(angles REQUIRED) @@ -125,13 +139,15 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS eigen3_cmake_module OCTOMAP Bullet - FCL + ${EXTRA_INCLUDE} ) pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) pluginlib_export_plugin_description_file(moveit_core collision_detector_bullet_description.xml) -include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS}) +include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS} + ${LIBFCL_INCLUDE_DIRS} +) include_directories(${THIS_PACKAGE_INCLUDE_DIRS} ${VERSION_FILE_PATH}) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 76850a86a4..082ffe56e4 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -12,7 +12,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom urdfdom_headers - FCL + ${FCL_NAME} Boost visualization_msgs ) From a3885d9e0c989f941a5b1bbb3e717a9063f65df6 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Thu, 8 Jul 2021 14:19:18 -0500 Subject: [PATCH 47/54] Fix --- moveit_core/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index a5ba35736b..d713241b33 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -28,7 +28,6 @@ else() endif() find_package(Bullet 2.87 REQUIRED) -find_package(fcl 0.5.0 REQUIRED) find_package(angles REQUIRED) find_package(OCTOMAP REQUIRED) find_package(urdfdom REQUIRED) From e53a6ae2a1355a5f6541e964083c9ae250edf2ac Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Sat, 10 Jul 2021 12:12:25 -0700 Subject: [PATCH 48/54] Fix linking fcl deps and only use pkg-config --- moveit_core/CMakeLists.txt | 23 ++++++++----------- .../collision_detection_fcl/CMakeLists.txt | 2 +- 2 files changed, 10 insertions(+), 15 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index d713241b33..06ca8b0554 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -13,19 +13,15 @@ find_package(Eigen3 REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) -find_package(FCL 0.5.0) -if(FCL_FOUND) - set(LIBFCL_INCLUDE_DIRS "${FCL_INCLUDE_DIRS}") - set(FCL_NAME "FCL") - set(EXTRA_INCLUDE "FCL") -else() - find_package(PkgConfig REQUIRED) - pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") - # replace LIBFCL_LIBRARIES with full path to the library - find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS}) - set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") - set(FCL_NAME "LIBFCL") -endif() +find_package(PkgConfig REQUIRED) +pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0") +# replace LIBFCL_LIBRARIES with full paths to the libraries +set(LIBFCL_LIBRARIES_FULL "") +foreach(LIBFCL_LIBRARY ${LIBFCL_LIBRARIES}) + find_library(${LIBFCL_LIBRARY}_LIB ${LIBFCL_LIBRARY} ${LIBFCL_LIBRARY_DIRS}) + list(APPEND LIBFCL_LIBRARIES_FULL ${${LIBFCL_LIBRARY}_LIB}) +endforeach() +set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}") find_package(Bullet 2.87 REQUIRED) find_package(angles REQUIRED) @@ -138,7 +134,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS eigen3_cmake_module OCTOMAP Bullet - ${EXTRA_INCLUDE} ) pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 082ffe56e4..12f0cdee97 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -12,7 +12,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom urdfdom_headers - ${FCL_NAME} + LIBFCL Boost visualization_msgs ) From f31f38707bc2337c48af21b2ff54a33e64cfe9f7 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Sat, 10 Jul 2021 12:28:04 -0700 Subject: [PATCH 49/54] Replace ${GLEW_LIBRARIES} with GLEW::glew for Windows --- moveit_ros/perception/CMakeLists.txt | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt index 27ce4ca893..f2fef34935 100644 --- a/moveit_ros/perception/CMakeLists.txt +++ b/moveit_ros/perception/CMakeLists.txt @@ -28,7 +28,11 @@ if(WITH_OPENGL) set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLEW::GLEW FreeGLUT::freeglut) else() find_package(GLUT REQUIRED) - set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT) + if(WIN32) + set(SYSTEM_GL_LIBRARIES GLEW::glew GLUT::GLUT) + else() + set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT) + endif() endif() set(perception_GL_INCLUDE_DIRS "mesh_filter/include" "depth_image_octomap_updater/include") set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR}) From 84140cfc21b1d8fbb35978d9fc0fd672370cd54f Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Sat, 17 Jul 2021 14:18:53 -0700 Subject: [PATCH 50/54] Switch to generated visibility headers --- .../collision_detection/CMakeLists.txt | 6 +- .../collision_detector_allocator_allvalid.h | 6 +- .../collision_detection/visibility_control.h | 70 ------------------- .../collision_detection_bullet/CMakeLists.txt | 5 +- .../collision_detector_allocator_bullet.h | 6 +- .../visibility_control.h | 70 ------------------- .../collision_detection_fcl/CMakeLists.txt | 5 +- .../collision_detector_allocator_fcl.h | 6 +- .../visibility_control.h | 70 ------------------- moveit_core/kinematics_base/CMakeLists.txt | 6 +- .../moveit/kinematics_base/kinematics_base.h | 10 +-- .../kinematics_base/visibility_control.h | 70 ------------------- moveit_core/planning_scene/CMakeLists.txt | 5 +- .../moveit/planning_scene/planning_scene.h | 8 +-- .../planning_scene/visibility_control.h | 70 ------------------- .../perception/mesh_filter/CMakeLists.txt | 5 +- .../moveit/mesh_filter/stereo_camera_model.h | 14 ++-- .../moveit/mesh_filter/visibility_control.h | 70 ------------------- .../planning/planning_pipeline/CMakeLists.txt | 5 +- .../planning_pipeline/planning_pipeline.h | 10 +-- .../planning_pipeline/visibility_control.h | 70 ------------------- .../planning_scene_monitor/CMakeLists.txt | 5 +- .../planning_scene_monitor.h | 18 ++--- .../visibility_control.h | 70 ------------------- .../CMakeLists.txt | 5 +- .../trajectory_execution_manager.h | 6 +- .../visibility_control.h | 70 ------------------- .../move_group_interface/CMakeLists.txt | 5 +- .../move_group_interface.h | 6 +- .../move_group_interface/visibility_control.h | 70 ------------------- moveit_ros/robot_interaction/CMakeLists.txt | 5 +- .../robot_interaction/kinematic_options_map.h | 8 +-- .../robot_interaction/visibility_control.h | 70 ------------------- .../planning_scene_rviz_plugin/CMakeLists.txt | 5 +- .../planning_scene_display.h | 4 +- .../visibility_control.h | 70 ------------------- moveit_ros/warehouse/warehouse/CMakeLists.txt | 5 +- .../moveit/warehouse/constraints_storage.h | 12 ++-- .../moveit/warehouse/planning_scene_storage.h | 10 +-- .../include/moveit/warehouse/state_storage.h | 10 +-- .../moveit/warehouse/visibility_control.h | 70 ------------------- 41 files changed, 119 insertions(+), 992 deletions(-) delete mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h delete mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h delete mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h delete mode 100644 moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h delete mode 100644 moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h delete mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h delete mode 100644 moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h delete mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h delete mode 100644 moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h delete mode 100644 moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h delete mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h delete mode 100644 moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h delete mode 100644 moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index d68979186a..734d0b48a5 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -10,9 +10,10 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/world_diff.cpp src/collision_env.cpp ) - +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE COLLISION_DETECTION_BUILDING_DLL) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation @@ -52,3 +53,4 @@ if(BUILD_TESTING) endif() install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index e14f587f4d..72800df357 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -39,15 +39,15 @@ #include #include -#include +#include "moveit_collision_detection_export.h" namespace collision_detection { /** \brief An allocator for AllValid collision detectors */ -class COLLISION_DETECTION_PUBLIC CollisionDetectorAllocatorAllValid +class CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_env_allvalid.cpp + static MOVEIT_COLLISION_DETECTION_EXPORT const std::string NAME; // defined in collision_env_allvalid.cpp }; } // namespace collision_detection diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h deleted file mode 100644 index 33e2c7fd54..0000000000 --- a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define COLLISION_DETECTION__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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_H_ diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index 2db5f2306e..1918466bac 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -9,8 +9,10 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/bullet_integration/contact_checker_common.cpp src/bullet_integration/ros_bullet_utils.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE COLLISION_DETECTION_BULLET_BUILDING_DLL) ament_target_dependencies(${MOVEIT_LIB_NAME} SYSTEM BULLET ) @@ -45,6 +47,7 @@ target_link_libraries(collision_detector_bullet_plugin ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} TARGETS collision_detector_bullet_plugin EXPORT collision_detector_bullet_plugin LIBRARY DESTINATION lib diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index ccb53accf7..de62b9b19f 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -39,15 +39,15 @@ #include #include -#include +#include "moveit_collision_detection_bullet_export.h" namespace collision_detection { /** \brief An allocator for Bullet collision detectors */ -class COLLISION_DETECTION_BULLET_PUBLIC CollisionDetectorAllocatorBullet +class CollisionDetectorAllocatorBullet : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_env_bullet.cpp + static MOVEIT_COLLISION_DETECTION_BULLET_EXPORT const std::string NAME; // defined in collision_env_bullet.cpp }; } // namespace collision_detection diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h deleted file mode 100644 index 53515a4eb6..0000000000 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_BULLET__VISIBILITY_CONTROL_H_ -#define COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ - -// 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_BULLET_EXPORT __attribute__((dllexport)) -#define COLLISION_DETECTION_BULLET_IMPORT __attribute__((dllimport)) -#else -#define COLLISION_DETECTION_BULLET_EXPORT __declspec(dllexport) -#define COLLISION_DETECTION_BULLET_IMPORT __declspec(dllimport) -#endif -#ifdef COLLISION_DETECTION_BULLET_BUILDING_DLL -#define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_EXPORT -#else -#define COLLISION_DETECTION_BULLET_PUBLIC COLLISION_DETECTION_BULLET_IMPORT -#endif -#define COLLISION_DETECTION_BULLET_PUBLIC_TYPE COLLISION_DETECTION_BULLET_PUBLIC -#define COLLISION_DETECTION_BULLET_LOCAL -#else -#define COLLISION_DETECTION_BULLET_EXPORT __attribute__((visibility("default"))) -#define COLLISION_DETECTION_BULLET_IMPORT -#if __GNUC__ >= 4 -#define COLLISION_DETECTION_BULLET_PUBLIC __attribute__((visibility("default"))) -#define COLLISION_DETECTION_BULLET_LOCAL __attribute__((visibility("hidden"))) -#else -#define COLLISION_DETECTION_BULLET_PUBLIC -#define COLLISION_DETECTION_BULLET_LOCAL -#endif -#define COLLISION_DETECTION_BULLET_PUBLIC_TYPE -#endif - -#endif // COLLISION_DETECTION_BULLET__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 12f0cdee97..32002955a7 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -4,8 +4,10 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/collision_common.cpp src/collision_env_fcl.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE COLLISION_DETECTION_FCL_BUILDING_DLL) ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp rmw_implementation @@ -35,6 +37,7 @@ target_link_libraries(collision_detector_fcl_plugin ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(BUILD_TESTING) if(WIN32) 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 d6cda534f5..353b572292 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -39,15 +39,15 @@ #include #include -#include +#include "moveit_collision_detection_fcl_export.h" namespace collision_detection { /** \brief An allocator for FCL collision detectors */ -class COLLISION_DETECTION_FCL_PUBLIC CollisionDetectorAllocatorFCL +class CollisionDetectorAllocatorFCL : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_env_fcl.cpp + static MOVEIT_COLLISION_DETECTION_FCL_EXPORT const std::string NAME; // defined in collision_env_fcl.cpp }; } // namespace collision_detection diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h deleted file mode 100644 index e4b92ba53d..0000000000 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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 - -#endif // COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index d9e447dd1e..a588d259f8 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -2,8 +2,9 @@ cmake_minimum_required(VERSION 3.5) set(MOVEIT_LIB_NAME moveit_kinematics_base) add_library(${MOVEIT_LIB_NAME} SHARED src/kinematics_base.cpp) -set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "KINEMATICS_BASE_BUILDING_DLL") +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) # This line is needed to ensure that messages are done being built before this is built ament_target_dependencies( @@ -18,3 +19,4 @@ ament_target_dependencies( ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index f1674dc33a..6f4d0620a8 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -43,7 +43,7 @@ #include #include -#include +#include "moveit_kinematics_base_export.h" namespace moveit { @@ -142,12 +142,12 @@ MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, W * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class KINEMATICS_BASE_PUBLIC KinematicsBase +class KinematicsBase { public: - static const rclcpp::Logger LOGGER; - static const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */ - static const double DEFAULT_TIMEOUT; /* = 1.0 */ + static MOVEIT_KINEMATICS_BASE_EXPORT const rclcpp::Logger LOGGER; + static MOVEIT_KINEMATICS_BASE_EXPORT const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */ + static MOVEIT_KINEMATICS_BASE_EXPORT const double DEFAULT_TIMEOUT; /* = 1.0 */ /** @brief Signature for a callback to validate an IK solution. Typically used for collision checking. */ using IKCallbackFn = boost::function&, diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h deleted file mode 100644 index be4e7f45dc..0000000000 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define KINEMATICS_BASE__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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 - -#endif // KINEMATICS_BASE__VISIBILITY_CONTROL_H_ diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index 0628361dac..bb62d2a351 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -1,9 +1,11 @@ set(MOVEIT_LIB_NAME moveit_planning_scene) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_scene.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) #TODO: Fix the versioning set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_SCENE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} Boost rclcpp @@ -27,6 +29,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 6ecc87cc78..29df503028 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -57,7 +57,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include +#include "moveit_planning_scene_export.h" /** \brief This namespace includes the central class for representing planning contexts */ namespace planning_scene @@ -87,7 +87,7 @@ using ObjectTypeMap = std::map { public: @@ -102,8 +102,8 @@ class PLANNING_SCENE_PUBLIC PlanningScene : private boost::noncopyable, 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; + static MOVEIT_PLANNING_SCENE_EXPORT const std::string OCTOMAP_NS; + static MOVEIT_PLANNING_SCENE_EXPORT const std::string DEFAULT_SCENE_NAME; ~PlanningScene(); diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h deleted file mode 100644 index a481f3d47f..0000000000 --- a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define PLANNING_SCENE__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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 - -#endif // PLANNING_SCENE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 000ffb9d15..54b973d317 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -7,6 +7,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/gl_renderer.cpp src/gl_mesh.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp @@ -15,7 +18,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} Eigen3 Boost ) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MESH_FILTER_BUILDING_DLL") target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) @@ -41,3 +43,4 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) # endif() install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index cc82a187cb..75f3e72786 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -39,7 +39,7 @@ #include #include -#include +#include "moveit_mesh_filter_export.h" namespace mesh_filter { @@ -47,7 +47,7 @@ namespace mesh_filter * \brief Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices * \author Suat Gedikli */ -class MESH_FILTER_PUBLIC StereoCameraModel : public SensorModel +class StereoCameraModel : public SensorModel { public: /** @@ -150,18 +150,18 @@ class MESH_FILTER_PUBLIC StereoCameraModel : public SensorModel }; /** \brief predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) */ - static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) + static MOVEIT_MESH_FILTER_EXPORT const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) /** \brief source code of the vertex shader used to render the meshes*/ - static const std::string RENDER_VERTEX_SHADER_SOURCE; + static MOVEIT_MESH_FILTER_EXPORT const std::string RENDER_VERTEX_SHADER_SOURCE; /** \brief source code of the fragment shader used to render the meshes*/ - static const std::string RENDER_FRAGMENT_SHADER_SOURCE; + static MOVEIT_MESH_FILTER_EXPORT const std::string RENDER_FRAGMENT_SHADER_SOURCE; /** \brief source code of the vertex shader used to filter the depth map*/ - static const std::string FILTER_VERTEX_SHADER_SOURCE; + static MOVEIT_MESH_FILTER_EXPORT const std::string FILTER_VERTEX_SHADER_SOURCE; /** \brief source code of the fragment shader used to filter the depth map*/ - static const std::string FILTER_FRAGMENT_SHADER_SOURCE; + static MOVEIT_MESH_FILTER_EXPORT const std::string FILTER_FRAGMENT_SHADER_SOURCE; }; } // namespace mesh_filter diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h deleted file mode 100644 index d2920a4a42..0000000000 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define MESH_FILTER__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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_H_ diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index e65bfa4b29..2e8c7c925c 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -1,8 +1,10 @@ set(MOVEIT_LIB_NAME moveit_planning_pipeline) add_library(${MOVEIT_LIB_NAME} SHARED src/planning_pipeline.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_PIPELINE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core @@ -13,3 +15,4 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index c00164b691..fe3afb2e86 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -45,7 +45,7 @@ #include -#include +#include "moveit_planning_pipeline_export.h" /** \brief Planning pipeline */ namespace planning_pipeline @@ -56,20 +56,20 @@ namespace planning_pipeline planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. */ -class PLANNING_PIPELINE_PUBLIC PlanningPipeline +class PlanningPipeline { public: /** \brief When motion plans are computed and they are supposed to be automatically displayed, they are sent to this * topic (moveit_msgs::msg::DisplauTrajectory) */ - static const std::string DISPLAY_PATH_TOPIC; + static MOVEIT_PLANNING_PIPELINE_EXPORT const std::string DISPLAY_PATH_TOPIC; /** \brief When motion planning requests are received and they are supposed to be automatically published, they are * sent to this topic (moveit_msgs::msg::MotionPlanRequest) */ - static const std::string MOTION_PLAN_REQUEST_TOPIC; + static MOVEIT_PLANNING_PIPELINE_EXPORT const std::string MOTION_PLAN_REQUEST_TOPIC; /** \brief When contacts are found in the solution path reported by a planner, they can be published as markers on * this topic (visualization_msgs::MarkerArray) */ - static const std::string MOTION_CONTACTS_TOPIC; + static MOVEIT_PLANNING_PIPELINE_EXPORT const std::string MOTION_CONTACTS_TOPIC; /** \brief Given a robot model (\e model), a node handle (\e pipeline_nh), initialize the planning pipeline. \param model The robot model for which this pipeline is initialized. diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h deleted file mode 100644 index bbb24f4894..0000000000 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_PIPELINE__VISIBILITY_CONTROL_H_ -#define PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ - -// 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_PIPELINE_EXPORT __attribute__((dllexport)) -#define PLANNING_PIPELINE_IMPORT __attribute__((dllimport)) -#else -#define PLANNING_PIPELINE_EXPORT __declspec(dllexport) -#define PLANNING_PIPELINE_IMPORT __declspec(dllimport) -#endif -#ifdef PLANNING_PIPELINE_BUILDING_DLL -#define PLANNING_PIPELINE_PUBLIC PLANNING_PIPELINE_EXPORT -#else -#define PLANNING_PIPELINE_PUBLIC PLANNING_PIPELINE_IMPORT -#endif -#define PLANNING_PIPELINE_PUBLIC_TYPE PLANNING_PIPELINE_PUBLIC -#define PLANNING_PIPELINE_LOCAL -#else -#define PLANNING_PIPELINE_EXPORT __attribute__((visibility("default"))) -#define PLANNING_PIPELINE_IMPORT -#if __GNUC__ >= 4 -#define PLANNING_PIPELINE_PUBLIC __attribute__((visibility("default"))) -#define PLANNING_PIPELINE_LOCAL __attribute__((visibility("hidden"))) -#else -#define PLANNING_PIPELINE_PUBLIC -#define PLANNING_PIPELINE_LOCAL -#endif -#define PLANNING_PIPELINE_PUBLIC_TYPE -#endif - -#endif // PLANNING_PIPELINE__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index 3665647e19..0abcbfde1a 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -5,8 +5,10 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/current_state_monitor.cpp src/trajectory_monitor.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_SCENE_MONITOR_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_ros_occupancy_map_monitor message_filters @@ -37,3 +39,4 @@ install(TARGETS demo_scene ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/planning/planning_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 d00148f3d4..45bd7862f4 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 @@ -53,7 +53,7 @@ #include #include -#include +#include "moveit_planning_scene_monitor_export.h" namespace planning_scene_monitor { @@ -62,7 +62,7 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class PLANNING_SCENE_MONITOR_PUBLIC PlanningSceneMonitor : private boost::noncopyable +class PlanningSceneMonitor : private boost::noncopyable { public: enum SceneUpdateType @@ -85,27 +85,27 @@ class PLANNING_SCENE_MONITOR_PUBLIC PlanningSceneMonitor : private boost::noncop }; /// The name of the topic used by default for receiving joint states - static const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states" /// The name of the topic used by default for attached collision objects - static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" /// The name of the topic used by default for receiving collision objects in the world - static const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object" /// The name of the topic used by default for receiving geometry information about a planning scene (complete /// overwrite of world geometry) - static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" /// The name of the topic used by default for receiving full planning scenes or planning scene diffs - static const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene" /// The name of the service used by default for requesting full planning scene state - static const std::string DEFAULT_PLANNING_SCENE_SERVICE; // "/get_planning_scene" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_SERVICE; // "/get_planning_scene" /// The name of the topic used by default for publishing the monitored planning scene (this is without "/" in the /// name, so the topic is prefixed by the node name) - static const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" /** @brief Constructor * @param robot_description The name of the ROS parameter that contains the URDF (in string format) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h deleted file mode 100644 index ac38d807d3..0000000000 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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_H_ diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index a6e58d2c40..95db3085ab 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -1,8 +1,10 @@ set(MOVEIT_LIB_NAME moveit_trajectory_execution_manager) add_library(${MOVEIT_LIB_NAME} SHARED src/trajectory_execution_manager.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "TRAJECTORY_EXECUTION_MANAGER_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_ros_occupancy_map_monitor @@ -19,6 +21,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) if(CATKIN_ENABLE_TESTING) diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 6d71e18a44..e6666fa4c8 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 @@ -50,7 +50,7 @@ #include #include -#include +#include "moveit_trajectory_execution_manager_export.h" namespace trajectory_execution_manager { @@ -59,10 +59,10 @@ MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager); // Defines TrajectoryExecutio // Two modes: // Managed controllers // Unmanaged controllers: given the trajectory, -class TRAJECTORY_EXECUTION_MANAGER_PUBLIC TrajectoryExecutionManager +class TrajectoryExecutionManager { public: - static const std::string EXECUTION_EVENT_TOPIC; + static MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT const std::string EXECUTION_EVENT_TOPIC; /// Definition of the function signature that is called when the execution of all the pushed trajectories completes. /// The status of the overall execution is passed as argument diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h deleted file mode 100644 index 1e3fd548f5..0000000000 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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 TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ -#define TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ - -// 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 TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__((dllexport)) -#define TRAJECTORY_EXECUTION_MANAGER_IMPORT __attribute__((dllimport)) -#else -#define TRAJECTORY_EXECUTION_MANAGER_EXPORT __declspec(dllexport) -#define TRAJECTORY_EXECUTION_MANAGER_IMPORT __declspec(dllimport) -#endif -#ifdef TRAJECTORY_EXECUTION_MANAGER_BUILDING_DLL -#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_EXPORT -#else -#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC TRAJECTORY_EXECUTION_MANAGER_IMPORT -#endif -#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE TRAJECTORY_EXECUTION_MANAGER_PUBLIC -#define TRAJECTORY_EXECUTION_MANAGER_LOCAL -#else -#define TRAJECTORY_EXECUTION_MANAGER_EXPORT __attribute__((visibility("default"))) -#define TRAJECTORY_EXECUTION_MANAGER_IMPORT -#if __GNUC__ >= 4 -#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC __attribute__((visibility("default"))) -#define TRAJECTORY_EXECUTION_MANAGER_LOCAL __attribute__((visibility("hidden"))) -#else -#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC -#define TRAJECTORY_EXECUTION_MANAGER_LOCAL -#endif -#define TRAJECTORY_EXECUTION_MANAGER_PUBLIC_TYPE -#endif - -#endif // TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index 1e63a2be04..776286d927 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -1,9 +1,11 @@ set(MOVEIT_LIB_NAME moveit_move_group_interface) add_library(${MOVEIT_LIB_NAME} SHARED src/move_group_interface.cpp) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${Boost_THREAD_LIBRARY}) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVE_GROUP_INTERFACE_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_msgs @@ -25,6 +27,7 @@ if(WIN32) endif() install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) #add_executable(demo src/demo.cpp) #target_link_libraries(demo ${MOVEIT_LIB_NAME} ${LIBS} ${Boost_LIBRARIES}) diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 619c889401..e64cb42cce 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -60,7 +60,7 @@ #include #include -#include +#include "moveit_move_group_interface_export.h" namespace moveit { @@ -103,11 +103,11 @@ MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, Con \brief Client class to conveniently use the ROS interfaces provided by the move_group node. This class includes many default settings to make things easy to use. */ -class MOVE_GROUP_INTERFACE_PUBLIC MoveGroupInterface +class MoveGroupInterface { public: /** \brief Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description' */ - static const std::string ROBOT_DESCRIPTION; + static MOVEIT_MOVE_GROUP_INTERFACE_EXPORT const std::string ROBOT_DESCRIPTION; /** \brief Specification of options to use when constructing the MoveGroupInterface class */ struct Options diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h deleted file mode 100644 index f96e025439..0000000000 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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_H_ diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index 5edbb52c90..c9298c2ca1 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -35,8 +35,10 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/interaction_handler.cpp src/robot_interaction.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "ROBOT_INTERACTION_BUILDING_DLL") ament_target_dependencies(${MOVEIT_LIB_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) if(BUILD_TESTING) @@ -57,6 +59,7 @@ install( ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) install(DIRECTORY resources DESTINATION share/${PROJECT_NAME}) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 807a66e5b9..942134f3a5 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -40,23 +40,23 @@ #include #include -#include +#include "moveit_robot_interaction_export.h" namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class ROBOT_INTERACTION_PUBLIC KinematicOptionsMap +class KinematicOptionsMap { public: /// Constructor - set all options to reasonable default values. KinematicOptionsMap(); /// When used as \e key this means the default value - static const std::string DEFAULT; + static MOVEIT_ROBOT_INTERACTION_EXPORT const std::string DEFAULT; /// When used as \e key this means set ALL keys (including default) - static const std::string ALL; + static MOVEIT_ROBOT_INTERACTION_EXPORT const std::string ALL; /// Set \e state using inverse kinematics. /// @param state the state to set diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h deleted file mode 100644 index 956d411039..0000000000 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define ROBOT_INTERACTION__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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_H_ diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index fe84f5c710..b987a90b9e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -3,8 +3,10 @@ set(MOVEIT_LIB_NAME moveit_planning_scene_rviz_plugin) add_library(${MOVEIT_LIB_NAME}_core SHARED src/planning_scene_display.cpp include/moveit/planning_scene_rviz_plugin/planning_scene_display.h) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}_core) +target_include_directories(${MOVEIT_LIB_NAME}_core PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_compile_definitions(${MOVEIT_LIB_NAME}_core PRIVATE "PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_DLL") target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_rviz_plugin_render_tools) ament_target_dependencies(${MOVEIT_LIB_NAME}_core rclcpp @@ -28,3 +30,4 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include") install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_core_export.h DESTINATION include) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index f54fd880cf..7f0fd21c06 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -47,7 +47,7 @@ #include #endif -#include +#include "moveit_planning_scene_rviz_plugin_core_export.h" namespace Ogre { @@ -68,7 +68,7 @@ class EnumProperty; namespace moveit_rviz_plugin { -class PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PlanningSceneDisplay : public rviz_common::Display +class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT PlanningSceneDisplay : public rviz_common::Display { Q_OBJECT diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h deleted file mode 100644 index 0fe3b83058..0000000000 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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_H_ -#define PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ - -// 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_DLL -#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 - -#endif // PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_H_ diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index 4faa64a9de..6c72e53c6a 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -9,9 +9,11 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/state_storage.cpp src/warehouse_connector.cpp ) +include(GenerateExportHeader) +generate_export_header(${MOVEIT_LIB_NAME}) +target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp Boost moveit_core warehouse_ros moveit_ros_planning) -target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE WAREHOUSE_BUILDING_DLL) add_executable(moveit_warehouse_broadcast src/broadcast.cpp) ament_target_dependencies(moveit_warehouse_broadcast rclcpp Boost warehouse_ros moveit_ros_planning) @@ -48,3 +50,4 @@ install( RUNTIME DESTINATION lib/${PROJECT_NAME} ) install(DIRECTORY include/ DESTINATION include) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include) diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h index f5c2353af3..1e4d9db309 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -40,7 +40,7 @@ #include #include -#include +#include "moveit_warehouse_export.h" namespace moveit_warehouse { @@ -49,14 +49,14 @@ typedef warehouse_ros::MessageCollection::Ptr Con MOVEIT_CLASS_FORWARD(ConstraintsStorage); // Defines ConstraintsStoragePtr, ConstPtr, WeakPtr... etc -class WAREHOUSE_PUBLIC ConstraintsStorage : public MoveItMessageStorage +class ConstraintsStorage : public MoveItMessageStorage { public: - static const std::string DATABASE_NAME; + static MOVEIT_WAREHOUSE_EXPORT 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; + static MOVEIT_WAREHOUSE_EXPORT const std::string CONSTRAINTS_ID_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string CONSTRAINTS_GROUP_NAME; + static MOVEIT_WAREHOUSE_EXPORT 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 befa4ecef9..9d45f5c55c 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -42,7 +42,7 @@ #include #include -#include +#include "moveit_warehouse_export.h" namespace moveit_warehouse { @@ -56,13 +56,13 @@ typedef warehouse_ros::MessageCollection::Ptr MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc -class WAREHOUSE_PUBLIC PlanningSceneStorage : public MoveItMessageStorage +class PlanningSceneStorage : public MoveItMessageStorage { public: - static const std::string DATABASE_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string DATABASE_NAME; - static const std::string PLANNING_SCENE_ID_NAME; - static const std::string MOTION_PLAN_REQUEST_ID_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string PLANNING_SCENE_ID_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string MOTION_PLAN_REQUEST_ID_NAME; PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn); 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 de80cb753d..d0cfa944b4 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -40,7 +40,7 @@ #include #include -#include +#include "moveit_warehouse_export.h" namespace moveit_warehouse { @@ -49,13 +49,13 @@ typedef warehouse_ros::MessageCollection::Ptr Robo MOVEIT_CLASS_FORWARD(RobotStateStorage); // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc -class WAREHOUSE_PUBLIC RobotStateStorage : public MoveItMessageStorage +class RobotStateStorage : public MoveItMessageStorage { public: - static const std::string DATABASE_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string DATABASE_NAME; - static const std::string STATE_NAME; - static const std::string ROBOT_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string STATE_NAME; + static MOVEIT_WAREHOUSE_EXPORT const std::string ROBOT_NAME; RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn); diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h deleted file mode 100644 index b9c3d42a70..0000000000 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/visibility_control.h +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright (c) 2021, 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 WAREHOUSE__VISIBILITY_CONTROL_H_ -#define WAREHOUSE__VISIBILITY_CONTROL_H_ - -// 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 WAREHOUSE_EXPORT __attribute__((dllexport)) -#define WAREHOUSE_IMPORT __attribute__((dllimport)) -#else -#define WAREHOUSE_EXPORT __declspec(dllexport) -#define WAREHOUSE_IMPORT __declspec(dllimport) -#endif -#ifdef WAREHOUSE_BUILDING_DLL -#define WAREHOUSE_PUBLIC WAREHOUSE_EXPORT -#else -#define WAREHOUSE_PUBLIC WAREHOUSE_IMPORT -#endif -#define WAREHOUSE_PUBLIC_TYPE WAREHOUSE_PUBLIC -#define WAREHOUSE_LOCAL -#else -#define WAREHOUSE_EXPORT __attribute__((visibility("default"))) -#define WAREHOUSE_IMPORT -#if __GNUC__ >= 4 -#define WAREHOUSE_PUBLIC __attribute__((visibility("default"))) -#define WAREHOUSE_LOCAL __attribute__((visibility("hidden"))) -#else -#define WAREHOUSE_PUBLIC -#define WAREHOUSE_LOCAL -#endif -#define WAREHOUSE_PUBLIC_TYPE -#endif - -#endif // WAREHOUSE__VISIBILITY_CONTROL_H_ From e14af580a4f71f8283b975469a8f56cc20bc21cf Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Sat, 17 Jul 2021 14:37:03 -0700 Subject: [PATCH 51/54] Run pre-commit --- .../include/moveit/planning_scene/planning_scene.h | 3 +-- .../include/moveit/mesh_filter/stereo_camera_model.h | 3 ++- .../planning_scene_monitor/planning_scene_monitor.h | 9 ++++++--- 3 files changed, 9 insertions(+), 6 deletions(-) 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 29df503028..e7e01dab8d 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 @@ -87,8 +87,7 @@ using ObjectTypeMap = std::map +class PlanningScene : private boost::noncopyable, public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ 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 75f3e72786..81f35f3fe5 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 @@ -150,7 +150,8 @@ class StereoCameraModel : public SensorModel }; /** \brief predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) */ - static MOVEIT_MESH_FILTER_EXPORT const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) + static MOVEIT_MESH_FILTER_EXPORT const StereoCameraModel::Parameters& + REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) /** \brief source code of the vertex shader used to render the meshes*/ static MOVEIT_MESH_FILTER_EXPORT const std::string RENDER_VERTEX_SHADER_SOURCE; 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 45bd7862f4..d733d2e701 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 @@ -88,14 +88,16 @@ class PlanningSceneMonitor : private boost::noncopyable static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states" /// The name of the topic used by default for attached collision objects - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string + DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" /// The name of the topic used by default for receiving collision objects in the world static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object" /// The name of the topic used by default for receiving geometry information about a planning scene (complete /// overwrite of world geometry) - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string + DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" /// The name of the topic used by default for receiving full planning scenes or planning scene diffs static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene" @@ -105,7 +107,8 @@ class PlanningSceneMonitor : private boost::noncopyable /// The name of the topic used by default for publishing the monitored planning scene (this is without "/" in the /// name, so the topic is prefixed by the node name) - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" + static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string + MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" /** @brief Constructor * @param robot_description The name of the ROS parameter that contains the URDF (in string format) From df9ae8d5bc48ea9747a94932935d8f9f673a9c33 Mon Sep 17 00:00:00 2001 From: Lior Lustgarten Date: Mon, 19 Jul 2021 15:44:37 -0700 Subject: [PATCH 52/54] exported whole classes to fix linker errors --- .../moveit/kinematics_base/kinematics_base.h | 8 ++++---- .../moveit/planning_scene/planning_scene.h | 6 +++--- .../moveit/planning_pipeline/planning_pipeline.h | 8 ++++---- .../planning_scene_monitor.h | 16 ++++++++-------- .../moveit/warehouse/constraints_storage.h | 10 +++++----- .../moveit/warehouse/planning_scene_storage.h | 8 ++++---- .../include/moveit/warehouse/state_storage.h | 8 ++++---- 7 files changed, 32 insertions(+), 32 deletions(-) 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 6f4d0620a8..1820513897 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -142,12 +142,12 @@ MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, W * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class KinematicsBase +class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase { public: - static MOVEIT_KINEMATICS_BASE_EXPORT const rclcpp::Logger LOGGER; - static MOVEIT_KINEMATICS_BASE_EXPORT const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */ - static MOVEIT_KINEMATICS_BASE_EXPORT const double DEFAULT_TIMEOUT; /* = 1.0 */ + static const rclcpp::Logger LOGGER; + static const double DEFAULT_SEARCH_DISCRETIZATION; /* = 0.1 */ + static const double DEFAULT_TIMEOUT; /* = 1.0 */ /** @brief Signature for a callback to validate an IK solution. Typically used for collision checking. */ using IKCallbackFn = boost::function&, 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 e7e01dab8d..b746f04d52 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 @@ -87,7 +87,7 @@ using ObjectTypeMap = std::map +class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : private boost::noncopyable, public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ @@ -101,8 +101,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 MOVEIT_PLANNING_SCENE_EXPORT const std::string OCTOMAP_NS; - static MOVEIT_PLANNING_SCENE_EXPORT const std::string DEFAULT_SCENE_NAME; + static const std::string OCTOMAP_NS; + static const std::string DEFAULT_SCENE_NAME; ~PlanningScene(); 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 fe3afb2e86..3c3527da32 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -56,20 +56,20 @@ namespace planning_pipeline planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. */ -class PlanningPipeline +class MOVEIT_PLANNING_PIPELINE_EXPORT PlanningPipeline { public: /** \brief When motion plans are computed and they are supposed to be automatically displayed, they are sent to this * topic (moveit_msgs::msg::DisplauTrajectory) */ - static MOVEIT_PLANNING_PIPELINE_EXPORT const std::string DISPLAY_PATH_TOPIC; + static const std::string DISPLAY_PATH_TOPIC; /** \brief When motion planning requests are received and they are supposed to be automatically published, they are * sent to this topic (moveit_msgs::msg::MotionPlanRequest) */ - static MOVEIT_PLANNING_PIPELINE_EXPORT const std::string MOTION_PLAN_REQUEST_TOPIC; + static const std::string MOTION_PLAN_REQUEST_TOPIC; /** \brief When contacts are found in the solution path reported by a planner, they can be published as markers on * this topic (visualization_msgs::MarkerArray) */ - static MOVEIT_PLANNING_PIPELINE_EXPORT const std::string MOTION_CONTACTS_TOPIC; + static const std::string MOTION_CONTACTS_TOPIC; /** \brief Given a robot model (\e model), a node handle (\e pipeline_nh), initialize the planning pipeline. \param model The robot model for which this pipeline is initialized. 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 d733d2e701..5c3415747d 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 @@ -62,7 +62,7 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class PlanningSceneMonitor : private boost::noncopyable +class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost::noncopyable { public: enum SceneUpdateType @@ -85,29 +85,29 @@ class PlanningSceneMonitor : private boost::noncopyable }; /// The name of the topic used by default for receiving joint states - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states" + static const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states" /// The name of the topic used by default for attached collision objects - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string + static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" /// The name of the topic used by default for receiving collision objects in the world - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object" + static const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object" /// The name of the topic used by default for receiving geometry information about a planning scene (complete /// overwrite of world geometry) - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string + static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" /// The name of the topic used by default for receiving full planning scenes or planning scene diffs - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene" + static const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene" /// The name of the service used by default for requesting full planning scene state - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string DEFAULT_PLANNING_SCENE_SERVICE; // "/get_planning_scene" + static const std::string DEFAULT_PLANNING_SCENE_SERVICE; // "/get_planning_scene" /// The name of the topic used by default for publishing the monitored planning scene (this is without "/" in the /// name, so the topic is prefixed by the node name) - static MOVEIT_PLANNING_SCENE_MONITOR_EXPORT const std::string + static const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" /** @brief Constructor 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 1e4d9db309..e170bda5cd 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -49,14 +49,14 @@ typedef warehouse_ros::MessageCollection::Ptr Con MOVEIT_CLASS_FORWARD(ConstraintsStorage); // Defines ConstraintsStoragePtr, ConstPtr, WeakPtr... etc -class ConstraintsStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_EXPORT ConstraintsStorage : public MoveItMessageStorage { public: - static MOVEIT_WAREHOUSE_EXPORT const std::string DATABASE_NAME; + static const std::string DATABASE_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string CONSTRAINTS_ID_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string CONSTRAINTS_GROUP_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string ROBOT_NAME; + static const std::string CONSTRAINTS_ID_NAME; + static const std::string CONSTRAINTS_GROUP_NAME; + 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 9d45f5c55c..6b6b633247 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -56,13 +56,13 @@ typedef warehouse_ros::MessageCollection::Ptr MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc -class PlanningSceneStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_EXPORT PlanningSceneStorage : public MoveItMessageStorage { public: - static MOVEIT_WAREHOUSE_EXPORT const std::string DATABASE_NAME; + static const std::string DATABASE_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string PLANNING_SCENE_ID_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string MOTION_PLAN_REQUEST_ID_NAME; + static const std::string PLANNING_SCENE_ID_NAME; + static const std::string MOTION_PLAN_REQUEST_ID_NAME; PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn); 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 d0cfa944b4..952c549945 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -49,13 +49,13 @@ typedef warehouse_ros::MessageCollection::Ptr Robo MOVEIT_CLASS_FORWARD(RobotStateStorage); // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc -class RobotStateStorage : public MoveItMessageStorage +class MOVEIT_WAREHOUSE_EXPORT RobotStateStorage : public MoveItMessageStorage { public: - static MOVEIT_WAREHOUSE_EXPORT const std::string DATABASE_NAME; + static const std::string DATABASE_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string STATE_NAME; - static MOVEIT_WAREHOUSE_EXPORT const std::string ROBOT_NAME; + static const std::string STATE_NAME; + static const std::string ROBOT_NAME; RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn); From 81d2ca311f00069819692a209a720452088e8777 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 19 Jul 2021 17:47:19 -0700 Subject: [PATCH 53/54] Export the other classes too --- .../allvalid/collision_detector_allocator_allvalid.h | 4 ++-- .../collision_detector_allocator_bullet.h | 4 ++-- .../collision_detector_allocator_fcl.h | 4 ++-- .../include/moveit/mesh_filter/stereo_camera_model.h | 12 ++++++------ .../trajectory_execution_manager.h | 4 ++-- .../move_group_interface/move_group_interface.h | 4 ++-- .../moveit/robot_interaction/kinematic_options_map.h | 6 +++--- 7 files changed, 19 insertions(+), 19 deletions(-) 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 72800df357..def3f3bc17 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -44,10 +44,10 @@ namespace collision_detection { /** \brief An allocator for AllValid collision detectors */ -class CollisionDetectorAllocatorAllValid +class MOVEIT_COLLISION_DETECTION_EXPORT CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: - static MOVEIT_COLLISION_DETECTION_EXPORT const std::string NAME; // defined in collision_env_allvalid.cpp + static const std::string NAME; // defined in collision_env_allvalid.cpp }; } // namespace collision_detection diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index de62b9b19f..c0cf1be7bf 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -44,10 +44,10 @@ namespace collision_detection { /** \brief An allocator for Bullet collision detectors */ -class CollisionDetectorAllocatorBullet +class MOVEIT_COLLISION_DETECTION_BULLET_EXPORT CollisionDetectorAllocatorBullet : public CollisionDetectorAllocatorTemplate { public: - static MOVEIT_COLLISION_DETECTION_BULLET_EXPORT const std::string NAME; // defined in collision_env_bullet.cpp + static const std::string NAME; // defined in collision_env_bullet.cpp }; } // namespace collision_detection 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 353b572292..56851f1679 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -44,10 +44,10 @@ namespace collision_detection { /** \brief An allocator for FCL collision detectors */ -class CollisionDetectorAllocatorFCL +class MOVEIT_COLLISION_DETECTION_FCL_EXPORT CollisionDetectorAllocatorFCL : public CollisionDetectorAllocatorTemplate { public: - static MOVEIT_COLLISION_DETECTION_FCL_EXPORT const std::string NAME; // defined in collision_env_fcl.cpp + static const std::string NAME; // defined in collision_env_fcl.cpp }; } // namespace collision_detection 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 81f35f3fe5..f4552879ce 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 @@ -47,7 +47,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 MOVEIT_MESH_FILTER_EXPORT StereoCameraModel : public SensorModel { public: /** @@ -150,19 +150,19 @@ class StereoCameraModel : public SensorModel }; /** \brief predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) */ - static MOVEIT_MESH_FILTER_EXPORT const StereoCameraModel::Parameters& + static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) /** \brief source code of the vertex shader used to render the meshes*/ - static MOVEIT_MESH_FILTER_EXPORT const std::string RENDER_VERTEX_SHADER_SOURCE; + static const std::string RENDER_VERTEX_SHADER_SOURCE; /** \brief source code of the fragment shader used to render the meshes*/ - static MOVEIT_MESH_FILTER_EXPORT const std::string RENDER_FRAGMENT_SHADER_SOURCE; + static const std::string RENDER_FRAGMENT_SHADER_SOURCE; /** \brief source code of the vertex shader used to filter the depth map*/ - static MOVEIT_MESH_FILTER_EXPORT const std::string FILTER_VERTEX_SHADER_SOURCE; + static const std::string FILTER_VERTEX_SHADER_SOURCE; /** \brief source code of the fragment shader used to filter the depth map*/ - static MOVEIT_MESH_FILTER_EXPORT const std::string FILTER_FRAGMENT_SHADER_SOURCE; + static const std::string FILTER_FRAGMENT_SHADER_SOURCE; }; } // namespace mesh_filter 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 e6666fa4c8..55e2b5b733 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -59,10 +59,10 @@ MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager); // Defines TrajectoryExecutio // Two modes: // Managed controllers // Unmanaged controllers: given the trajectory, -class TrajectoryExecutionManager +class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager { public: - static MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT const std::string EXECUTION_EVENT_TOPIC; + static const std::string EXECUTION_EVENT_TOPIC; /// Definition of the function signature that is called when the execution of all the pushed trajectories completes. /// The status of the overall execution is passed as argument 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 e64cb42cce..6e725bac02 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -103,11 +103,11 @@ MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, Con \brief Client class to conveniently use the ROS interfaces provided by the move_group node. This class includes many default settings to make things easy to use. */ -class MoveGroupInterface +class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface { public: /** \brief Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description' */ - static MOVEIT_MOVE_GROUP_INTERFACE_EXPORT const std::string ROBOT_DESCRIPTION; + static const std::string ROBOT_DESCRIPTION; /** \brief Specification of options to use when constructing the MoveGroupInterface class */ struct Options 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 942134f3a5..d00a29541a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -46,17 +46,17 @@ namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class KinematicOptionsMap +class MOVEIT_ROBOT_INTERACTION_EXPORT KinematicOptionsMap { public: /// Constructor - set all options to reasonable default values. KinematicOptionsMap(); /// When used as \e key this means the default value - static MOVEIT_ROBOT_INTERACTION_EXPORT const std::string DEFAULT; + static const std::string DEFAULT; /// When used as \e key this means set ALL keys (including default) - static MOVEIT_ROBOT_INTERACTION_EXPORT const std::string ALL; + static const std::string ALL; /// Set \e state using inverse kinematics. /// @param state the state to set From 62526dee9604eb3ff588694dd86afd055343f9a6 Mon Sep 17 00:00:00 2001 From: Akash Munagala Date: Mon, 19 Jul 2021 18:00:26 -0700 Subject: [PATCH 54/54] Run pre-commit --- .../include/moveit/planning_scene/planning_scene.h | 3 ++- .../include/moveit/mesh_filter/stereo_camera_model.h | 3 +-- .../planning_scene_monitor/planning_scene_monitor.h | 9 +++------ 3 files changed, 6 insertions(+), 9 deletions(-) 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 b746f04d52..9e367ef258 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -87,7 +87,8 @@ using ObjectTypeMap = std::map +class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : private boost::noncopyable, + public std::enable_shared_from_this { public: /** \brief construct using an existing RobotModel */ diff --git a/moveit_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 f4552879ce..cd4a0a7732 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -150,8 +150,7 @@ class MOVEIT_MESH_FILTER_EXPORT StereoCameraModel : public SensorModel }; /** \brief predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) */ - static const StereoCameraModel::Parameters& - REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) + static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming) /** \brief source code of the vertex shader used to render the meshes*/ static const std::string RENDER_VERTEX_SHADER_SOURCE; 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 5c3415747d..c275e40d40 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -88,16 +88,14 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: static const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states" /// The name of the topic used by default for attached collision objects - static const std::string - DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" + static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object" /// The name of the topic used by default for receiving collision objects in the world static const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object" /// The name of the topic used by default for receiving geometry information about a planning scene (complete /// overwrite of world geometry) - static const std::string - DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" + static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world" /// The name of the topic used by default for receiving full planning scenes or planning scene diffs static const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene" @@ -107,8 +105,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: /// The name of the topic used by default for publishing the monitored planning scene (this is without "/" in the /// name, so the topic is prefixed by the node name) - static const std::string - MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" + static const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene" /** @brief Constructor * @param robot_description The name of the ROS parameter that contains the URDF (in string format)