diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index 49111a4270..a1603e8b77 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -50,6 +50,10 @@ if(BUILD_TESTING) target_link_libraries(test_all_valid ${MOVEIT_LIB_NAME} moveit_robot_model) endif() +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "COLLISION_DETECTION_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib ARCHIVE DESTINATION lib diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index fdc9aec03b..a23bcb8afb 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -38,6 +38,7 @@ #include #include +#include namespace collision_detection { @@ -46,6 +47,6 @@ class CollisionDetectorAllocatorAllValid : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_env_allvalid.cpp + COLLISION_DETECTION_PUBLIC static const std::string NAME; // defined in collision_env_allvalid.cpp }; } // namespace collision_detection diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.hpp new file mode 100644 index 0000000000..de3c080893 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/visibility_control.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COLLISION_DETECTION__VISIBILITY_CONTROL_HPP_ +#define COLLISION_DETECTION__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define COLLISION_DETECTION_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_BUILDING_LIBRARY + #define COLLISION_DETECTION_PUBLIC COLLISION_DETECTION_EXPORT + #else + #define COLLISION_DETECTION_PUBLIC COLLISION_DETECTION_IMPORT + #endif + #define COLLISION_DETECTION_PUBLIC_TYPE COLLISION_DETECTION_PUBLIC + #define COLLISION_DETECTION_LOCAL +#else + #define COLLISION_DETECTION_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_PUBLIC + #define COLLISION_DETECTION_LOCAL + #endif + #define COLLISION_DETECTION_PUBLIC_TYPE +#endif +// clang-format on +#endif // COLLISION_DETECTION__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 5e2baec8b4..3ded044c96 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -19,6 +19,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_collision_detection ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "COLLISION_DETECTION_FCL_BUILDING_LIBRARY") + add_library(collision_detector_fcl_plugin SHARED src/collision_detector_fcl_plugin_loader.cpp) set_target_properties(collision_detector_fcl_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(collision_detector_fcl_plugin 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..dedda9c0d7 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -38,6 +38,7 @@ #include #include +#include namespace collision_detection { @@ -46,6 +47,6 @@ class CollisionDetectorAllocatorFCL : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_env_fcl.cpp + COLLISION_DETECTION_FCL_PUBLIC static 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/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 307130939c..5f872dc0ed 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -38,10 +38,11 @@ #include #include +#include namespace collision_detection { -class CollisionDetectorFCLPluginLoader : public CollisionPlugin +class COLLISION_DETECTION_FCL_PLUGIN_PUBLIC CollisionDetectorFCLPluginLoader : public CollisionPlugin { public: bool initialize(const planning_scene::PlanningScenePtr& scene, bool exclusive) const override; diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.hpp b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.hpp new file mode 100644 index 0000000000..91c54499c5 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/visibility_control.hpp @@ -0,0 +1,100 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_HPP_ +#define COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define COLLISION_DETECTION_FCL_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_FCL_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_FCL_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_FCL_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_FCL_BUILDING_LIBRARY + #define COLLISION_DETECTION_FCL_PUBLIC COLLISION_DETECTION_FCL_EXPORT + #else + #define COLLISION_DETECTION_FCL_PUBLIC COLLISION_DETECTION_FCL_IMPORT + #endif + #define COLLISION_DETECTION_FCL_PUBLIC_TYPE COLLISION_DETECTION_FCL_PUBLIC + #define COLLISION_DETECTION_FCL_LOCAL +#else + #define COLLISION_DETECTION_FCL_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_FCL_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_FCL_PUBLIC + #define COLLISION_DETECTION_FCL_LOCAL + #endif + #define COLLISION_DETECTION_FCL_PUBLIC_TYPE +#endif + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define COLLISION_DETECTION_FCL_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define COLLISION_DETECTION_FCL_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define COLLISION_DETECTION_FCL_PLUGIN_EXPORT __declspec(dllexport) + #define COLLISION_DETECTION_FCL_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef COLLISION_DETECTION_FCL_PLUGIN_BUILDING_LIBRARY + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC COLLISION_DETECTION_FCL_PLUGIN_EXPORT + #else + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC COLLISION_DETECTION_FCL_PLUGIN_IMPORT + #endif + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC_TYPE COLLISION_DETECTION_FCL_PLUGIN_PUBLIC + #define COLLISION_DETECTION_FCL_PLUGIN_LOCAL +#else + #define COLLISION_DETECTION_FCL_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define COLLISION_DETECTION_FCL_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC + #define COLLISION_DETECTION_FCL_PLUGIN_LOCAL + #endif + #define COLLISION_DETECTION_FCL_PLUGIN_PUBLIC_TYPE +#endif + +// clang-format on +#endif // COLLISION_DETECTION_FCL__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index ce3e6c3fe9..621b192668 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -7,6 +7,10 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V # This line is needed to ensure that messages are done being built before this is built ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp urdf urdfdom_headers srdfdom moveit_msgs geometric_shapes geometry_msgs Boost) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "KINEMATICS_BASE_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib ARCHIVE DESTINATION lib diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 9f55085f61..158e710d47 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -39,6 +39,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" #include #include @@ -140,7 +141,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase) // Defines KinematicsBasePtr, ConstPtr, We * @class KinematicsBase * @brief Provides an interface for kinematics solvers. */ -class KinematicsBase +class KINEMATICS_BASE_PUBLIC KinematicsBase { public: static const rclcpp::Logger LOGGER; diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.hpp b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.hpp new file mode 100644 index 0000000000..1ed3f33d2e --- /dev/null +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef KINEMATICS_BASE__VISIBILITY_CONTROL_HPP_ +#define KINEMATICS_BASE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define KINEMATICS_BASE_EXPORT __attribute__ ((dllexport)) + #define KINEMATICS_BASE_IMPORT __attribute__ ((dllimport)) + #else + #define KINEMATICS_BASE_EXPORT __declspec(dllexport) + #define KINEMATICS_BASE_IMPORT __declspec(dllimport) + #endif + #ifdef KINEMATICS_BASE_BUILDING_LIBRARY + #define KINEMATICS_BASE_PUBLIC KINEMATICS_BASE_EXPORT + #else + #define KINEMATICS_BASE_PUBLIC KINEMATICS_BASE_IMPORT + #endif + #define KINEMATICS_BASE_PUBLIC_TYPE KINEMATICS_BASE_PUBLIC + #define KINEMATICS_BASE_LOCAL +#else + #define KINEMATICS_BASE_EXPORT __attribute__ ((visibility("default"))) + #define KINEMATICS_BASE_IMPORT + #if __GNUC__ >= 4 + #define KINEMATICS_BASE_PUBLIC __attribute__ ((visibility("default"))) + #define KINEMATICS_BASE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define KINEMATICS_BASE_PUBLIC + #define KINEMATICS_BASE_LOCAL + #endif + #define KINEMATICS_BASE_PUBLIC_TYPE +#endif + +// clang-format on +#endif // KINEMATICS_BASE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index 5413bc5c1e..f81fcc925d 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -25,6 +25,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_utils ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_SCENE_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib ARCHIVE DESTINATION lib 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 a34f79f2f6..a65850e90d 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -46,6 +46,7 @@ #include #include #include +#include #include #include #include @@ -99,8 +100,8 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model, const collision_detection::WorldPtr& world = collision_detection::WorldPtr(new collision_detection::World())); - static const std::string OCTOMAP_NS; - static const std::string DEFAULT_SCENE_NAME; + PLANNING_SCENE_PUBLIC static const std::string OCTOMAP_NS; + PLANNING_SCENE_PUBLIC static const std::string DEFAULT_SCENE_NAME; ~PlanningScene(); diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.hpp new file mode 100644 index 0000000000..e2ac322d90 --- /dev/null +++ b/moveit_core/planning_scene/include/moveit/planning_scene/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_SCENE__VISIBILITY_CONTROL_HPP_ +#define PLANNING_SCENE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_BUILDING_LIBRARY + #define PLANNING_SCENE_PUBLIC PLANNING_SCENE_EXPORT + #else + #define PLANNING_SCENE_PUBLIC PLANNING_SCENE_IMPORT + #endif + #define PLANNING_SCENE_PUBLIC_TYPE PLANNING_SCENE_PUBLIC + #define PLANNING_SCENE_LOCAL +#else + #define PLANNING_SCENE_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_PUBLIC + #define PLANNING_SCENE_LOCAL + #endif + #define PLANNING_SCENE_PUBLIC_TYPE +#endif + +// clang-format on +#endif // PLANNING_SCENE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/robot_model/CMakeLists.txt b/moveit_core/robot_model/CMakeLists.txt index 66057ccffc..4ae6f6408b 100644 --- a/moveit_core/robot_model/CMakeLists.txt +++ b/moveit_core/robot_model/CMakeLists.txt @@ -29,6 +29,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_kinematics_base ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "ROBOT_MODEL_BUILDING_LIBRARY") + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(test_robot_model test/test.cpp) diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 3560c67da7..22278a9ce7 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -39,6 +39,7 @@ #include #include +#include #include // joint types @@ -61,7 +62,7 @@ MOVEIT_CLASS_FORWARD(RobotModel) // Defines RobotModelPtr, ConstPtr, WeakPtr... /** \brief Definition of a kinematic model. This class is not thread safe, however multiple instances can be created */ -class RobotModel +class ROBOT_MODEL_PUBLIC RobotModel { public: /** \brief Construct a kinematic model from a parsed description and a list of planning groups */ diff --git a/moveit_core/robot_model/include/moveit/robot_model/visibility_control.hpp b/moveit_core/robot_model/include/moveit/robot_model/visibility_control.hpp new file mode 100644 index 0000000000..b08a2e876e --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROBOT_MODEL__VISIBILITY_CONTROL_HPP_ +#define ROBOT_MODEL__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_MODEL_EXPORT __attribute__ ((dllexport)) + #define ROBOT_MODEL_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_MODEL_EXPORT __declspec(dllexport) + #define ROBOT_MODEL_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_MODEL_BUILDING_LIBRARY + #define ROBOT_MODEL_PUBLIC ROBOT_MODEL_EXPORT + #else + #define ROBOT_MODEL_PUBLIC ROBOT_MODEL_IMPORT + #endif + #define ROBOT_MODEL_PUBLIC_TYPE ROBOT_MODEL_PUBLIC + #define ROBOT_MODEL_LOCAL +#else + #define ROBOT_MODEL_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_MODEL_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_MODEL_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_MODEL_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_MODEL_PUBLIC + #define ROBOT_MODEL_LOCAL + #endif + #define ROBOT_MODEL_PUBLIC_TYPE +#endif + +// clang-format on +#endif // ROBOT_MODEL__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/robot_state/CMakeLists.txt b/moveit_core/robot_state/CMakeLists.txt index 89e77072d1..e648cbe122 100644 --- a/moveit_core/robot_state/CMakeLists.txt +++ b/moveit_core/robot_state/CMakeLists.txt @@ -25,6 +25,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_transforms ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "ROBOT_STATE_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib ARCHIVE DESTINATION lib diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 0a3fcf35a3..d7b7f432c2 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -86,7 +87,7 @@ typedef boost::function= 4 + #define ROBOT_STATE_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_STATE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_STATE_PUBLIC + #define ROBOT_STATE_LOCAL + #endif + #define ROBOT_STATE_PUBLIC_TYPE +#endif + +// clang-format on +#endif // ROBOT_STATE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_core/robot_trajectory/CMakeLists.txt b/moveit_core/robot_trajectory/CMakeLists.txt index 64b40492ee..cd215ae5f9 100644 --- a/moveit_core/robot_trajectory/CMakeLists.txt +++ b/moveit_core/robot_trajectory/CMakeLists.txt @@ -14,6 +14,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_state ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "ROBOT_TRAJECTORY_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index f5168b7fe8..7a48ce0abe 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -37,6 +37,7 @@ #pragma once #include +#include #include #include #include @@ -55,7 +56,7 @@ MOVEIT_CLASS_FORWARD(RobotTrajectory) // Defines RobotTrajectoryPtr, ConstPtr, /** \brief Maintain a sequence of waypoints and the time durations between these waypoints */ -class RobotTrajectory +class ROBOT_TRAJECTORY_PUBLIC RobotTrajectory { public: RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group); diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/visibility_control.hpp b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/visibility_control.hpp new file mode 100644 index 0000000000..2e98ad530a --- /dev/null +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROBOT_TRAJECTORY__VISIBILITY_CONTROL_HPP_ +#define ROBOT_TRAJECTORY__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_TRAJECTORY_EXPORT __attribute__ ((dllexport)) + #define ROBOT_TRAJECTORY_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_TRAJECTORY_EXPORT __declspec(dllexport) + #define ROBOT_TRAJECTORY_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_TRAJECTORY_BUILDING_LIBRARY + #define ROBOT_TRAJECTORY_PUBLIC ROBOT_TRAJECTORY_EXPORT + #else + #define ROBOT_TRAJECTORY_PUBLIC ROBOT_TRAJECTORY_IMPORT + #endif + #define ROBOT_TRAJECTORY_PUBLIC_TYPE ROBOT_TRAJECTORY_PUBLIC + #define ROBOT_TRAJECTORY_LOCAL +#else + #define ROBOT_TRAJECTORY_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_TRAJECTORY_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_TRAJECTORY_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_TRAJECTORY_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_TRAJECTORY_PUBLIC + #define ROBOT_TRAJECTORY_LOCAL + #endif + #define ROBOT_TRAJECTORY_PUBLIC_TYPE +#endif + +// clang-format on +#endif // ROBOT_TRAJECTORY__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/move_group/CMakeLists.txt b/moveit_ros/move_group/CMakeLists.txt index 1695187ba4..c7289ee426 100644 --- a/moveit_ros/move_group/CMakeLists.txt +++ b/moveit_ros/move_group/CMakeLists.txt @@ -26,6 +26,10 @@ target_include_directories(moveit_move_group_capabilities_base PUBLIC include) ament_target_dependencies(moveit_move_group_capabilities_base rclcpp moveit_core moveit_ros_planning tf2_geometry_msgs) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(moveit_move_group_capabilities_base PRIVATE "MOVE_GROUP_BUILDING_LIBRARY") + add_executable(move_group src/move_group.cpp) target_include_directories(move_group PUBLIC include) ament_target_dependencies(move_group diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index f80e3fd7f4..0f04dd4422 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -41,6 +41,7 @@ #include #include #include +#include namespace move_group { @@ -54,7 +55,7 @@ enum MoveGroupState MOVEIT_CLASS_FORWARD(MoveGroupCapability) // Defines MoveGroupCapabilityPtr, ConstPtr, WeakPtr... etc -class MoveGroupCapability +class MOVE_GROUP_PUBLIC MoveGroupCapability { public: MoveGroupCapability(const std::string& capability_name) : capability_name_(capability_name) diff --git a/moveit_ros/move_group/include/moveit/move_group/visibility_control.hpp b/moveit_ros/move_group/include/moveit/move_group/visibility_control.hpp new file mode 100644 index 0000000000..64065b4afa --- /dev/null +++ b/moveit_ros/move_group/include/moveit/move_group/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVE_GROUP__VISIBILITY_CONTROL_HPP_ +#define MOVE_GROUP__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVE_GROUP_EXPORT __attribute__ ((dllexport)) + #define MOVE_GROUP_IMPORT __attribute__ ((dllimport)) + #else + #define MOVE_GROUP_EXPORT __declspec(dllexport) + #define MOVE_GROUP_IMPORT __declspec(dllimport) + #endif + #ifdef MOVE_GROUP_BUILDING_LIBRARY + #define MOVE_GROUP_PUBLIC MOVE_GROUP_EXPORT + #else + #define MOVE_GROUP_PUBLIC MOVE_GROUP_IMPORT + #endif + #define MOVE_GROUP_PUBLIC_TYPE MOVE_GROUP_PUBLIC + #define MOVE_GROUP_LOCAL +#else + #define MOVE_GROUP_EXPORT __attribute__ ((visibility("default"))) + #define MOVE_GROUP_IMPORT + #if __GNUC__ >= 4 + #define MOVE_GROUP_PUBLIC __attribute__ ((visibility("default"))) + #define MOVE_GROUP_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVE_GROUP_PUBLIC + #define MOVE_GROUP_LOCAL + #endif + #define MOVE_GROUP_PUBLIC_TYPE +#endif + +// clang-format on +#endif // MOVE_GROUP__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index 3ef0122175..d7d988b1eb 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -3,6 +3,10 @@ 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}") +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_PIPELINE_BUILDING_LIBRARY") + ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_msgs 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..b50b268f54 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -42,6 +42,7 @@ #include #include #include +#include #include @@ -59,15 +60,15 @@ 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; + PLANNING_PIPELINE_PUBLIC 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 const std::string MOTION_PLAN_REQUEST_TOPIC; + PLANNING_PIPELINE_PUBLIC 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 const std::string MOTION_CONTACTS_TOPIC; + PLANNING_PIPELINE_PUBLIC static const std::string MOTION_CONTACTS_TOPIC; /** \brief Given a robot model (\e model), a node handle (\e 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.hpp b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.hpp new file mode 100644 index 0000000000..0da8614141 --- /dev/null +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_PIPELINE__VISIBILITY_CONTROL_HPP_ +#define PLANNING_PIPELINE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#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_LIBRARY + #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 + +// clang-format on +#endif // PLANNING_PIPELINE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index 36566283b8..c92d171286 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -31,6 +31,10 @@ ament_target_dependencies(demo_scene ) target_link_libraries(demo_scene ${MOVEIT_LIB_NAME}) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "PLANNING_SCENE_MONITOR_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib 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..fc7eaeb6d2 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -45,6 +45,7 @@ #include #include #include +#include #include #include #include @@ -59,7 +60,7 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor) // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class PlanningSceneMonitor : private boost::noncopyable +class PLANNING_SCENE_MONITOR_PUBLIC PlanningSceneMonitor : private boost::noncopyable { public: enum SceneUpdateType diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.hpp b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.hpp new file mode 100644 index 0000000000..e28e847a82 --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_HPP_ +#define PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_MONITOR_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_MONITOR_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_MONITOR_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_MONITOR_BUILDING_LIBRARY + #define PLANNING_SCENE_MONITOR_PUBLIC PLANNING_SCENE_MONITOR_EXPORT + #else + #define PLANNING_SCENE_MONITOR_PUBLIC PLANNING_SCENE_MONITOR_IMPORT + #endif + #define PLANNING_SCENE_MONITOR_PUBLIC_TYPE PLANNING_SCENE_MONITOR_PUBLIC + #define PLANNING_SCENE_MONITOR_LOCAL +#else + #define PLANNING_SCENE_MONITOR_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_MONITOR_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_MONITOR_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_MONITOR_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_MONITOR_PUBLIC + #define PLANNING_SCENE_MONITOR_LOCAL + #endif + #define PLANNING_SCENE_MONITOR_PUBLIC_TYPE +#endif + +// clang-format on +#endif // PLANNING_SCENE_MONITOR__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index cbd701ea71..9a9ee0424f 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -18,6 +18,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_planning_scene_monitor ) +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "TRAJECTORY_EXECUTION_MANAGER_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib 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..2112a48c44 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 @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -59,7 +60,7 @@ MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager) // Defines TrajectoryExecution class TrajectoryExecutionManager { public: - static const std::string EXECUTION_EVENT_TOPIC; + TRAJECTORY_EXECUTION_MANAGER_PUBLIC 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/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.hpp b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.hpp new file mode 100644 index 0000000000..9eefc78833 --- /dev/null +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_HPP_ +#define TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#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_LIBRARY + #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 + +// clang-format on +#endif // TRAJECTORY_EXECUTION_MANAGER__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index 7fef2462e2..0aa85f1399 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -22,6 +22,10 @@ if(WIN32) # set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES SUFFIX .pyd) endif() +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "MOVE_GROUP_INTERFACE_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION lib 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 3d12582654..a35d446b15 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 @@ -39,6 +39,7 @@ #include #include +#include #include #include #include @@ -105,7 +106,7 @@ 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; + MOVE_GROUP_INTERFACE_PUBLIC static 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.hpp b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.hpp new file mode 100644 index 0000000000..a261941aa4 --- /dev/null +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_HPP_ +#define MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((dllexport)) + #define MOVE_GROUP_INTERFACE_IMPORT __attribute__ ((dllimport)) + #else + #define MOVE_GROUP_INTERFACE_EXPORT __declspec(dllexport) + #define MOVE_GROUP_INTERFACE_IMPORT __declspec(dllimport) + #endif + #ifdef MOVE_GROUP_INTERFACE_BUILDING_LIBRARY + #define MOVE_GROUP_INTERFACE_PUBLIC MOVE_GROUP_INTERFACE_EXPORT + #else + #define MOVE_GROUP_INTERFACE_PUBLIC MOVE_GROUP_INTERFACE_IMPORT + #endif + #define MOVE_GROUP_INTERFACE_PUBLIC_TYPE MOVE_GROUP_INTERFACE_PUBLIC + #define MOVE_GROUP_INTERFACE_LOCAL +#else + #define MOVE_GROUP_INTERFACE_EXPORT __attribute__ ((visibility("default"))) + #define MOVE_GROUP_INTERFACE_IMPORT + #if __GNUC__ >= 4 + #define MOVE_GROUP_INTERFACE_PUBLIC __attribute__ ((visibility("default"))) + #define MOVE_GROUP_INTERFACE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define MOVE_GROUP_INTERFACE_PUBLIC + #define MOVE_GROUP_INTERFACE_LOCAL + #endif + #define MOVE_GROUP_INTERFACE_PUBLIC_TYPE +#endif + +// clang-format on +#endif // MOVE_GROUP_INTERFACE__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index ba10e6ce0c..710aa53078 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -42,6 +42,10 @@ if(BUILD_TESTING) Boost) endif() +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME} PRIVATE "ROBOT_INTERACTION_BUILDING_LIBRARY") + install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib ARCHIVE DESTINATION lib diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 12a9c9203d..5674d46e3d 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -37,6 +37,7 @@ #pragma once #include +#include #include #include @@ -44,7 +45,7 @@ namespace robot_interaction { // Maintains a set of KinematicOptions with a key/value mapping and a default // value. -class KinematicOptionsMap +class ROBOT_INTERACTION_PUBLIC KinematicOptionsMap { public: /// Constructor - set all options to reasonable default values. diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.hpp b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.hpp new file mode 100644 index 0000000000..cfa6a9b327 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROBOT_INTERACTION__VISIBILITY_CONTROL_HPP_ +#define ROBOT_INTERACTION__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ROBOT_INTERACTION_EXPORT __attribute__ ((dllexport)) + #define ROBOT_INTERACTION_IMPORT __attribute__ ((dllimport)) + #else + #define ROBOT_INTERACTION_EXPORT __declspec(dllexport) + #define ROBOT_INTERACTION_IMPORT __declspec(dllimport) + #endif + #ifdef ROBOT_INTERACTION_BUILDING_LIBRARY + #define ROBOT_INTERACTION_PUBLIC ROBOT_INTERACTION_EXPORT + #else + #define ROBOT_INTERACTION_PUBLIC ROBOT_INTERACTION_IMPORT + #endif + #define ROBOT_INTERACTION_PUBLIC_TYPE ROBOT_INTERACTION_PUBLIC + #define ROBOT_INTERACTION_LOCAL +#else + #define ROBOT_INTERACTION_EXPORT __attribute__ ((visibility("default"))) + #define ROBOT_INTERACTION_IMPORT + #if __GNUC__ >= 4 + #define ROBOT_INTERACTION_PUBLIC __attribute__ ((visibility("default"))) + #define ROBOT_INTERACTION_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ROBOT_INTERACTION_PUBLIC + #define ROBOT_INTERACTION_LOCAL + #endif + #define ROBOT_INTERACTION_PUBLIC_TYPE +#endif + +// clang-format on +#endif // ROBOT_INTERACTION__VISIBILITY_CONTROL_HPP_ \ No newline at end of file diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 7307aa383c..99c9bc395d 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -26,6 +26,10 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} ) target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include") +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${MOVEIT_LIB_NAME}_core PRIVATE "PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_LIBRARY") + install(DIRECTORY include/ DESTINATION include) install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME} 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..a87ac33365 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 @@ -40,6 +40,7 @@ #include #include #include +#include #ifndef Q_MOC_RUN #include #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.hpp new file mode 100644 index 0000000000..f0207458be --- /dev/null +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/visibility_control.hpp @@ -0,0 +1,72 @@ +// Copyright (c) 2019, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Open Source Robotics Foundation, Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ +#define PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +// clang-format off +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((dllexport)) + #define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __attribute__ ((dllimport)) + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __declspec(dllexport) + #define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT __declspec(dllimport) + #endif + #ifdef PLANNING_SCENE_RVIZ_PLUGIN_BUILDING_LIBRARY + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_EXPORT + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC PLANNING_SCENE_RVIZ_PLUGIN_IMPORT + #endif + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC + #define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL +#else + #define PLANNING_SCENE_RVIZ_PLUGIN_EXPORT __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_RVIZ_PLUGIN_IMPORT + #if __GNUC__ >= 4 + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC __attribute__ ((visibility("default"))) + #define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC + #define PLANNING_SCENE_RVIZ_PLUGIN_LOCAL + #endif + #define PLANNING_SCENE_RVIZ_PLUGIN_PUBLIC_TYPE +#endif + +// clang-format on +#endif // PLANNING_SCENE_RVIZ_PLUGIN__VISIBILITY_CONTROL_HPP_ \ No newline at end of file