diff --git a/nodelet/include/nodelet/detail/callback_queue.h b/nodelet/include/nodelet/detail/callback_queue.h index 45ea68a2..f4aa6edf 100644 --- a/nodelet/include/nodelet/detail/callback_queue.h +++ b/nodelet/include/nodelet/detail/callback_queue.h @@ -30,6 +30,8 @@ #ifndef NODELET_CALLBACK_QUEUE_H #define NODELET_CALLBACK_QUEUE_H +#include "nodelet/nodeletdecl.h" + #include #include #include @@ -47,7 +49,7 @@ namespace detail class CallbackQueueManager; -class CallbackQueue : public ros::CallbackQueueInterface, +class NODELETLIB_DECL CallbackQueue : public ros::CallbackQueueInterface, public boost::enable_shared_from_this { public: diff --git a/nodelet/include/nodelet/detail/callback_queue_manager.h b/nodelet/include/nodelet/detail/callback_queue_manager.h index 59c6f5c7..bcf341c3 100644 --- a/nodelet/include/nodelet/detail/callback_queue_manager.h +++ b/nodelet/include/nodelet/detail/callback_queue_manager.h @@ -30,6 +30,8 @@ #ifndef NODELET_CALLBACK_QUEUE_MANAGER_H #define NODELET_CALLBACK_QUEUE_MANAGER_H +#include "nodelet/nodeletdecl.h" + #include #include @@ -60,7 +62,7 @@ typedef boost::shared_ptr CallbackQueuePtr; * single long-running callback can potentially block other callbacks from being executed. Some kind of * work-stealing could mitigate this, and is a good direction for future work. */ -class CallbackQueueManager +class NODELETLIB_DECL CallbackQueueManager { public: /** diff --git a/nodelet/include/nodelet/loader.h b/nodelet/include/nodelet/loader.h index 95d193e7..00cd87f4 100644 --- a/nodelet/include/nodelet/loader.h +++ b/nodelet/include/nodelet/loader.h @@ -36,6 +36,8 @@ #ifndef NODELET_LOADER_H #define NODELET_LOADER_H +#include "nodeletdecl.h" + #include #include #include @@ -57,7 +59,7 @@ typedef std::vector V_string; /** \brief A class which will construct and sequentially call Nodelets according to xml * This is the primary way in which users are expected to interact with Nodelets */ -class Loader +class NODELETLIB_DECL Loader { public: /** \brief Construct the nodelet loader with optional ros API at default location of NodeHandle("~")*/ diff --git a/nodelet/include/nodelet/nodelet.h b/nodelet/include/nodelet/nodelet.h index 48b82411..ae94892e 100644 --- a/nodelet/include/nodelet/nodelet.h +++ b/nodelet/include/nodelet/nodelet.h @@ -30,6 +30,7 @@ #ifndef NODELET_NODELET_H #define NODELET_NODELET_H +#include "nodeletdecl.h" #include "exception.h" #include @@ -182,7 +183,7 @@ class MultipleInitializationException : public Exception {} }; -class Nodelet +class NODELETLIB_DECL Nodelet { // Protected data fields for use by the subclass. protected: diff --git a/nodelet/include/nodelet/nodeletdecl.h b/nodelet/include/nodelet/nodeletdecl.h new file mode 100644 index 00000000..5ea2e84b --- /dev/null +++ b/nodelet/include/nodelet/nodeletdecl.h @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2010, Willow Garage, Inc. + * + * 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 names of Stanford University or Willow Garage, 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. + */ + +#ifndef NODELETDECL_H +#define NODELETDECL_H + +#include + +#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries + #ifdef nodeletlib_EXPORTS // we are building a shared lib/dll + #define NODELETLIB_DECL ROS_HELPER_EXPORT + #else // we are using shared lib/dll + #define NODELETLIB_DECL ROS_HELPER_IMPORT + #endif +#else // ros is being built around static libraries + #define NODELETLIB_DECL +#endif + +#endif // NODELETDECL_H + +