pax_global_header00006660000000000000000000000064133673106030014514gustar00rootroot0000000000000052 comment=f61e5e123bd5b472209cfdbcf2886f0dff94a982 ros-nodelet-core-1.9.16/000077500000000000000000000000001336731060300147735ustar00rootroot00000000000000ros-nodelet-core-1.9.16/.hgignore000066400000000000000000000002241336731060300165740ustar00rootroot00000000000000^nodelet/build ^nodelet/bin ^nodelet/lib ^nodelet/src/nodelet/srv ^nodelet/srv_gen ^nodelet_topic_tools/build ^test_nodelet/build ^test_nodelet/lib ros-nodelet-core-1.9.16/nodelet/000077500000000000000000000000001336731060300164255ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/CHANGELOG.rst000066400000000000000000000323161336731060300204530ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package nodelet ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.9.16 (2018-04-27) ------------------- * uuid dependency fixup (`#74 `_) * don't export uuid library * wrap for readability * Contributors: Mikael Arguedas 1.9.15 (2018-03-16) ------------------- * use new pluginlib headers (`#73 `_) * Contributors: Mikael Arguedas 1.9.14 (2017-11-15) ------------------- * declared_nodelets: continue on missing plugin xml (`#70 `_) * Contributors: Furushchev 1.9.13 (2017-10-27) ------------------- * Drop unneeded forward declaration. (`#68 `_) * Contributors: Mike Purvis 1.9.12 (2017-08-04) ------------------- 1.9.11 (2017-07-27) ------------------- * Add getRemappingArgs method to nodelet to reuse it in subclass (`#61 `_) * remove trailing whitespaces (`#62 `_) * switch to package format 2 (`#63 `_) * Show pkg and manifest file with verbose option (`#59 `_) * Contributors: Kentaro Wada, Mikael Arguedas 1.9.10 (2017-03-27) ------------------- * installs the list_nodelets script (`#58 `_) * python3 compatibility * pep8 * install list_nodelets * print message with service name * return outside of try catch * fix unused var warning * give node a name, empty node names not supported since https://github.com/ros/ros_comm/commit/bd3af70520648783da8aa4d3610f234a4d2bd41f * remove tabs * fix help message * Contributors: Mikael Arguedas 1.9.9 (2017-02-17) ------------------ * drop unused dependency on tinyxml (`#54 `_) * Install the declared_nodelets script (`#53 `_) * Contributors: Dmitry Rozhkov, Kentaro Wada 1.9.8 (2016-11-15) ------------------ * Fix bond handling during nodelet unloading (`#51 `_) * add test whether bond breaking on unload works (tests `#50 `_) * disable callback for broken bond when we are breaking it This avoids the nodelet::LoaderROS::unload() method to be called twice for the same nodelet, causing an error output. * use AsyncSpinner for nodelet load in order for the shutdown procedure to work During shutdown, the bonds still need to communicate their status in order for the nodelet to properly/cleanly/quickly unload. This requires the node to spin. * add test whether LoaderROS::unload() is called twice (tests `#50 `_) * Contributors: Daniel Seifert 1.9.7 (2016-10-24) ------------------ * Use rospkg instead of roslib in declared_nodelets Close https://github.com/ros/nodelet_core/issues/48 * Contributors: Kentaro Wada 1.9.6 (2016-09-20) ------------------ 1.9.5 (2016-06-22) ------------------ * more sane debugging messages * Contributors: Daniel Stonier 1.9.4 (2016-03-15) ------------------ * update maintainer * Contributors: Mikael Arguedas 1.9.3 (2015-08-05) ------------------ * adding support for named nodelet loggers * nodelet loader: display error messages from both load attempts on failure * Contributors: Max Schwarz, Tully Foote 1.9.2 (2014-10-30) ------------------ * Fix dependency version * Contributors: Esteve Fernandez 1.9.1 (2014-10-29) ------------------ * Use FindUUID.cmake from cmake-modules to find the UUID libraries * nodelet: Loader: do not call impl->refresh_classes_ if not available * Contributors: Esteve Fernandez, Max Schwarz 1.9.0 (2014-06-16) ------------------ * Fix initialization error handling (`#13 `_) * Contributors: Esteve Fernandez 1.8.3 (2014-05-08) ------------------ * Add version to pluginlib dependency * nodelet: avoid breaking bond when unloading unknown nodelet * nodelet: refresh list of available classes if class is not found * Fixed missing header * Correctly check that there are enough arguments when nodelet is launched with the unload command * Exit if Loader::load returns failure in "standalone" mode instead of continuing to run * Contributors: Dirk Thomas, Esteve Fernandez, Forrest Voight, Gary Servin, Marcus Liebhardt, Mitchell Wills * fix missing header (`#14 `_) * fix check that there are enough arguments when nodelet is launched with the unload command (`#12 `_) * exit if Loader::load returns failure in "standalone" mode instead of continuing to run (`#11 `_) 1.8.2 (2014-01-07) ------------------ * fix erasing bond when it breaks (`#8 `_) 1.8.0 (2013-07-11) ------------------ * add missing archive/library/runtime destination for library * Export pluginlib as a transitive dependency Also remove some old Apple specific rules which are no longer required. * use EXPORTED_TARGETS variable instead of explicit target names * update email in package.xml 1.7.15 (2013-03-12) ------------------- 1.7.14 (2013-01-13) ------------------- * add missing link library uuid (fix `#4 `_) 1.7.13 (2012-12-27) ------------------- * move nodelet_topic_tools to separate package, fix unit tests 1.7.12 (2012-12-19 01:34) ------------------------- 1.7.11 (2012-12-19 00:58) ------------------------- 1.7.10 (2012-12-14) ------------------- * add missing dep to catkin 1.7.9 (2012-12-13) ------------------ * add missing downstream depend * switched from langs to message_* packages 1.7.8 (2012-12-06) ------------------ * updated catkin_package(DEPENDS) 1.7.7 (2012-11-01) ------------------ 1.7.6 (2012-10-30) ------------------ * fix catkin function order * clean up package.xml files 1.7.5 (2012-10-23) ------------------ 1.7.4 (2012-10-08) ------------------ 1.7.3 (2012-10-04) ------------------ 1.7.2 (2012-10-03) ------------------ 1.7.1 (2012-10-02) ------------------ * adding nodelet_core metapackage and reving to 1.7.1 1.7.0 (2012-10-01) ------------------ * fix dependencies * make it compile locally * first pass at catkinizing the stack * updated to latest pluginlib * updated usage of pluginlib according to updated REP 121 * use updated pluginlib to auto-unload libraries when unloading nodelets * fixed issue `#5144 `_ on OS X lion * Commentary on who owns what among Loader, Nodelet, CallbackQueue and CallbackQueueManager. * Moved most of Loader's member variables into an opaque PIMPL struct so we can change things without breaking ABI. * All bond code moved to LoaderROS. Loader no longer needs to know about bond. * Removed CallbackQueue::disable(). Loader removes a nodelet's queues from the queue manager when unloading it, which is sufficient to prevent new callbacks for that nodelet getting added. * Removed some code and comments concerned with callbacks getting called after their nodelet's destruction. This can't actually happen anymore, since callbacks only fire if they can lock a weak_ptr to their parent nodelet. * Refactoring to streamline Nodelet back down to a simple plugin interface. It no longer knows about detail::CallbackQueue[Manager] or Bond; init() simply takes the single- and multi-threaded ros::CallbackQueueInterface* instead (defaulting to NULL). Loader owns the callback queues and bond for each nodelet. This makes it possible to use Nodelet without all the surrounding infrastructure. * Take Bond pointers as const-ref instead of value in Loader and Nodelet. * Added Loader constructor taking a boost::function object used as a factory for nodelet instances, replacing the default use of a pluginlib class loader. This is to support ROSGUI, which defines its specialized plugin interface as a subclass of Nodelet, and thus needs a different class loader. * Removed some debug code in Loader constructor. * 'nodelet load' more reliably unloads the nodelet on exiting. In particular it intercepts XML-RPC shutdown command, used for example by 'rosnode kill'. * Enabled error output when service calls fail abnormally. * Rewrote tracked_object logic to be clearer. * Have detail::CallbackQueue use a ros::VoidConstWPtr as the tracked object, which is now optional. More generic, and fixes test_nodelet which was broken by the last commit. * Fixed race conditions/deadlocks when unloading a nodelet. Now disable the nodelet's callback queues before deleting it. The queues have a WPtr to the nodelet, so any outstanding callbacks will get discarded. * ~Loader now stops callback manager threads before destroying the nodelets. Otherwise the worker threads could operate on nodelet data as/after it's destroyed. * Use ros::names::parentNamespace(). * Cleaned scoped_ptr's out of ThreadInfo and updated its padding. * Made ThreadInfo::calling an atomic_count. This allows the manager thread to pick the queue with least work more accurately, and reduces contention b/c getSmallestQueue no longer needs to lock on ``queue_mutex_``. * Minor code cleanup and finer locking in managerThread(). * Actually pad ThreadInfo to a multiple of 64 bytes. Previous expression was wrongly wrapped in sizeof(). * Instead of ``thread_info_``.resize(num_threads), push each ThreadInfo on individually. With resize(), all threads ended up sharing the same queue_mutex and queue_cond. Doesn't seem to be much of a performance win though. * Added test instrumentation to CallbackQueueManager to track size of worker thread queues over time. Must be enabled at compilation time with -DNODELET_QUEUE_DEBUG. * nodelet patches for osx lion support from wjwwood * Added --no-bond option to nodelet loading to disable bonds. * updated platform tags * don't need to link against tinyxml directly * link against system tinyxml * Fix for `#4855 `_ This fix actually makes sense, but that it wasn't caught earlier doesn't. The construction of nodelet::Loader n(false) was creating the first node handle and letting it go out of scope, which was automagically calling ros::shutdown(), which is a dumb thing for ros::NodeHandle to do automagically on destruction. * Each nodelet now places its bonds on a custom callback queue * a script to list declared nodelets * real fix for `#4460 `_ * patch for `#4460 `_ * adding support for once, throttle, and filter features. With unit tests for all but the filters `#4681 `_ * fix for `#4609 `_ * MUX simplified by using a 8-connected null filters DeMUX has a specialization for message type (uses ros::Subscriber internally by default) Added rosdep for nodelet (uuid) * adding optional namespace aware constructor to nodelet loader. `#4243 `_ and fixing vestigial comments referencing Filters `#4221 `_ * nodelet uses bond to handle crashes on the manager or the spawner end. `#4221 `_ * locking in all cases * fix hang on CallbackQueueManager destruction (`#4402 `_) * better check for services * fix hanging tests and a hang on nodelet CallbackQueueManager destruction (`#4082 `_) * added a boost mutex * preventing nodelets from busywaiting * Added optional parameter num_worker_threads to nodelets. * Added Ubuntu platform tags to manifest * implemented nodelet unloading on shutdown * fixed a segfault on destroy * merging josh's branch from ticket `#3875 `_ * adding usage * fancy new command line parsing for nodelets `#3876 `_ * moving topic tools out of nodelet proper, removing rospy and message_filters dependencies from nodelet * doc updates * fixed a segfault * small changes (ptr->boost shared_ptr) * init guard * making nodehandles pointers to avoid default constructors * switching mt_spinner to be a pointer created on init so it's not trying to create a nodehandle at construction * cleanup * switching to cpp command based nodelet implementation as per API review * changes as per API review * enforcing unique name in manager * supporting argv passing on server side * getname return type for API review * adding MT Nodehandle creation methods and fixing up tutorials * passing parameters * we're always going to spin * added my_args in the service call * some changes as we discuss them during the API review * cleaning up private and public api elements * nodelet_internal_init is now private and a friend of NodeletLoader * nodelet API changes * COND rosconsole Nodelet wrappers working * adding multithreaded callback queue * removing unnecessary code after refactor * adding NODELET rosconsole wrappers, note init method is now void args * moving nodelet package into common trunk so I don't lose it in reorganization ros-nodelet-core-1.9.16/nodelet/CMakeLists.txt000066400000000000000000000034301336731060300211650ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(nodelet) ## Find catkin dependencies find_package(catkin REQUIRED bondcpp cmake_modules message_generation pluginlib rosconsole roscpp std_msgs ) ## Find Boost (only headers) find_package(Boost REQUIRED) ## Find UUID libraries find_package(UUID REQUIRED) ## Add service files to be generated add_service_files(DIRECTORY srv FILES NodeletList.srv NodeletLoad.srv NodeletUnload.srv) ## Generate servics generate_messages(DEPENDENCIES std_msgs) catkin_package( INCLUDE_DIRS include LIBRARIES nodeletlib CATKIN_DEPENDS bondcpp message_runtime pluginlib rosconsole roscpp std_msgs DEPENDS Boost ) include_directories( include ${catkin_INCLUDE_DIRS} ${BOOST_INCLUDE_DIRS} ${UUID_INCLUDE_DIRS}) # Debug only, collects stats on how callbacks are doled out to worker threads #add_definitions(-DNODELET_QUEUE_DEBUG) add_library(nodeletlib src/nodelet_class.cpp src/loader.cpp src/callback_queue.cpp src/callback_queue_manager.cpp) target_link_libraries(nodeletlib ${catkin_LIBRARIES} ${BOOST_LIBRARIES}) add_dependencies(nodeletlib ${nodelet_EXPORTED_TARGETS}) add_executable(nodelet src/nodelet.cpp) target_link_libraries(nodelet nodeletlib ${UUID_LIBRARIES} ${catkin_LIBRARIES} ${BOOST_LIBRARIES}) # install catkin_install_python(PROGRAMS scripts/declared_nodelets scripts/list_nodelets DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} ) install(TARGETS nodeletlib ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) install(TARGETS nodelet DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) ros-nodelet-core-1.9.16/nodelet/include/000077500000000000000000000000001336731060300200505ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/include/nodelet/000077500000000000000000000000001336731060300215025ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/include/nodelet/detail/000077500000000000000000000000001336731060300227445ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/include/nodelet/detail/callback_queue.h000066400000000000000000000050311336731060300260540ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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 NODELET_CALLBACK_QUEUE_H #define NODELET_CALLBACK_QUEUE_H #include #include #include namespace ros { class CallbackQueue; } namespace nodelet { namespace detail { class CallbackQueueManager; class CallbackQueue : public ros::CallbackQueueInterface, public boost::enable_shared_from_this { public: CallbackQueue(CallbackQueueManager* parent, const ros::VoidConstPtr& tracked_object = ros::VoidConstPtr()); ~CallbackQueue(); virtual void addCallback(const ros::CallbackInterfacePtr& callback, uint64_t owner_id = 0); virtual void removeByID(uint64_t owner_id); uint32_t callOne(); private: CallbackQueueManager* parent_; ros::CallbackQueue queue_; ros::VoidConstWPtr tracked_object_; bool has_tracked_object_; }; } // namespace detail } // namespace nodelet #endif // NODELET_CALLBACK_QUEUE_H ros-nodelet-core-1.9.16/nodelet/include/nodelet/detail/callback_queue_manager.h000066400000000000000000000124631336731060300275550ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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 NODELET_CALLBACK_QUEUE_MANAGER_H #define NODELET_CALLBACK_QUEUE_MANAGER_H #include #include #include #include #include #include #include #include #include namespace nodelet { namespace detail { class CallbackQueue; typedef boost::shared_ptr CallbackQueuePtr; /** * \brief Internal use * * Manages a set of callback queues, potentially calling callbacks from them concurrently in * different threads. Essentially a task manager specialized for callback queues. * * Uses 1 manager thread + N worker threads. The manager thread gives work to the worker threads by * finding the thread with the fewest pending tasks and appending to that list. This does mean that a * 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 { public: /** * \brief Constructor * * By default, uses the number of hardware threads available on the current system. */ CallbackQueueManager(uint32_t num_worker_threads = 0); ~CallbackQueueManager(); void addQueue(const CallbackQueuePtr& queue, bool threaded); void removeQueue(const CallbackQueuePtr& queue); void callbackAdded(const CallbackQueuePtr& queue); uint32_t getNumWorkerThreads(); void stop(); private: void managerThread(); struct ThreadInfo; void workerThread(ThreadInfo*); ThreadInfo* getSmallestQueue(); struct QueueInfo { QueueInfo() : threaded(false) , thread_index(0xffffffff) , in_thread(0) {} CallbackQueuePtr queue; bool threaded; // Only used if threaded == false boost::mutex st_mutex; /// @todo Could get rid of st_mutex by updating [thread_index|in_thread] atomically uint32_t thread_index; uint32_t in_thread; }; typedef boost::shared_ptr QueueInfoPtr; typedef boost::unordered_map M_Queue; M_Queue queues_; boost::mutex queues_mutex_; /// @todo SRMW lockfree queue. waiting_mutex_ has the potential for a lot of contention typedef std::vector V_Queue; V_Queue waiting_; boost::mutex waiting_mutex_; boost::condition_variable waiting_cond_; boost::thread_group tg_; struct ThreadInfo { ThreadInfo() : calling(0) {} /// @todo SRSW lockfree queue boost::mutex queue_mutex; boost::condition_variable queue_cond; std::vector > queue; boost::detail::atomic_count calling; #ifdef NODELET_QUEUE_DEBUG struct Record { Record(double stamp, uint32_t tasks, bool threaded) : stamp(stamp), tasks(tasks), threaded(threaded) {} double stamp; uint32_t tasks; bool threaded; }; std::vector history; #endif // Pad sizeof(ThreadInfo) to be a multiple of 64 (cache line size) to avoid false sharing. // This still doesn't guarantee ThreadInfo is actually allocated on a cache line boundary though. static const int ACTUAL_SIZE = sizeof(boost::mutex) + sizeof(boost::condition_variable) + sizeof(std::vector >) + sizeof(boost::detail::atomic_count); uint8_t pad[((ACTUAL_SIZE + 63) & ~63) - ACTUAL_SIZE]; }; /// @todo Use cache-aligned allocator for thread_info_ typedef boost::scoped_array V_ThreadInfo; V_ThreadInfo thread_info_; bool running_; uint32_t num_worker_threads_; }; } // namespace detail } // namespace nodelet #endif // NODELET_CALLBACK_QUEUE_MANAGER_H ros-nodelet-core-1.9.16/nodelet/include/nodelet/exception.h000066400000000000000000000036241336731060300236560ustar00rootroot00000000000000/* * 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 NODELET_EXCEPTION_H #define NODELET_EXCEPTION_H #include namespace nodelet { /** * \brief Base class for all exceptions thrown by nodelet */ class Exception : public std::runtime_error { public: Exception(const std::string& what) : std::runtime_error(what) {} }; } // namespace nodelet #endif // NODELET_EXCEPTION_H ros-nodelet-core-1.9.16/nodelet/include/nodelet/loader.h000066400000000000000000000065071336731060300231310ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ /** @mainpage \author Tully Foote **/ #ifndef NODELET_LOADER_H #define NODELET_LOADER_H #include #include #include #include #include #include namespace ros { class NodeHandle; } namespace nodelet { class Nodelet; typedef std::map M_string; 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 { public: /** \brief Construct the nodelet loader with optional ros API at default location of NodeHandle("~")*/ Loader(bool provide_ros_api = true); /** \brief Construct the nodelet loader with optional ros API in namespace of passed NodeHandle */ Loader(const ros::NodeHandle& server_nh); /** * \brief Construct the nodelet loader without ros API, using non-standard factory function to * create nodelet instances */ Loader(const boost::function (const std::string& lookup_name)>& create_instance); ~Loader(); /** \brief Load a nodelet */ bool load(const std::string& name, const std::string& type, const M_string& remappings, const V_string& my_argv); /** \brief Unload a nodelet */ bool unload(const std::string& name); /** \brief Clear all nodelets from this loader */ bool clear(); /**\brief List the names of all loaded nodelets */ std::vector listLoadedNodelets(); private: boost::mutex lock_; /// impl_; }; } // namespace nodelet #endif //#ifndef NODELET_LOADER_H ros-nodelet-core-1.9.16/nodelet/include/nodelet/nodelet.h000066400000000000000000000346051336731060300233150ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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 NODELET_NODELET_H #define NODELET_NODELET_H #include "exception.h" #include #include #include #include #include namespace ros { class NodeHandle; class CallbackQueueInterface; } #define NODELET_DEBUG(...) ROS_DEBUG_NAMED(getName(), __VA_ARGS__) #define NODELET_DEBUG_STREAM(...) ROS_DEBUG_STREAM_NAMED(getName(), __VA_ARGS__) #define NODELET_DEBUG_ONCE(...) ROS_DEBUG_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_DEBUG_STREAM_ONCE(...) ROS_DEBUG_STREAM_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_DEBUG_COND(cond, ...) ROS_DEBUG_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_DEBUG_STREAM_COND(cond, ...) ROS_DEBUG_STREAM_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_DEBUG_THROTTLE(rate, ...) ROS_DEBUG_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_DEBUG_STREAM_THROTTLE(rate, ...) ROS_DEBUG_STREAM_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_DEBUG_FILTER(filter, ...) ROS_DEBUG_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_DEBUG_STREAM_FILTER(filter, ...) ROS_DEBUG_STREAM_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_INFO(...) ROS_INFO_NAMED(getName(), __VA_ARGS__) #define NODELET_INFO_STREAM(...) ROS_INFO_STREAM_NAMED(getName(), __VA_ARGS__) #define NODELET_INFO_ONCE(...) ROS_INFO_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_INFO_STREAM_ONCE(...) ROS_INFO_STREAM_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_INFO_COND(cond, ...) ROS_INFO_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_INFO_STREAM_COND(cond, ...) ROS_INFO_STREAM_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_INFO_THROTTLE(rate, ...) ROS_INFO_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_INFO_STREAM_THROTTLE(rate, ...) ROS_INFO_STREAM_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_INFO_FILTER(filter, ...) ROS_INFO_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_INFO_STREAM_FILTER(filter, ...) ROS_INFO_STREAM_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_WARN(...) ROS_WARN_NAMED(getName(), __VA_ARGS__) #define NODELET_WARN_STREAM(...) ROS_WARN_STREAM_NAMED(getName(), __VA_ARGS__) #define NODELET_WARN_ONCE(...) ROS_WARN_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_WARN_STREAM_ONCE(...) ROS_WARN_STREAM_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_WARN_COND(cond, ...) ROS_WARN_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_WARN_STREAM_COND(cond, ...) ROS_WARN_STREAM_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_WARN_THROTTLE(rate, ...) ROS_WARN_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_WARN_STREAM_THROTTLE(rate, ...) ROS_WARN_STREAM_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_WARN_FILTER(filter, ...) ROS_WARN_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_WARN_STREAM_FILTER(filter, ...) ROS_WARN_STREAM_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_ERROR(...) ROS_ERROR_NAMED(getName(), __VA_ARGS__) #define NODELET_ERROR_STREAM(...) ROS_ERROR_STREAM_NAMED(getName(), __VA_ARGS__) #define NODELET_ERROR_ONCE(...) ROS_ERROR_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_ERROR_STREAM_ONCE(...) ROS_ERROR_STREAM_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_ERROR_COND(cond, ...) ROS_ERROR_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_ERROR_STREAM_COND(cond, ...) ROS_ERROR_STREAM_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_ERROR_THROTTLE(rate, ...) ROS_ERROR_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_ERROR_STREAM_THROTTLE(rate, ...) ROS_ERROR_STREAM_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_ERROR_FILTER(filter, ...) ROS_ERROR_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_ERROR_STREAM_FILTER(filter, ...) ROS_ERROR_STREAM_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_FATAL(...) ROS_FATAL_NAMED(getName(), __VA_ARGS__) #define NODELET_FATAL_STREAM(...) ROS_FATAL_STREAM_NAMED(getName(), __VA_ARGS__) #define NODELET_FATAL_ONCE(...) ROS_FATAL_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_FATAL_STREAM_ONCE(...) ROS_FATAL_STREAM_ONCE_NAMED(getName(), __VA_ARGS__) #define NODELET_FATAL_COND(cond, ...) ROS_FATAL_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_FATAL_STREAM_COND(cond, ...) ROS_FATAL_STREAM_COND_NAMED(cond, getName(), __VA_ARGS__) #define NODELET_FATAL_THROTTLE(rate, ...) ROS_FATAL_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_FATAL_STREAM_THROTTLE(rate, ...) ROS_FATAL_STREAM_THROTTLE_NAMED(rate, getName(), __VA_ARGS__) #define NODELET_FATAL_FILTER(filter, ...) ROS_FATAL_FILTER_NAMED(filter, getName(), __VA_ARGS__) #define NODELET_FATAL_STREAM_FILTER(filter, ...) ROS_FATAL_STREAM_FILTER_NAMED(filter, getName(), __VA_ARGS__) // named versions of the macros #define NODELET_DEBUG_NAMED(suffix, ...) ROS_DEBUG_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_STREAM_NAMED(suffix, ...) ROS_DEBUG_STREAM_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_ONCE_NAMED(suffix, ...) ROS_DEBUG_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_STREAM_ONCE_NAMED(suffix, ...) ROS_DEBUG_STREAM_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_COND_NAMED(cond, suffix, ...) ROS_DEBUG_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_STREAM_COND_NAMED(cond, suffix, ...) ROS_DEBUG_STREAM_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_THROTTLE_NAMED(rate, suffix, ...) ROS_DEBUG_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_STREAM_THROTTLE_NAMED(rate, suffix, ...) ROS_DEBUG_STREAM_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_FILTER_NAMED(filter, suffix, ...) ROS_DEBUG_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_DEBUG_STREAM_FILTER_NAMED(filter, suffix, ...) ROS_DEBUG_STREAM_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_NAMED(suffix, ...) ROS_INFO_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_STREAM_NAMED(suffix, ...) ROS_INFO_STREAM_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_ONCE_NAMED(suffix, ...) ROS_INFO_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_STREAM_ONCE_NAMED(suffix, ...) ROS_INFO_STREAM_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_COND_NAMED(cond, suffix, ...) ROS_INFO_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_STREAM_COND_NAMED(cond, suffix, ...) ROS_INFO_STREAM_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_THROTTLE_NAMED(rate, suffix, ...) ROS_INFO_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_STREAM_THROTTLE_NAMED(rate, suffix, ...) ROS_INFO_STREAM_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_FILTER_NAMED(filter, suffix, ...) ROS_INFO_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_INFO_STREAM_FILTER_NAMED(filter, suffix, ...) ROS_INFO_STREAM_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_NAMED(suffix, ...) ROS_WARN_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_STREAM_NAMED(suffix, ...) ROS_WARN_STREAM_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_ONCE_NAMED(suffix, ...) ROS_WARN_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_STREAM_ONCE_NAMED(suffix, ...) ROS_WARN_STREAM_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_COND_NAMED(cond, suffix, ...) ROS_WARN_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_STREAM_COND_NAMED(cond, suffix, ...) ROS_WARN_STREAM_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_THROTTLE_NAMED(rate, suffix, ...) ROS_WARN_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_STREAM_THROTTLE_NAMED(rate, suffix, ...) ROS_WARN_STREAM_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_FILTER_NAMED(filter, suffix, ...) ROS_WARN_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_WARN_STREAM_FILTER_NAMED(filter, suffix, ...) ROS_WARN_STREAM_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_NAMED(suffix, ...) ROS_ERROR_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_STREAM_NAMED(suffix, ...) ROS_ERROR_STREAM_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_ONCE_NAMED(suffix, ...) ROS_ERROR_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_STREAM_ONCE_NAMED(suffix, ...) ROS_ERROR_STREAM_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_COND_NAMED(cond, suffix, ...) ROS_ERROR_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_STREAM_COND_NAMED(cond, suffix, ...) ROS_ERROR_STREAM_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_THROTTLE_NAMED(rate, suffix, ...) ROS_ERROR_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_STREAM_THROTTLE_NAMED(rate, suffix, ...) ROS_ERROR_STREAM_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_FILTER_NAMED(filter, suffix, ...) ROS_ERROR_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_ERROR_STREAM_FILTER_NAMED(filter, suffix, ...) ROS_ERROR_STREAM_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_NAMED(suffix, ...) ROS_FATAL_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_STREAM_NAMED(suffix, ...) ROS_FATAL_STREAM_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_ONCE_NAMED(suffix, ...) ROS_FATAL_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_STREAM_ONCE_NAMED(suffix, ...) ROS_FATAL_STREAM_ONCE_NAMED(getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_COND_NAMED(cond, suffix, ...) ROS_FATAL_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_STREAM_COND_NAMED(cond, suffix, ...) ROS_FATAL_STREAM_COND_NAMED(cond, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_THROTTLE_NAMED(rate, suffix, ...) ROS_FATAL_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_STREAM_THROTTLE_NAMED(rate, suffix, ...) ROS_FATAL_STREAM_THROTTLE_NAMED(rate, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_FILTER_NAMED(filter, suffix, ...) ROS_FATAL_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) #define NODELET_FATAL_STREAM_FILTER_NAMED(filter, suffix, ...) ROS_FATAL_STREAM_FILTER_NAMED(filter, getSuffixedName(suffix), __VA_ARGS__) namespace nodelet { typedef boost::shared_ptr NodeHandlePtr; typedef std::map M_string; typedef std::vector V_string; class UninitializedException : public Exception { public: UninitializedException(const std::string& method_name) : Exception("Calling [" + method_name + "] before the Nodelet is initialized is not allowed.") {} }; class MultipleInitializationException : public Exception { public: MultipleInitializationException() : Exception("Initialized multiple times") {} }; class Nodelet { // Protected data fields for use by the subclass. protected: inline const std::string& getName() const { return nodelet_name_; } inline std::string getSuffixedName(const std::string& suffix) const { return nodelet_name_ + "." + suffix; } inline const V_string& getMyArgv() const { return my_argv_; } inline const M_string& getRemappingArgs() const { return remapping_args_; } ros::NodeHandle& getNodeHandle() const; ros::NodeHandle& getPrivateNodeHandle() const; ros::NodeHandle& getMTNodeHandle() const; ros::NodeHandle& getMTPrivateNodeHandle() const; ros::CallbackQueueInterface& getSTCallbackQueue() const; ros::CallbackQueueInterface& getMTCallbackQueue() const; // Internal storage; private: bool inited_; std::string nodelet_name_; NodeHandlePtr nh_; NodeHandlePtr private_nh_; NodeHandlePtr mt_nh_; NodeHandlePtr mt_private_nh_; V_string my_argv_; M_string remapping_args_; // Method to be overridden by subclass when starting up. virtual void onInit() = 0; // Public API used for launching public: /**\brief Empty constructor required for dynamic loading */ Nodelet(); /**\brief Init function called at startup * \param name The name of the nodelet * \param remapping_args The remapping args in a map for the nodelet * \param my_argv The commandline arguments for this nodelet stripped of special arguments such as ROS arguments */ void init(const std::string& name, const M_string& remapping_args, const V_string& my_argv, ros::CallbackQueueInterface* st_queue = NULL, ros::CallbackQueueInterface* mt_queue = NULL); virtual ~Nodelet(); }; } #endif //NODELET_NODELET_H ros-nodelet-core-1.9.16/nodelet/mainpage.dox000066400000000000000000000015661336731060300207320ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b injectable_ros is ... \section codeapi Code API */ros-nodelet-core-1.9.16/nodelet/package.xml000066400000000000000000000025661336731060300205530ustar00rootroot00000000000000 nodelet 1.9.16 The nodelet package is designed to provide a way to run multiple algorithms in the same process with zero copy transport between algorithms. This package provides both the nodelet base class needed for implementing a nodelet, as well as the NodeletLoader class used for instantiating nodelets. Mikael Arguedas BSD http://ros.org/wiki/nodelet https://github.com/ros/nodelet_core/issues https://github.com/ros/nodelet_core Tully Foote Radu Bogdan Rusu catkin cmake_modules message_generation bondcpp boost pluginlib rosconsole roscpp std_msgs uuid message_runtime rospy ros-nodelet-core-1.9.16/nodelet/scripts/000077500000000000000000000000001336731060300201145ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/scripts/declared_nodelets000077500000000000000000000073371336731060300235140ustar00rootroot00000000000000#!/usr/bin/env python # Software License Agreement (BSD License) # # Copyright (c) 2008, Willow Garage, Inc. # All rights reserved. # # 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 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. from __future__ import print_function import argparse import os import sys import xml from xml.dom import minidom import rospkg def main(): parser = argparse.ArgumentParser() parser.add_argument('-v', '--verbose', action='store_true') parser.add_argument('-p', '--package') args = parser.parse_args() rp = rospkg.RosPack() nodelet_files = [] for p in rp.get_depends_on('nodelet', implicit=False): manifest = rp.get_manifest(p) for e in manifest.exports: try: if e.__dict__['tag'] == 'nodelet': plugin_file = e.get('plugin') if plugin_file: plugin_file = plugin_file.replace('${prefix}', rp.get_path(p)) nodelet_files.append((p, plugin_file)) except Exception as e: print(e, file=sys.stderr) declared_nodelets = [] for p, f in nodelet_files: nodelets = [] if not os.path.isfile(f): print('%s: %s' % (f, 'The file does not exist.'), file=sys.stderr) continue with open(f) as fh: try: dom = minidom.parse(fh) for lib in dom.getElementsByTagName('library'): for name in lib.getElementsByTagName('class'): nodelets.append(name.getAttribute('name')) except xml.parsers.expat.ExpatError as e: print('%s: %s' % (f, e), file=sys.stderr) continue declared_nodelets.append({ 'package': p, 'manifest': f, 'nodelets': nodelets, }) for declared in declared_nodelets: if args.package and declared['package'] != args.package: continue if args.verbose: print('- package: %s' % declared['package']) print(' manifest: %s' % declared['manifest']) print(' nodelets:') for nodelet in declared['nodelets']: print(' - %s' % nodelet) else: for nodelet in declared['nodelets']: print(nodelet) if __name__ == '__main__': main() ros-nodelet-core-1.9.16/nodelet/scripts/list_nodelets000077500000000000000000000024021336731060300227100ustar00rootroot00000000000000#! /usr/bin/env python # Provides quick access to the services exposed by MechanismControlNode from __future__ import print_function import roslib roslib.load_manifest('nodelet') from optparse import OptionParser import rospy from nodelet.srv import NodeletList class NodeletInterface(): def list_nodelets(self, manager): service_manager = manager + "/list" rospy.loginfo('Waiting for service: %s', service_manager) rospy.wait_for_service(service_manager) service_client = rospy.ServiceProxy(service_manager, NodeletList) resp = service_client() print(resp) def usage(): return '''list_nodelets - List active nodelets on the manager''' if __name__ == '__main__': parser = OptionParser(usage=usage()) rospy.init_node("nodelet", anonymous=True) options, args = parser.parse_args(rospy.myargv()) if len(args) != 2: parser.error("Command 'list_nodelets' requires 2 arguments not %d" % len(args)) manager = args[1] service_manager = manager + "/list" rospy.loginfo('Waiting for service: %s', service_manager) rospy.wait_for_service(service_manager) service_client = rospy.ServiceProxy(service_manager, NodeletList) resp = service_client() print(resp) ros-nodelet-core-1.9.16/nodelet/src/000077500000000000000000000000001336731060300172145ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/src/callback_queue.cpp000066400000000000000000000052021336731060300226570ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include namespace nodelet { namespace detail { CallbackQueue::CallbackQueue(CallbackQueueManager* parent, const ros::VoidConstPtr& tracked_object) : parent_(parent) , tracked_object_(tracked_object) , has_tracked_object_(tracked_object) { } CallbackQueue::~CallbackQueue() { } void CallbackQueue::addCallback(const ros::CallbackInterfacePtr& cb, uint64_t owner_id) { if (queue_.isEnabled()) { queue_.addCallback(cb, owner_id); parent_->callbackAdded(shared_from_this()); } } void CallbackQueue::removeByID(uint64_t owner_id) { queue_.removeByID(owner_id); } uint32_t CallbackQueue::callOne() { // Don't try to call the callback after its nodelet has been destroyed! ros::VoidConstPtr tracker; if (has_tracked_object_) { tracker = tracked_object_.lock(); if (!tracker) return ros::CallbackQueue::Disabled; } return queue_.callOne(); } } // namespace detail } // namespace nodelet ros-nodelet-core-1.9.16/nodelet/src/callback_queue_manager.cpp000066400000000000000000000174701336731060300243630ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include #include #include #include namespace nodelet { namespace detail { CallbackQueueManager::CallbackQueueManager(uint32_t num_worker_threads) : running_(true), num_worker_threads_(num_worker_threads) { if (num_worker_threads_ == 0) num_worker_threads_ = boost::thread::hardware_concurrency(); tg_.create_thread(boost::bind(&CallbackQueueManager::managerThread, this)); size_t num_threads = getNumWorkerThreads(); thread_info_.reset( new ThreadInfo[num_threads] ); for (size_t i = 0; i < num_threads; ++i) { tg_.create_thread(boost::bind(&CallbackQueueManager::workerThread, this, &thread_info_[i])); } } CallbackQueueManager::~CallbackQueueManager() { stop(); #ifdef NODELET_QUEUE_DEBUG // Write out task assignment histories for each thread typedef ThreadInfo::Record Record; for (size_t i = 0; i < num_threads; ++i) { char filename[128]; sprintf(filename, "thread_history_%d.txt", (int)i); FILE* file = fopen(filename, "w"); fprintf(file, "# timestamps tasks threaded\n"); const std::vector& history = thread_info_[i].history; for (int j = 0; j < (int)history.size(); ++j) { Record r = history[j]; fprintf(file, "%.6f %u %d\n", r.stamp, r.tasks, (int)r.threaded); } fclose(file); } #endif } void CallbackQueueManager::stop() { running_ = false; { boost::mutex::scoped_lock lock(waiting_mutex_); waiting_cond_.notify_all(); } size_t num_threads = getNumWorkerThreads(); for (size_t i = 0; i < num_threads; ++i) { boost::mutex::scoped_lock lock(thread_info_[i].queue_mutex); thread_info_[i].queue_cond.notify_all(); } tg_.join_all(); } uint32_t CallbackQueueManager::getNumWorkerThreads() { return num_worker_threads_; } void CallbackQueueManager::addQueue(const CallbackQueuePtr& queue, bool threaded) { boost::mutex::scoped_lock lock(queues_mutex_); QueueInfoPtr& info = queues_[queue.get()]; ROS_ASSERT(!info); info.reset(new QueueInfo); info->queue = queue; info->threaded = threaded; } void CallbackQueueManager::removeQueue(const CallbackQueuePtr& queue) { boost::mutex::scoped_lock lock(queues_mutex_); ROS_ASSERT(queues_.find(queue.get()) != queues_.end()); queues_.erase(queue.get()); } void CallbackQueueManager::callbackAdded(const CallbackQueuePtr& queue) { { boost::mutex::scoped_lock lock(waiting_mutex_); waiting_.push_back(queue); } waiting_cond_.notify_all(); } CallbackQueueManager::ThreadInfo* CallbackQueueManager::getSmallestQueue() { size_t smallest = std::numeric_limits::max(); uint32_t smallest_index = 0xffffffff; for (unsigned i = 0; i < num_worker_threads_; ++i) { ThreadInfo& ti = thread_info_[i]; size_t size = ti.calling; if (size == 0) { return &ti; } if (size < smallest) { smallest = size; smallest_index = i; } } return &thread_info_[smallest_index]; } void CallbackQueueManager::managerThread() { V_Queue local_waiting; while (running_) { { boost::mutex::scoped_lock lock(waiting_mutex_); while (waiting_.empty() && running_) { waiting_cond_.wait(lock); } if (!running_) { return; } local_waiting.swap(waiting_); } { boost::mutex::scoped_lock lock(queues_mutex_); V_Queue::iterator it = local_waiting.begin(); V_Queue::iterator end = local_waiting.end(); for (; it != end; ++it) { CallbackQueuePtr& queue = *it; M_Queue::iterator it = queues_.find(queue.get()); if (it != queues_.end()) { QueueInfoPtr& info = it->second; ThreadInfo* ti = 0; if (info->threaded) { // If this queue is thread-safe we immediately add it to the thread with the least work queued ti = getSmallestQueue(); } else { // If this queue is non-thread-safe and has no in-progress calls happening, we add it to the // thread with the least work queued. If the queue already has calls in-progress we add it // to the thread it's already being called from boost::mutex::scoped_lock lock(info->st_mutex); if (info->in_thread == 0) { ti = getSmallestQueue(); info->thread_index = ti - thread_info_.get(); } else { ti = &thread_info_[info->thread_index]; } ++info->in_thread; } { boost::mutex::scoped_lock lock(ti->queue_mutex); ti->queue.push_back(std::make_pair(queue, info)); ++ti->calling; #ifdef NODELET_QUEUE_DEBUG double stamp = ros::WallTime::now().toSec(); uint32_t tasks = ti->calling; ti->history.push_back(ThreadInfo::Record(stamp, tasks, true)); #endif } ti->queue_cond.notify_all(); } } } local_waiting.clear(); } } void CallbackQueueManager::workerThread(ThreadInfo* info) { std::vector > local_queues; while (running_) { { boost::mutex::scoped_lock lock(info->queue_mutex); while (info->queue.empty() && running_) { info->queue_cond.wait(lock); } if (!running_) { return; } info->queue.swap(local_queues); } std::vector >::iterator it = local_queues.begin(); std::vector >::iterator end = local_queues.end(); for (; it != end; ++it) { CallbackQueuePtr& queue = it->first; QueueInfoPtr& qi = it->second; if (queue->callOne() == ros::CallbackQueue::TryAgain) { callbackAdded(queue); } --info->calling; if (!qi->threaded) { boost::mutex::scoped_lock lock(qi->st_mutex); --qi->in_thread; } } local_queues.clear(); } } } // namespace detail } // namespace nodelet ros-nodelet-core-1.9.16/nodelet/src/loader.cpp000066400000000000000000000300571336731060300211730ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include #include #include #include #include #include #include #include #include /* Between Loader, Nodelet, CallbackQueue and CallbackQueueManager, who owns what? Loader contains the CallbackQueueManager. Loader and CallbackQueueManager share ownership of the CallbackQueues. Loader is primary owner of the Nodelets, but each CallbackQueue has weak ownership of its associated Nodelet. Loader ensures that the CallbackQueues associated with a Nodelet outlive that Nodelet. CallbackQueueManager ensures that CallbackQueues continue to survive as long as they have pending callbacks. CallbackQueue holds a weak_ptr to its associated Nodelet, which it attempts to lock before invoking any callback. So any lingering callbacks processed after a Nodelet is destroyed are safely discarded, and then the CallbackQueue expires. When Loader unloads a Nodelet, it calls CallbackQueueManager::removeQueue() for the associated CallbackQueues, which prevents them from adding any more callbacks to CallbackQueueManager. Otherwise a Nodelet that is continuously executing callbacks might persist in a "zombie" state after being unloaded. */ namespace nodelet { typedef boost::shared_ptr NodeletPtr; /// @todo Consider moving this to nodelet executable, it's implemented entirely on top of Loader class LoaderROS { public: LoaderROS(Loader* parent, const ros::NodeHandle& nh) : parent_(parent) , nh_(nh) , bond_spinner_(1, &bond_callback_queue_) { load_server_ = nh_.advertiseService("load_nodelet", &LoaderROS::serviceLoad, this); unload_server_ = nh_.advertiseService("unload_nodelet", &LoaderROS::serviceUnload, this); list_server_ = nh_.advertiseService("list", &LoaderROS::serviceList, this); bond_spinner_.start(); } private: bool serviceLoad(nodelet::NodeletLoad::Request &req, nodelet::NodeletLoad::Response &res) { boost::mutex::scoped_lock lock(lock_); // build map M_string remappings; if (req.remap_source_args.size() != req.remap_target_args.size()) { ROS_ERROR("Bad remapppings provided, target and source of different length"); } else { for (size_t i = 0; i < req.remap_source_args.size(); ++i) { remappings[ros::names::resolve(req.remap_source_args[i])] = ros::names::resolve(req.remap_target_args[i]); ROS_DEBUG("%s:%s\n", ros::names::resolve(req.remap_source_args[i]).c_str(), remappings[ros::names::resolve(req.remap_source_args[i])].c_str()); } } res.success = parent_->load(req.name, req.type, remappings, req.my_argv); // If requested, create bond to sister process if (res.success && !req.bond_id.empty()) { bond::Bond* bond = new bond::Bond(nh_.getNamespace() + "/bond", req.bond_id); bond_map_.insert(req.name, bond); bond->setCallbackQueue(&bond_callback_queue_); bond->setBrokenCallback(boost::bind(&LoaderROS::unload, this, req.name)); bond->start(); } return res.success; } bool serviceUnload(nodelet::NodeletUnload::Request &req, nodelet::NodeletUnload::Response &res) { res.success = unload(req.name); return res.success; } bool unload(const std::string& name) { boost::mutex::scoped_lock lock(lock_); bool success = parent_->unload(name); if (!success) { ROS_ERROR("Failed to find nodelet with name '%s' to unload.", name.c_str()); return success; } // break the bond, if there is one M_stringToBond::iterator it = bond_map_.find(name); if (it != bond_map_.end()) { // disable callback for broken bond, as we are breaking it intentially now it->second->setBrokenCallback(boost::function()); // erase (and break) bond bond_map_.erase(name); } return success; } bool serviceList(nodelet::NodeletList::Request &, nodelet::NodeletList::Response &res) { res.nodelets = parent_->listLoadedNodelets(); return true; } Loader* parent_; ros::NodeHandle nh_; ros::ServiceServer load_server_; ros::ServiceServer unload_server_; ros::ServiceServer list_server_; boost::mutex lock_; ros::CallbackQueue bond_callback_queue_; ros::AsyncSpinner bond_spinner_; typedef boost::ptr_map M_stringToBond; M_stringToBond bond_map_; }; // Owns a Nodelet and its callback queues struct ManagedNodelet : boost::noncopyable { detail::CallbackQueuePtr st_queue; detail::CallbackQueuePtr mt_queue; NodeletPtr nodelet; // destroyed before the queues detail::CallbackQueueManager* callback_manager; /// @todo Maybe addQueue/removeQueue should be done by CallbackQueue ManagedNodelet(const NodeletPtr& nodelet, detail::CallbackQueueManager* cqm) : st_queue(new detail::CallbackQueue(cqm, nodelet)) , mt_queue(new detail::CallbackQueue(cqm, nodelet)) , nodelet(nodelet) , callback_manager(cqm) { // NOTE: Can't do this in CallbackQueue constructor because the shared_ptr to // it doesn't exist then. callback_manager->addQueue(st_queue, false); callback_manager->addQueue(mt_queue, true); } ~ManagedNodelet() { callback_manager->removeQueue(st_queue); callback_manager->removeQueue(mt_queue); } }; struct Loader::Impl { boost::shared_ptr services_; boost::function (const std::string& lookup_name)> create_instance_; boost::function refresh_classes_; boost::shared_ptr callback_manager_; // Must outlive nodelets_ typedef boost::ptr_map M_stringToNodelet; M_stringToNodelet nodelets_; /// Loader; boost::shared_ptr loader(new Loader("nodelet", "nodelet::Nodelet")); // create_instance_ is self-contained; it owns a copy of the loader shared_ptr create_instance_ = boost::bind(&Loader::createInstance, loader, _1); refresh_classes_ = boost::bind(&Loader::refreshDeclaredClasses, loader); } Impl(const boost::function (const std::string& lookup_name)>& create_instance) : create_instance_(create_instance) { } void advertiseRosApi(Loader* parent, const ros::NodeHandle& server_nh) { int num_threads_param; server_nh.param("num_worker_threads", num_threads_param, 0); callback_manager_.reset(new detail::CallbackQueueManager(num_threads_param)); ROS_INFO("Initializing nodelet with %d worker threads.", (int)callback_manager_->getNumWorkerThreads()); services_.reset(new LoaderROS(parent, server_nh)); } }; /// @todo Instance of ROS API-related constructors, just take #threads for the manager Loader::Loader(bool provide_ros_api) : impl_(new Impl) { if (provide_ros_api) impl_->advertiseRosApi(this, ros::NodeHandle("~")); else impl_->callback_manager_.reset(new detail::CallbackQueueManager); } Loader::Loader(const ros::NodeHandle& server_nh) : impl_(new Impl) { impl_->advertiseRosApi(this, server_nh); } Loader::Loader(const boost::function (const std::string& lookup_name)>& create_instance) : impl_(new Impl(create_instance)) { impl_->callback_manager_.reset(new detail::CallbackQueueManager); } Loader::~Loader() { } bool Loader::load(const std::string &name, const std::string& type, const ros::M_string& remappings, const std::vector & my_argv) { boost::mutex::scoped_lock lock(lock_); if (impl_->nodelets_.count(name) > 0) { ROS_ERROR("Cannot load nodelet %s for one exists with that name already", name.c_str()); return false; } NodeletPtr p; try { p = impl_->create_instance_(type); } catch (std::runtime_error& e) { // If we cannot refresh the nodelet cache, fail immediately if(!impl_->refresh_classes_) { ROS_ERROR("Failed to load nodelet [%s] of type [%s]: %s", name.c_str(), type.c_str(), e.what()); return false; } // otherwise, refresh the cache and try again. try { impl_->refresh_classes_(); p = impl_->create_instance_(type); } catch (std::runtime_error& e2) { // dlopen() can return inconsistent results currently (see // https://sourceware.org/bugzilla/show_bug.cgi?id=17833), so make sure // that we display the messages of both exceptions to the user. ROS_ERROR("Failed to load nodelet [%s] of type [%s] even after refreshing the cache: %s", name.c_str(), type.c_str(), e2.what()); ROS_ERROR("The error before refreshing the cache was: %s", e.what()); return false; } } if (!p) { return false; } ROS_DEBUG("Done loading nodelet %s", name.c_str()); ManagedNodelet* mn = new ManagedNodelet(p, impl_->callback_manager_.get()); impl_->nodelets_.insert(const_cast(name), mn); // mn now owned by boost::ptr_map try { p->init(name, remappings, my_argv, mn->st_queue.get(), mn->mt_queue.get()); /// @todo Can we delay processing the queues until Nodelet::onInit() returns? ROS_DEBUG("Done initing nodelet %s", name.c_str()); } catch(...) { Impl::M_stringToNodelet::iterator it = impl_->nodelets_.find(name); if (it != impl_->nodelets_.end()) { impl_->nodelets_.erase(it); ROS_DEBUG ("Failed to initialize nodelet %s", name.c_str ()); return (false); } } return true; } bool Loader::unload (const std::string & name) { boost::mutex::scoped_lock lock (lock_); Impl::M_stringToNodelet::iterator it = impl_->nodelets_.find(name); if (it != impl_->nodelets_.end()) { impl_->nodelets_.erase(it); ROS_DEBUG ("Done unloading nodelet %s", name.c_str ()); return (true); } return (false); } bool Loader::clear () { boost::mutex::scoped_lock lock(lock_); impl_->nodelets_.clear(); return true; }; std::vector Loader::listLoadedNodelets() { boost::mutex::scoped_lock lock (lock_); std::vector output; Impl::M_stringToNodelet::iterator it = impl_->nodelets_.begin(); for (; it != impl_->nodelets_.end(); ++it) { output.push_back(it->first); } return output; } } // namespace nodelet ros-nodelet-core-1.9.16/nodelet/src/nodelet.cpp000066400000000000000000000266621336731060300213660ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 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. * * $Id$ * */ /** @mainpage \author Radu Bogdan Rusu @b nodeletcpp is a tool for loading/unloading nodelets to/from a Nodelet manager. **/ #include #include #include #include #include #include "nodelet/loader.h" #include "nodelet/NodeletList.h" #include "nodelet/NodeletLoad.h" #include "nodelet/NodeletUnload.h" std::string genId() { uuid_t uuid; uuid_generate_random(uuid); char uuid_str[40]; uuid_unparse(uuid, uuid_str); return std::string(uuid_str); } class NodeletArgumentParsing { private: std::string command_; std::string type_; std::string name_; std::string default_name_; std::string manager_; std::vector local_args_; bool is_bond_enabled_; public: //NodeletArgumentParsing() { }; bool parseArgs(int argc, char** argv) { is_bond_enabled_ = true; std::vector non_ros_args; ros::removeROSArgs (argc, argv, non_ros_args); size_t used_args = 0; if (non_ros_args.size() > 1) command_ = non_ros_args[1]; else return false; if (command_ == "load" && non_ros_args.size() > 3) { type_ = non_ros_args[2]; manager_ = non_ros_args[3]; used_args = 4; if (non_ros_args.size() > used_args) { if (non_ros_args[used_args] == "--no-bond") { is_bond_enabled_ = false; ++used_args; } } } else if (command_ == "unload" && non_ros_args.size() > 3) { type_ = "nodelet_unloader"; name_ = non_ros_args[2]; manager_ = non_ros_args[3]; used_args = 4; } else if (command_ == "standalone" && non_ros_args.size() > 2) { type_ = non_ros_args[2]; printf("type is %s\n", type_.c_str()); used_args = 3; } if (command_ == "manager") used_args = 2; for (size_t i = used_args; i < non_ros_args.size(); i++) local_args_.push_back(non_ros_args[i]); if (used_args > 0) return true; else return false; }; std::string getCommand () const { return (command_); } std::string getType () const { return (type_); } std::string getName () const { return (name_); } std::string getManager() const { return (manager_); } bool isBondEnabled() const { return is_bond_enabled_; } std::vector getMyArgv () const {return local_args_;}; std::string getDefaultName() { std::string s = type_; replace(s.begin(), s.end(), '/', '_'); return s; }; }; class NodeletInterface { public: //////////////////////////////////////////////////////////////////////////////// /** \brief Unload the nodelet */ bool unloadNodelet (const std::string &name, const std::string &manager) { ROS_INFO_STREAM ("Unloading nodelet " << name << " from manager " << manager); std::string service_name = manager + "/unload_nodelet"; // Check if the service exists and is available if (!ros::service::exists (service_name, true)) { // Probably the manager has shut down already, which is fine ROS_WARN("Couldn't find service %s, perhaps the manager is already shut down", service_name.c_str()); return (false); } ros::ServiceClient client = n_.serviceClient (service_name); //client.waitForExistence (); // Call the service nodelet::NodeletUnload srv; srv.request.name = name; if (!client.call (srv)) { // Maybe service shut down in the meantime, which isn't an error if (ros::service::exists(service_name, false)) ROS_FATAL_STREAM("Failed to unload nodelet '" << name << "` from manager `" << manager << "'"); return (false); } return (true); } //////////////////////////////////////////////////////////////////////////////// /** \brief Load the nodelet */ bool loadNodelet (const std::string &name, const std::string &type, const std::string &manager, const std::vector &args, const std::string &bond_id) { ros::M_string remappings = ros::names::getRemappings (); std::vector sources (remappings.size ()), targets (remappings.size ()); ROS_INFO_STREAM ("Loading nodelet " << name << " of type " << type << " to manager " << manager << " with the following remappings:"); int i = 0; for (ros::M_string::iterator it = remappings.begin (); it != remappings.end (); ++it, ++i) { sources[i] = (*it).first; targets[i] = (*it).second; ROS_INFO_STREAM (sources[i] << " -> " << targets[i]); } // Get and set the parameters XmlRpc::XmlRpcValue param; std::string node_name = ros::this_node::getName (); n_.getParam (node_name, param); n_.setParam (name, param); std::string service_name = std::string (manager) + "/load_nodelet"; // Wait until the service is advertised ROS_DEBUG ("Waiting for service %s to be available...", service_name.c_str ()); ros::ServiceClient client = n_.serviceClient (service_name); client.waitForExistence (); // Call the service nodelet::NodeletLoad srv; srv.request.name = std::string (name); srv.request.type = std::string (type); srv.request.remap_source_args = sources; srv.request.remap_target_args = targets; srv.request.my_argv = args; srv.request.bond_id = bond_id; if (!client.call (srv)) { ROS_FATAL_STREAM("Failed to load nodelet '" << name << "` of type `" << type << "` to manager `" << manager << "'"); return false; } return true; } private: ros::NodeHandle n_; }; void print_usage(int argc, char** argv) { printf("Your usage: \n"); for (int i = 0; i < argc; i++) printf("%s ", argv[i]); printf("\nnodelet usage:\n"); printf("nodelet load pkg/Type manager [--no-bond] - Launch a nodelet of type pkg/Type on manager manager\n"); printf("nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n"); printf("nodelet unload name manager - Unload a nodelet by name from manager\n"); printf("nodelet manager - Launch a nodelet manager node\n"); }; sig_atomic_t volatile request_shutdown = 0; void nodeletLoaderSigIntHandler(int) { request_shutdown = 1; } // Shutdown can be triggered externally by an XML-RPC call, this is how "rosnode kill" // works. When shutting down a "nodelet load" we always want to unload the nodelet // before shutting down our ROS comm channels, so we override the default roscpp // handler for a "shutdown" XML-RPC call. void shutdownCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result) { int num_params = 0; if (params.getType() == XmlRpc::XmlRpcValue::TypeArray) num_params = params.size(); if (num_params > 1) { std::string reason = params[1]; ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str()); request_shutdown = 1; } result = ros::xmlrpc::responseInt(1, "", 0); } /* ---[ */ int main (int argc, char** argv) { NodeletArgumentParsing arg_parser; if (!arg_parser.parseArgs(argc, argv)) { print_usage(argc, argv); return (-1); } std::string command = arg_parser.getCommand(); if (command == "manager") { ros::init (argc, argv, "manager"); nodelet::Loader n; ros::spin (); } else if (command == "standalone") { ros::init (argc, argv, arg_parser.getDefaultName()); ros::NodeHandle nh; nodelet::Loader n(false); ros::M_string remappings; //Remappings are already applied by ROS no need to generate them. std::string nodelet_name = ros::this_node::getName (); std::string nodelet_type = arg_parser.getType(); if(!n.load(nodelet_name, nodelet_type, remappings, arg_parser.getMyArgv())) return -1; ROS_DEBUG("Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str()); ros::spin(); } else if (command == "load") { ros::init (argc, argv, arg_parser.getDefaultName (), ros::init_options::NoSigintHandler); NodeletInterface ni; ros::NodeHandle nh; std::string name = ros::this_node::getName (); std::string type = arg_parser.getType(); std::string manager = arg_parser.getManager(); std::string bond_id; if (arg_parser.isBondEnabled()) bond_id = name + "_" + genId(); bond::Bond bond(manager + "/bond", bond_id); if (!ni.loadNodelet(name, type, manager, arg_parser.getMyArgv(), bond_id)) return -1; // Override default exit handlers for roscpp signal(SIGINT, nodeletLoaderSigIntHandler); ros::XMLRPCManager::instance()->unbind("shutdown"); ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback); if (arg_parser.isBondEnabled()) bond.start(); // Spin our own loop ros::AsyncSpinner spinner(1); spinner.start(); while (!request_shutdown) { if (arg_parser.isBondEnabled() && bond.isBroken()) { ROS_INFO("Bond broken, exiting"); goto shutdown; } usleep(100000); } // Attempt to unload the nodelet before shutting down ROS ni.unloadNodelet(name, manager); if (arg_parser.isBondEnabled()) bond.breakBond(); shutdown: ros::shutdown(); } else if (command == "unload") { ros::init (argc, argv, arg_parser.getDefaultName ()); std::string name = arg_parser.getName (); std::string manager = arg_parser.getManager(); NodeletInterface ni; if (!ni.unloadNodelet(name, manager)) return -1; } else { ros::init(argc, argv, "nodelet"); ROS_ERROR("Command %s unknown", command.c_str()); return -1; } return (0); } /* ]--- */ ros-nodelet-core-1.9.16/nodelet/src/nodelet_class.cpp000066400000000000000000000077341336731060300225520ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include namespace nodelet { Nodelet::Nodelet () : inited_(false) , nodelet_name_("uninitialized") { } Nodelet::~Nodelet() { } ros::CallbackQueueInterface& Nodelet::getSTCallbackQueue () const { if (!inited_) { throw UninitializedException("getSTCallbackQueue"); } return *nh_->getCallbackQueue(); } ros::CallbackQueueInterface& Nodelet::getMTCallbackQueue () const { if (!inited_) { throw UninitializedException("getMTCallbackQueue"); } return *mt_nh_->getCallbackQueue(); } ros::NodeHandle& Nodelet::getNodeHandle() const { if (!inited_) { throw UninitializedException("getNodeHandle"); } return *nh_; } ros::NodeHandle& Nodelet::getPrivateNodeHandle() const { if (!inited_) { throw UninitializedException("getPrivateNodeHandle"); } return *private_nh_; } ros::NodeHandle& Nodelet::getMTNodeHandle() const { if (!inited_) { throw UninitializedException("getMTNodeHandle"); } return *mt_nh_; } ros::NodeHandle& Nodelet::getMTPrivateNodeHandle() const { if (!inited_) { throw UninitializedException("getMTPrivateNodeHandle"); } return *mt_private_nh_; } void Nodelet::init(const std::string& name, const M_string& remapping_args, const V_string& my_argv, ros::CallbackQueueInterface* st_queue, ros::CallbackQueueInterface* mt_queue) { if (inited_) { throw MultipleInitializationException(); } nodelet_name_ = name; remapping_args_ = remapping_args; my_argv_ = my_argv; // Set up NodeHandles with correct namespaces private_nh_.reset(new ros::NodeHandle(name, remapping_args)); nh_.reset(new ros::NodeHandle(ros::names::parentNamespace(name), remapping_args)); mt_private_nh_.reset(new ros::NodeHandle(name, remapping_args)); mt_nh_.reset(new ros::NodeHandle(ros::names::parentNamespace(name), remapping_args)); // Use the provided callback queues (or the global queue if they're NULL). // This allows Loader and CallbackQueueManager to spread nodelets over multiple threads. private_nh_->setCallbackQueue(st_queue); nh_->setCallbackQueue(st_queue); mt_private_nh_->setCallbackQueue(mt_queue); mt_nh_->setCallbackQueue(mt_queue); NODELET_DEBUG ("Nodelet initializing"); inited_ = true; this->onInit (); } } // namespace nodelet ros-nodelet-core-1.9.16/nodelet/srv/000077500000000000000000000000001336731060300172375ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet/srv/NodeletList.srv000066400000000000000000000000261336731060300222170ustar00rootroot00000000000000--- string[] nodelets ros-nodelet-core-1.9.16/nodelet/srv/NodeletLoad.srv000066400000000000000000000002001336731060300221550ustar00rootroot00000000000000string name string type string[] remap_source_args string[] remap_target_args string[] my_argv string bond_id --- bool success ros-nodelet-core-1.9.16/nodelet/srv/NodeletUnload.srv000066400000000000000000000000351336731060300225260ustar00rootroot00000000000000string name --- bool success ros-nodelet-core-1.9.16/nodelet_core/000077500000000000000000000000001336731060300174355ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet_core/CHANGELOG.rst000066400000000000000000000041631336731060300214620ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package nodelet_core ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.9.16 (2018-04-27) ------------------- 1.9.15 (2018-03-16) ------------------- 1.9.14 (2017-11-15) ------------------- 1.9.13 (2017-10-27) ------------------- 1.9.12 (2017-08-04) ------------------- 1.9.11 (2017-07-27) ------------------- * remove trailing whitespaces (`#62 `_) * switch to package format 2 (`#63 `_) * Contributors: Mikael Arguedas 1.9.10 (2017-03-27) ------------------- 1.9.9 (2017-02-17) ------------------ 1.9.8 (2016-11-15) ------------------ 1.9.7 (2016-10-24) ------------------ 1.9.6 (2016-09-20) ------------------ 1.9.5 (2016-06-22) ------------------ 1.9.4 (2016-03-15) ------------------ * update maintainer * Contributors: Mikael Arguedas 1.9.3 (2015-08-05) ------------------ * Update bugtracker url * Contributors: Esteve Fernandez 1.9.2 (2014-10-30) ------------------ 1.9.1 (2014-10-29) ------------------ 1.9.0 (2014-06-16) ------------------ 1.8.3 (2014-05-08) ------------------ * update changelogs * Update maintainer field * Contributors: Dirk Thomas, Esteve Fernandez 1.8.2 (2014-01-07) ------------------ 1.8.0 (2013-07-11) ------------------ * update email in package.xml 1.7.15 (2013-03-12) ------------------- * Fix nodelet_core metpackage package.xml * add CMakeLists.txt for metapackage 1.7.14 (2013-01-13) ------------------- 1.7.13 (2012-12-27) ------------------- 1.7.12 (2012-12-19 01:34) ------------------------- 1.7.11 (2012-12-19 00:58) ------------------------- 1.7.10 (2012-12-14) ------------------- 1.7.9 (2012-12-13) ------------------ 1.7.8 (2012-12-06) ------------------ 1.7.7 (2012-11-01) ------------------ 1.7.6 (2012-10-30) ------------------ 1.7.5 (2012-10-23) ------------------ 1.7.4 (2012-10-08) ------------------ 1.7.3 (2012-10-04) ------------------ 1.7.2 (2012-10-03) ------------------ * remove test_nodelets for install 1.7.1 (2012-10-02) ------------------ * adding nodelet_core metapackage and reving to 1.7.1 1.7.0 (2012-10-01) ------------------ ros-nodelet-core-1.9.16/nodelet_core/CMakeLists.txt000066400000000000000000000001571336731060300222000ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(nodelet_core) find_package(catkin REQUIRED) catkin_metapackage() ros-nodelet-core-1.9.16/nodelet_core/package.xml000066400000000000000000000015001336731060300215460ustar00rootroot00000000000000 nodelet_core 1.9.16 Nodelet Core Metapackage Mikael Arguedas BSD http://www.ros.org/wiki/nodelet_core https://github.com/ros/nodelet_core/issues https://github.com/ros/nodelet_core Tully Foote catkin nodelet nodelet_topic_tools ros-nodelet-core-1.9.16/nodelet_topic_tools/000077500000000000000000000000001336731060300210435ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet_topic_tools/CHANGELOG.rst000066400000000000000000000075771336731060300231040ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package nodelet_topic_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.9.16 (2018-04-27) ------------------- 1.9.15 (2018-03-16) ------------------- * use new pluginlib headers (`#73 `_) * Contributors: Mikael Arguedas 1.9.14 (2017-11-15) ------------------- 1.9.13 (2017-10-27) ------------------- 1.9.12 (2017-08-04) ------------------- * fix exec_depend that are actually build_export_depends (`#65 `_) * Contributors: Mikael Arguedas 1.9.11 (2017-07-27) ------------------- * remove trailing whitespaces (`#62 `_) * switch to package format 2 (`#63 `_) * Contributors: Mikael Arguedas 1.9.10 (2017-03-27) ------------------- 1.9.9 (2017-02-17) ------------------ 1.9.8 (2016-11-15) ------------------ 1.9.7 (2016-10-24) ------------------ 1.9.6 (2016-09-20) ------------------ * Add NodeletLazy abstract class for lazy transport (`#45 `_) * Add NodeletLazy abstract class for lazy transport * Add test for NodeletLazy with checking its lazy-ness * Fix ROS logging format supporting `ros/ros_comm#875 `_ * Fix ever_subscribed\_ flag setting location * Clearfy the comment describing advertise method * Parameterize the duration to warn the no connection User can disable this feature by setting -1 to the param. * Contributors: Kentaro Wada 1.9.5 (2016-06-22) ------------------ 1.9.4 (2016-03-15) ------------------ * update maintainer * Contributors: Mikael Arguedas 1.9.3 (2015-08-05) ------------------ 1.9.2 (2014-10-30) ------------------ 1.9.1 (2014-10-29) ------------------ 1.9.0 (2014-06-16) ------------------ 1.8.3 (2014-05-08) ------------------ * update changelogs * Update maintainer field * fix missing boost dependency * Contributors: Dirk Thomas, Esteve Fernandez * fix missing boost dependency 1.8.2 (2014-01-07) ------------------ 1.8.0 (2013-07-11) ------------------ * update email in package.xml 1.7.15 (2013-03-12) ------------------- 1.7.14 (2013-01-13) ------------------- 1.7.13 (2012-12-27) ------------------- * move nodelet_topic_tools to separate package, fix unit tests 1.7.12 (2012-12-19 01:34) ------------------------- * remove obsolete imports 1.7.11 (2012-12-19 00:58) ------------------------- * reordering dynamic_reconfigure in CMakeLists.txt 1.7.10 (2012-12-14) ------------------- * add missing dep to catkin 1.7.9 (2012-12-13) ------------------ 1.7.8 (2012-12-06) ------------------ * updated catkin_package(DEPENDS) 1.7.7 (2012-11-01) ------------------ * no need to export the plugin as it is for testing only 1.7.6 (2012-10-30) ------------------ * clean up package.xml files 1.7.5 (2012-10-23) ------------------ * comply to the new dynamic_reconfigure API 1.7.4 (2012-10-08) ------------------ * fixed cmake to find dependencies correctly 1.7.3 (2012-10-04) ------------------ * fix typo 1.7.2 (2012-10-03) ------------------ * add rostest as a dependency 1.7.1 (2012-10-02) ------------------ * adding nodelet_core metapackage and reving to 1.7.1 1.7.0 (2012-10-01) ------------------ * make it compile locally * first pass at catkinizing the stack * Adding nodelet throttle, `#5295 `_ * fixed a grave bug where nullfilters were not working correctly * added missing dependency * MUX simplified by using a 8-connected null filters DeMUX has a specialization for message type (uses ros::Subscriber internally by default) Added rosdep for nodelet (uuid) * Added Ubuntu platform tags to manifest * fixed the tools (broken, did not compile) * removed the transport for now * moving topic tools out of nodelet proper, removing rospy and message_filters dependencies from nodelet ros-nodelet-core-1.9.16/nodelet_topic_tools/CMakeLists.txt000066400000000000000000000007161336731060300236070ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(nodelet_topic_tools) find_package(catkin REQUIRED COMPONENTS dynamic_reconfigure) find_package(Boost REQUIRED thread) generate_dynamic_reconfigure_options(cfg/NodeletThrottle.cfg) catkin_package( INCLUDE_DIRS include CATKIN_DEPENDS dynamic_reconfigure message_filters nodelet pluginlib roscpp DEPENDS Boost ) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} ) ros-nodelet-core-1.9.16/nodelet_topic_tools/cfg/000077500000000000000000000000001336731060300216025ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet_topic_tools/cfg/NodeletThrottle.cfg000077500000000000000000000004701336731060300254070ustar00rootroot00000000000000#! /usr/bin/env python from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() gen.add("update_rate", double_t, 0, "Maximum update rate of throttle", -1.0, -1.0) # No max rate exit(gen.generate('nodelet_topic_tools', "nodelet_throttle_dynamic_reconfigure", "NodeletThrottle")) ros-nodelet-core-1.9.16/nodelet_topic_tools/include/000077500000000000000000000000001336731060300224665ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/000077500000000000000000000000001336731060300265365ustar00rootroot00000000000000ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_demux.h000066400000000000000000000171001336731060300315420ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 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 OWNERff 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. * * $Id: nodelet_mux.h 27892 2010-02-25 06:47:29Z rusu $ * */ #ifndef NODELET_NODELET_DEMUX_H_ #define NODELET_NODELET_DEMUX_H_ #include #include #include #include namespace nodelet { /** \brief @b NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) output topics. * \author Radu Bogdan Rusu */ template > class NodeletDEMUX: public Nodelet { typedef typename boost::shared_ptr TConstPtr; public: ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Nodelet initialization routine. */ void onInit () { private_nh_ = getPrivateNodeHandle (); sub_input_.subscribe (private_nh_, "input", 1, bind (&NodeletDEMUX::input_callback, this, _1)); if (!private_nh_.getParam ("output_topics", output_topics_)) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!"); return; } // Check the type switch (output_topics_.getType ()) { case XmlRpc::XmlRpcValue::TypeArray: { if (output_topics_.size () == 1) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Only one topic given. Does it make sense to passthrough?"); return; } if (output_topics_.size () > 8) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] More than 8 topics passed!"); return; } ROS_INFO_STREAM ("[nodelet::NodeletDEMUX::init] Publishing to " << output_topics_.size () << " user given topics as outputs:"); for (int d = 0; d < output_topics_.size (); ++d) ROS_INFO_STREAM (" - " << (std::string)(output_topics_[d])); pubs_output_.resize (output_topics_.size ()); for (int d = 0; d < output_topics_.size (); ++d) *pubs_output_[d] = private_nh_.template advertise ((std::string)(output_topics_[d]), 1); break; } default: { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Invalid 'output_topics' parameter given!"); return; } } } private: ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void input_callback (const TConstPtr &input) { for (size_t d = 0; d < pubs_output_.size (); ++d) pubs_output_[d]->publish (input); } /** \brief ROS local node handle. */ ros::NodeHandle private_nh_; /** \brief The output list of publishers. */ std::vector > pubs_output_; /** \brief The input subscriber. */ Subscriber sub_input_; /** \brief The list of output topics passed as a parameter. */ XmlRpc::XmlRpcValue output_topics_; }; /** \brief @b NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) output topics. * \author Radu Bogdan Rusu */ template class NodeletDEMUX >: public Nodelet { typedef typename boost::shared_ptr TConstPtr; public: ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Nodelet initialization routine. */ void onInit () { private_nh_ = getPrivateNodeHandle (); sub_input_ = private_nh_.subscribe ("input", 1, &NodeletDEMUX::input_callback, this); if (!private_nh_.getParam ("output_topics", output_topics_)) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!"); return; } // Check the type switch (output_topics_.getType ()) { case XmlRpc::XmlRpcValue::TypeArray: { if (output_topics_.size () == 1) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Only one topic given. Does it make sense to passthrough?"); return; } if (output_topics_.size () > 8) { ROS_ERROR ("[nodelet::NodeletDEMUX::init] More than 8 topics passed!"); return; } ROS_INFO_STREAM ("[nodelet::NodeletDEMUX::init] Publishing to " << output_topics_.size () << " user given topics as outputs:"); for (int d = 0; d < output_topics_.size (); ++d) ROS_INFO_STREAM (" - " << (std::string)(output_topics_[d])); pubs_output_.resize (output_topics_.size ()); for (int d = 0; d < output_topics_.size (); ++d) *pubs_output_[d] = private_nh_.template advertise ((std::string)(output_topics_[d]), 1); break; } default: { ROS_ERROR ("[nodelet::NodeletDEMUX::init] Invalid 'output_topics' parameter given!"); return; } } } private: ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void input_callback (const TConstPtr &input) { for (size_t d = 0; d < pubs_output_.size (); ++d) pubs_output_[d]->publish (input); } /** \brief ROS local node handle. */ ros::NodeHandle private_nh_; /** \brief The output list of publishers. */ std::vector > pubs_output_; /** \brief The input subscriber. */ ros::Subscriber sub_input_; /** \brief The list of output topics passed as a parameter. */ XmlRpc::XmlRpcValue output_topics_; }; } #endif ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h000066400000000000000000000206631336731060300314070ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2014-2016, JSK Lab, University of Tokyo. * All rights reserved. * * 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/o2r other materials provided * with the distribution. * * Neither the name of the JSK Lab 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. *********************************************************************/ /* Author: Ryohei Ueda, Kentaro Wada */ #ifndef NODELET_LAZY_H_ #define NODELET_LAZY_H_ #include #include #include #include #include namespace nodelet_topic_tools { /** @brief * Enum to represent connection status. */ enum ConnectionStatus { NOT_INITIALIZED, NOT_SUBSCRIBED, SUBSCRIBED }; /** @brief * Nodelet to automatically subscribe/unsubscribe * topics according to subscription of advertised topics. * * It's important not to subscribe topic if no output is required. * * In order to watch advertised topics, need to use advertise template method. * And create subscribers in subscribe() and shutdown them in unsubscribed(). * */ class NodeletLazy: public nodelet::Nodelet { public: NodeletLazy() {} protected: /** @brief * Initialize nodehandles nh_ and pnh_. Subclass should call * this method in its onInit method */ virtual void onInit() { connection_status_ = NOT_SUBSCRIBED; bool use_multithread; ros::param::param("~use_multithread_callback", use_multithread, true); if (use_multithread) { NODELET_DEBUG("Using multithread callback"); nh_.reset (new ros::NodeHandle(getMTNodeHandle())); pnh_.reset (new ros::NodeHandle(getMTPrivateNodeHandle())); } else { NODELET_DEBUG("Using singlethread callback"); nh_.reset(new ros::NodeHandle(getNodeHandle())); pnh_.reset(new ros::NodeHandle(getPrivateNodeHandle())); } // option to use lazy transport pnh_->param("lazy", lazy_, true); // option for logging about being subscribed pnh_->param("verbose_connection", verbose_connection_, false); if (!verbose_connection_) { nh_->param("verbose_connection", verbose_connection_, false); } // timer to warn when no connection in the specified seconds ever_subscribed_ = false; double duration_to_warn_no_connection; pnh_->param("duration_to_warn_no_connection", duration_to_warn_no_connection, 5.0); if (duration_to_warn_no_connection > 0) { timer_ever_subscribed_ = nh_->createWallTimer( ros::WallDuration(duration_to_warn_no_connection), &NodeletLazy::warnNeverSubscribedCallback, this, /*oneshot=*/true); } } /** @brief * Post processing of initialization of nodelet. * You need to call this method in order to use always_subscribe * feature. */ virtual void onInitPostProcess() { if (!lazy_) { boost::mutex::scoped_lock lock(connection_mutex_); subscribe(); ever_subscribed_ = true; } } /** @brief * callback function which is called when new subscriber come */ virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub) { if (verbose_connection_) { NODELET_INFO("New connection or disconnection is detected"); } if (lazy_) { boost::mutex::scoped_lock lock(connection_mutex_); for (size_t i = 0; i < publishers_.size(); i++) { ros::Publisher pub = publishers_[i]; if (pub.getNumSubscribers() > 0) { if (connection_status_ != SUBSCRIBED) { if (verbose_connection_) { NODELET_INFO("Subscribe input topics"); } subscribe(); connection_status_ = SUBSCRIBED; } if (!ever_subscribed_) { ever_subscribed_ = true; } return; } } if (connection_status_ == SUBSCRIBED) { if (verbose_connection_) { NODELET_INFO("Unsubscribe input topics"); } unsubscribe(); connection_status_ = NOT_SUBSCRIBED; } } } /** @brief * callback function which is called when walltimer * duration run out. */ virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event) { if (!ever_subscribed_) { NODELET_WARN("This node/nodelet subscribes topics only when subscribed."); } } /** @brief * This method is called when publisher is subscribed by other * nodes. * Set up subscribers in this method. */ virtual void subscribe() = 0; /** @brief * This method is called when publisher is unsubscribed by other * nodes. * Shut down subscribers in this method. */ virtual void unsubscribe() = 0; /** @brief * Update the list of Publishers created by this method. * It automatically reads latch boolean parameter from nh and * publish topic with appropriate latch parameter. * * @param nh NodeHandle. * @param topic topic name to advertise. * @param queue_size queue size for publisher. * @param latch set true if latch topic publication. * @return Publisher for the advertised topic. */ template ros::Publisher advertise(ros::NodeHandle& nh, std::string topic, int queue_size, bool latch=false) { boost::mutex::scoped_lock lock(connection_mutex_); ros::SubscriberStatusCallback connect_cb = boost::bind(&NodeletLazy::connectionCallback, this, _1); ros::SubscriberStatusCallback disconnect_cb = boost::bind(&NodeletLazy::connectionCallback, this, _1); ros::Publisher pub = nh.advertise(topic, queue_size, connect_cb, disconnect_cb, ros::VoidConstPtr(), latch); publishers_.push_back(pub); return pub; } /** @brief * mutex to call subscribe() and unsubscribe() in * critical section. */ boost::mutex connection_mutex_; /** @brief * Shared pointer to nodehandle. */ boost::shared_ptr nh_; /** @brief * Shared pointer to private nodehandle. */ boost::shared_ptr pnh_; /** @brief * List of watching publishers */ std::vector publishers_; /** @brief * WallTimer instance for warning about no connection. */ ros::WallTimer timer_ever_subscribed_; /** @brief * A flag to check if the node has been ever subscribed * or not. */ bool ever_subscribed_; /** @brief * A flag to disable watching mechanism and always subscribe input * topics. It can be specified via `~lazy` parameter. */ bool lazy_; /** @brief * Status of connection */ ConnectionStatus connection_status_; /** @brief * true if `~verbose_connection` or `verbose_connection` parameter is true. */ bool verbose_connection_; private: }; } // namespace nodelet_topic_tools #endif // NODELET_LAZY_H_ ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_mux.h000066400000000000000000000165331336731060300312420ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 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 OWNERff 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. * * $Id$ * */ #ifndef NODELET_NODELET_MUX_H_ #define NODELET_NODELET_MUX_H_ #include #include #include #include namespace nodelet { /** \brief @b NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them * on one output topic. * \author Radu Bogdan Rusu */ template class NodeletMUX: public Nodelet { typedef typename boost::shared_ptr TPtr; typedef typename boost::shared_ptr TConstPtr; public: NodeletMUX () : maximum_queue_size_ (3) {} ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Nodelet initialization routine. */ virtual void onInit () { private_nh_ = getMTPrivateNodeHandle (); pub_output_ = private_nh_.template advertise ("output", 1); XmlRpc::XmlRpcValue input_topics; if (!private_nh_.getParam ("input_topics", input_topics)) { ROS_ERROR ("[nodelet::NodeletMUX::init] Need a 'input_topics' parameter to be set before continuing!"); return; } private_nh_.getParam ("max_queue_size", maximum_queue_size_); // Check the type switch (input_topics.getType ()) { case XmlRpc::XmlRpcValue::TypeArray: { if (input_topics.size () == 1) { ROS_ERROR ("[nodelet::NodeletMUX::init] Only one topic given. Does it make sense to passthrough?"); return; } if (input_topics.size () > 8) { ROS_ERROR ("[nodelet::NodeletMUX::init] More than 8 topics passed!"); return; } ROS_INFO_STREAM ("[nodelet::NodeletMUX::init] Subscribing to " << input_topics.size () << " user given topics as inputs:"); for (int d = 0; d < input_topics.size (); ++d) ROS_INFO_STREAM (" - " << (std::string)(input_topics[d])); // Subscribe to the filters filters_.resize (input_topics.size ()); for (int d = 0; d < input_topics.size (); ++d) { filters_[d].reset (new Filter ()); filters_[d]->subscribe (private_nh_, (std::string)(input_topics[d]), 1); } // Subscribe to 1 callback to fill in the passthrough filters_[0]->registerCallback (boost::bind (&NodeletMUX::filter_cb, this, _1)); ts_.reset (new message_filters::TimeSynchronizer (maximum_queue_size_)); switch (input_topics.size ()) { case 2: { ts_->connectInput (*filters_[0], *filters_[1], nf_, nf_, nf_, nf_, nf_, nf_); break; } case 3: { ts_->connectInput (*filters_[0], *filters_[1], *filters_[2], nf_, nf_, nf_, nf_, nf_); break; } case 4: { ts_->connectInput (*filters_[0], *filters_[1], *filters_[2], *filters_[3], nf_, nf_, nf_, nf_); break; } case 5: { ts_->connectInput (*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4], nf_, nf_, nf_); break; } case 6: { ts_->connectInput (*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4], *filters_[5], nf_, nf_); break; } case 7: { ts_->connectInput (*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4], *filters_[5], *filters_[6], nf_); break; } case 8: { ts_->connectInput (*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4], *filters_[5], *filters_[6], *filters_[7]); break; } default: { ROS_ERROR ("[nodelet::NodeletMUX::init] Invalid 'input_topics' parameter given!"); return; } } break; } default: { ROS_ERROR ("[nodelet::NodeletMUX::init] Invalid 'input_topics' parameter given!"); return; } } ts_->registerCallback (boost::bind (&NodeletMUX::input, this, _1, _2, _3, _4, _5, _6, _7, _8)); } private: void filter_cb (const TConstPtr &input) { nf_.add (input); } void input (const TConstPtr &in1, const TConstPtr &in2, const TConstPtr &in3, const TConstPtr &in4, const TConstPtr &in5, const TConstPtr &in6, const TConstPtr &in7, const TConstPtr &in8) { pub_output_.publish (in1); pub_output_.publish (in2); pub_output_.publish (in3); pub_output_.publish (in4); pub_output_.publish (in5); pub_output_.publish (in6); pub_output_.publish (in7); pub_output_.publish (in8); } /** \brief ROS local node handle. */ ros::NodeHandle private_nh_; /** \brief The output ROS publisher. */ ros::Publisher pub_output_; /** \brief Null filter. */ message_filters::PassThrough nf_; /** \brief The maximum number of messages that we can store in the queue. */ int maximum_queue_size_; /** \brief A vector of message filters. */ std::vector > filters_; /** \brief Synchronizer object. */ boost::shared_ptr > ts_; }; } #endif ros-nodelet-core-1.9.16/nodelet_topic_tools/include/nodelet_topic_tools/nodelet_throttle.h000066400000000000000000000106221336731060300322670ustar00rootroot00000000000000#ifndef _NODELET_TOPIC_TOOLS_NODELET_THROTTLE_H_ #define _NODELET_TOPIC_TOOLS_NODELET_THROTTLE_H_ /* * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include #include #include namespace nodelet_topic_tools { template class NodeletThrottle : public nodelet::Nodelet { public: //Constructor NodeletThrottle(): max_update_rate_(0) { }; ~NodeletThrottle() { delete srv_; } private: ros::Time last_update_; double max_update_rate_; boost::mutex connect_mutex_; dynamic_reconfigure::Server* srv_; virtual void onInit() { nh_ = getNodeHandle(); ros::NodeHandle& private_nh = getPrivateNodeHandle(); srv_ = new dynamic_reconfigure::Server(private_nh); dynamic_reconfigure::Server::CallbackType f = boost::bind(&NodeletThrottle::reconfigure, this, _1, _2); srv_->setCallback(f); // Lazy subscription to topic ros::AdvertiseOptions publisher_ao = ros::AdvertiseOptions::create( "topic_out", 10, boost::bind( &NodeletThrottle::connectCB, this), boost::bind( &NodeletThrottle::disconnectCB, this), ros::VoidPtr(), nh_.getCallbackQueue()); // Need to create the publisher with connection mutex // connectCB can be called before the publisher is created in nodelet // which means no topics will connect boost::lock_guard lock(connect_mutex_); pub_ = nh_.advertise(publisher_ao); }; void callback(const boost::shared_ptr& cloud) { if (max_update_rate_ > 0.0) { NODELET_DEBUG("update set to %f", max_update_rate_); if ( last_update_ + ros::Duration(1.0/max_update_rate_) > ros::Time::now()) { NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec()); return; } } last_update_ = ros::Time::now(); pub_.publish(cloud); } void reconfigure(nodelet_topic_tools::NodeletThrottleConfig &config, uint32_t level) { max_update_rate_ = config.update_rate; } void connectCB() { boost::lock_guard lock(connect_mutex_); if (pub_.getNumSubscribers() > 0) { NODELET_DEBUG("Connecting to topic"); sub_ = nh_.subscribe("topic_in", 10, &NodeletThrottle::callback, this); } } void disconnectCB() { boost::lock_guard lock(connect_mutex_); if (pub_.getNumSubscribers() == 0) { NODELET_DEBUG("Unsubscribing from topic."); sub_.shutdown(); } } ros::NodeHandle nh_; ros::Publisher pub_; ros::Subscriber sub_; }; } // namespace #endif // guard ros-nodelet-core-1.9.16/nodelet_topic_tools/mainpage.dox000066400000000000000000000011251336731060300233370ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b nodelet_topic_tools is ... \section codeapi Code API */ ros-nodelet-core-1.9.16/nodelet_topic_tools/package.xml000066400000000000000000000020501336731060300231550ustar00rootroot00000000000000 nodelet_topic_tools 1.9.16 This package contains common nodelet tools such as a mux, demux and throttle. Mikael Arguedas BSD http://ros.org/wiki/nodelet_topic_tools https://github.com/ros/nodelet_core/issues https://github.com/ros/nodelet_core Radu Bogdan Rusu Tully Foote catkin boost dynamic_reconfigure message_filters nodelet pluginlib roscpp ros-nodelet-core-1.9.16/test_nodelet/000077500000000000000000000000001336731060300174645ustar00rootroot00000000000000ros-nodelet-core-1.9.16/test_nodelet/CHANGELOG.rst000066400000000000000000000122141336731060300215050ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package test_nodelet ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.9.16 (2018-04-27) ------------------- 1.9.15 (2018-03-16) ------------------- * use new pluginlib headers (`#73 `_) * Contributors: Mikael Arguedas 1.9.14 (2017-11-15) ------------------- * update to use non deprecated pluginlib macro (`#69 `_) * Contributors: Mikael Arguedas 1.9.13 (2017-10-27) ------------------- 1.9.12 (2017-08-04) ------------------- 1.9.11 (2017-07-27) ------------------- * Test nodehandles (`#64 `_) * remove trailing whitespaces (`#62 `_) * switch to package format 2 (`#63 `_) * Contributors: Mikael Arguedas 1.9.10 (2017-03-27) ------------------- * fix unused var warning * Contributors: Mikael Arguedas 1.9.9 (2017-02-17) ------------------ 1.9.8 (2016-11-15) ------------------ * Fix bond handling during nodelet unloading (`#51 `_) * add test whether bond breaking on unload works (tests `#50 `_) * disable callback for broken bond when we are breaking it This avoids the nodelet::LoaderROS::unload() method to be called twice for the same nodelet, causing an error output. * use AsyncSpinner for nodelet load in order for the shutdown procedure to work During shutdown, the bonds still need to communicate their status in order for the nodelet to properly/cleanly/quickly unload. This requires the node to spin. * add test whether LoaderROS::unload() is called twice (tests `#50 `_) * Contributors: Daniel Seifert 1.9.7 (2016-10-24) ------------------ 1.9.6 (2016-09-20) ------------------ 1.9.5 (2016-06-22) ------------------ 1.9.4 (2016-03-15) ------------------ * add test dependency on rosbash http://build.ros.org/job/Jdev__nodelet_core__ubuntu_trusty_amd64/3/ should fix this * update maintainer * Contributors: Mikael Arguedas 1.9.3 (2015-08-05) ------------------ * adding support for named nodelet loggers * Contributors: Tully Foote 1.9.2 (2014-10-30) ------------------ 1.9.1 (2014-10-29) ------------------ * test_nodelet: test for `#23 `_ (display helpful error msg) * Contributors: Max Schwarz 1.9.0 (2014-06-16) ------------------ 1.8.3 (2014-05-08) ------------------ * update changelogs * Update maintainer field * Contributors: Dirk Thomas, Esteve Fernandez 1.8.2 (2014-01-07) ------------------ 1.8.0 (2013-07-11) ------------------ * check for CATKIN_ENABLE_TESTING * update email in package.xml 1.7.15 (2013-03-12) ------------------- 1.7.14 (2013-01-13) ------------------- 1.7.13 (2012-12-27) ------------------- * move nodelet_topic_tools to separate package, fix unit tests 1.7.12 (2012-12-19 01:34) ------------------------- 1.7.11 (2012-12-19 00:58) ------------------------- 1.7.10 (2012-12-14) ------------------- * add missing dep to catkin 1.7.9 (2012-12-13) ------------------ 1.7.8 (2012-12-06) ------------------ * fix test registration 1.7.7 (2012-11-01) ------------------ 1.7.6 (2012-10-30) ------------------ * clean up package.xml files 1.7.5 (2012-10-23) ------------------ * fixed compiling tests 1.7.4 (2012-10-08) ------------------ * fixed cmake to find dependencies correctly 1.7.3 (2012-10-04) ------------------ 1.7.2 (2012-10-03) ------------------ 1.7.1 (2012-10-02) ------------------ * adding nodelet_core metapackage and reving to 1.7.1 1.7.0 (2012-10-01) ------------------ * make it compile locally * first pass at catkinizing the stack * add explicit boost link * Added benchmark for CallbackQueueManager performance. * adding support for once, throttle, and filter features. With unit tests for all but the filters `#4681 `_ * fix test on machines with only 1 core (`#4082 `_) * fix hanging tests and a hang on nodelet CallbackQueueManager destruction (`#4082 `_) * backing out my testing changes accidentally committed * reving for release 1.1.6 * Added Ubuntu platform tags to manifest * Hopefully fix what is probably a load-related test problem (http://build.willowgarage.com/job/ros-latest-all-test-ubuntu-jaunty-x86_64/36/testReport/test_nodelet.test_callback_queue_manager/CallbackQueueManager/test_nodelet_test_callback_queue_manager_multipleSingleThreaded/) * Fix && that should have been || (`#4048 `_) * add wait_for_service calls * merging josh's branch from ticket `#3875 `_ * moving topic tools out of nodelet proper, removing rospy and message_filters dependencies from nodelet * review status * removing extra launch files and adding test to CMake * coverage on nodelet commands in tests, coverage of parameter and remapping passing * two unit tests passing * first unittest working * creating test package for nodelet ros-nodelet-core-1.9.16/test_nodelet/CMakeLists.txt000066400000000000000000000045421336731060300222310ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(test_nodelet) find_package(catkin REQUIRED) catkin_package() if(CATKIN_ENABLE_TESTING) find_package(Boost REQUIRED thread) find_package(catkin REQUIRED nodelet pluginlib rostest) include_directories(SYSTEM ${BOOST_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} ) #common commands for building c++ executables and libraries add_library(${PROJECT_NAME} src/plus.cpp src/console_tests.cpp src/failing_nodelet.cpp src/nodehandles.cpp) target_link_libraries(${PROJECT_NAME} ${BOOST_LIBRARIES} ${catkin_LIBRARIES} ) add_rostest(test_local.launch) add_rostest(test_loader.launch) catkin_add_gtest(test_callback_queue_manager src/test_callback_queue_manager.cpp) target_link_libraries(test_callback_queue_manager ${BOOST_LIBRARIES} ${catkin_LIBRARIES}) add_executable(test_console EXCLUDE_FROM_ALL test/test_console.cpp) target_link_libraries(test_console ${catkin_LIBRARIES} ${GTEST_LIBRARIES}) add_dependencies(tests test_console) add_rostest(test/test_console.launch) add_rostest(test/test_bond_break_on_shutdown.launch) add_rostest(test/test_unload_called_twice.launch) add_rostest_gtest(test_nodehandles_different_namespaces test/test_nodehandles_different_namespaces.test test/test_nodehandles_different_namespaces.cpp) target_link_libraries(test_nodehandles_different_namespaces ${catkin_LIBRARIES}) add_rostest_gtest(test_nodehandles_same_namespaces test/test_nodehandles_same_namespaces.test test/test_nodehandles_same_namespaces.cpp) target_link_libraries(test_nodehandles_same_namespaces ${catkin_LIBRARIES}) add_rostest_gtest(test_nodehandles_manager_namespaced test/test_nodehandles_manager_namespaced.test test/test_nodehandles_manager_namespaced.cpp) target_link_libraries(test_nodehandles_manager_namespaced ${catkin_LIBRARIES}) # Not a real test. Tries to measure overhead of CallbackQueueManager. add_executable(benchmark src/benchmark.cpp) target_link_libraries(benchmark ${BOOST_LIBRARIES} ${PROJECT_NAME} ) add_executable(create_instance_cb_error src/create_instance_cb_error.cpp) target_link_libraries(create_instance_cb_error ${catkin_LIBRARIES}) endif() ros-nodelet-core-1.9.16/test_nodelet/debug_logging.conf000066400000000000000000000000271336731060300231260ustar00rootroot00000000000000log4j.logger.ros=DEBUG ros-nodelet-core-1.9.16/test_nodelet/mainpage.dox000066400000000000000000000011161336731060300217600ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b test_nodelet is ... \section codeapi Code API */ ros-nodelet-core-1.9.16/test_nodelet/package.xml000066400000000000000000000016401336731060300216020ustar00rootroot00000000000000 test_nodelet 1.9.16 A package for nodelet unit tests Mikael Arguedas BSD http://ros.org/wiki/test_nodelet https://github.com/ros/nodelet_core/issues https://github.com/ros/nodelet_core Tully Foote catkin nodelet pluginlib rostest std_msgs rosbash ros-nodelet-core-1.9.16/test_nodelet/plus_default.yaml000066400000000000000000000000121336731060300230300ustar00rootroot00000000000000value: 10 ros-nodelet-core-1.9.16/test_nodelet/src/000077500000000000000000000000001336731060300202535ustar00rootroot00000000000000ros-nodelet-core-1.9.16/test_nodelet/src/benchmark.cpp000066400000000000000000000023221336731060300227100ustar00rootroot00000000000000#include #include #include #include #include #include #include using namespace nodelet::detail; using boost::detail::atomic_count; static const long NUM_CALLBACKS = 1e7; atomic_count g_count(NUM_CALLBACKS); boost::mutex g_mutex; boost::condition_variable g_cond; class MyCallback : public ros::CallbackInterface { public: ros::CallbackInterface::CallResult call() { if (--g_count == 0) { boost::mutex::scoped_lock lock(g_mutex); g_cond.notify_all(); } return Success; } }; typedef boost::shared_ptr MyCallbackPtr; int main(int argc, char** argv) { CallbackQueueManager man; CallbackQueuePtr queue(new CallbackQueue(&man)); man.addQueue(queue, true); double start = ros::WallTime::now().toSec(); for (long i = 0; i < NUM_CALLBACKS; ++i) { MyCallbackPtr cb(new MyCallback); queue->addCallback(cb, 0); } { boost::mutex::scoped_lock lock(g_mutex); g_cond.wait(lock); } double end = ros::WallTime::now().toSec(); printf("Total time = %.3f\n", end - start); return 0; } ros-nodelet-core-1.9.16/test_nodelet/src/console_tests.cpp000066400000000000000000000223031336731060300236430ustar00rootroot00000000000000/* * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include #include //fabs namespace test_nodelet { class ConsoleTest : public nodelet::Nodelet { private: virtual void onInit() { std::string suffix("logger_suffix"); NODELET_DEBUG("DEBUG output"); NODELET_DEBUG_STREAM("DEBUG" << " output"); NODELET_DEBUG_ONCE("DEBUG output"); NODELET_DEBUG_STREAM_ONCE("DEBUG" << " output"); NODELET_DEBUG_COND(1 == 1, "DEBUG output"); NODELET_DEBUG_STREAM_COND(1 == 1, "DEBUG" << " output"); NODELET_DEBUG_COND(1 == 0, "DEBUG output unseen"); NODELET_DEBUG_STREAM_COND(1 == 0, "DEBUG" << " output unseen"); NODELET_DEBUG_THROTTLE(10.0, "DEBUG output"); NODELET_DEBUG_STREAM_THROTTLE(10.0, "DEBUG" << " output"); //TODO TEST FILTERS //NODELET_DEBUG_FILTER(10.0, "DEBUG output"); //NODELET_DEBUG_STREAM_FILTER(10.0, "DEBUG" << " output"); NODELET_DEBUG_NAMED(suffix, "DEBUG output"); NODELET_DEBUG_STREAM_NAMED(suffix, "DEBUG" << " output"); NODELET_DEBUG_ONCE_NAMED(suffix, "DEBUG output"); NODELET_DEBUG_STREAM_ONCE_NAMED(suffix, "DEBUG" << " output"); NODELET_DEBUG_COND_NAMED(1 == 1, suffix, "DEBUG output"); NODELET_DEBUG_STREAM_COND_NAMED(1 == 1, suffix, "DEBUG" << " output"); NODELET_DEBUG_COND_NAMED(1 == 0, suffix, "DEBUG output unseen"); NODELET_DEBUG_STREAM_COND_NAMED(1 == 0, suffix, "DEBUG" << " output unseen"); NODELET_DEBUG_THROTTLE_NAMED(10.0, suffix, "DEBUG output"); NODELET_DEBUG_STREAM_THROTTLE_NAMED(10.0, suffix, "DEBUG" << " output"); //TODO TEST FILTERS //NODELET_DEBUG_FILTER_NAMED(10.0, suffix, "DEBUG output"); //NODELET_DEBUG_STREAM_FILTER_NAMED(10.0, suffix, "DEBUG" << " output"); NODELET_INFO("INFO output"); NODELET_INFO_STREAM("INFO" << " output"); NODELET_INFO_ONCE("INFO output"); NODELET_INFO_STREAM_ONCE("INFO" << " output"); NODELET_INFO_COND(1 == 1, "INFO output"); NODELET_INFO_STREAM_COND(1 == 1, "INFO" << " output"); NODELET_INFO_COND(1 == 0, "INFO output unseen"); NODELET_INFO_STREAM_COND(1 == 0, "INFO" << " output unseen"); NODELET_INFO_THROTTLE(10.0, "INFO output"); NODELET_INFO_STREAM_THROTTLE(10.0, "INFO" << " output"); //TODO TEST FILTERS //NODELET_INFO_FILTER(10.0, "INFO output"); //NODELET_INFO_STREAM_FILTER(10.0, "INFO" << " output"); NODELET_INFO_NAMED(suffix, "INFO output"); NODELET_INFO_STREAM_NAMED(suffix, "INFO" << " output"); NODELET_INFO_ONCE_NAMED(suffix, "INFO output"); NODELET_INFO_STREAM_ONCE_NAMED(suffix, "INFO" << " output"); NODELET_INFO_COND_NAMED(1 == 1, suffix, "INFO output"); NODELET_INFO_STREAM_COND_NAMED(1 == 1, suffix, "INFO" << " output"); NODELET_INFO_COND_NAMED(1 == 0, suffix, "INFO output unseen"); NODELET_INFO_STREAM_COND_NAMED(1 == 0, suffix, "INFO" << " output unseen"); NODELET_INFO_THROTTLE_NAMED(10.0, suffix, "INFO output"); NODELET_INFO_STREAM_THROTTLE_NAMED(10.0, suffix, "INFO" << " output"); //TODO TEST FILTERS //NODELET_INFO_FILTER_NAMED(10.0, suffix, "INFO output"); //NODELET_INFO_STREAM_FILTER_NAMED(10.0, suffix, "INFO" << " output"); NODELET_WARN("WARN output"); NODELET_WARN_STREAM("WARN" << " output"); NODELET_WARN_ONCE("WARN output"); NODELET_WARN_STREAM_ONCE("WARN" << " output"); NODELET_WARN_COND(1 == 1, "WARN output"); NODELET_WARN_STREAM_COND(1 == 1, "WARN" << " output"); NODELET_WARN_COND(1 == 0, "WARN output unseen"); NODELET_WARN_STREAM_COND(1 == 0, "WARN" << " output unseen"); NODELET_WARN_THROTTLE(10.0, "WARN output"); NODELET_WARN_STREAM_THROTTLE(10.0, "WARN" << " output"); //TODO TEST FILTERS //NODELET_WARN_FILTER(10.0, "WARN output"); //NODELET_WARN_STREAM_FILTER(10.0, "WARN" << " output"); NODELET_WARN_NAMED(suffix, "WARN output"); NODELET_WARN_STREAM_NAMED(suffix, "WARN" << " output"); NODELET_WARN_ONCE_NAMED(suffix, "WARN output"); NODELET_WARN_STREAM_ONCE_NAMED(suffix, "WARN" << " output"); NODELET_WARN_COND_NAMED(1 == 1, suffix, "WARN output"); NODELET_WARN_STREAM_COND_NAMED(1 == 1, suffix, "WARN" << " output"); NODELET_WARN_COND_NAMED(1 == 0, suffix, "WARN output unseen"); NODELET_WARN_STREAM_COND_NAMED(1 == 0, suffix, "WARN" << " output unseen"); NODELET_WARN_THROTTLE_NAMED(10.0, suffix, "WARN output"); NODELET_WARN_STREAM_THROTTLE_NAMED(10.0, suffix, "WARN" << " output"); //TODO TEST FILTERS //NODELET_WARN_FILTER_NAMED(10.0, suffix, "WARN output"); //NODELET_WARN_STREAM_FILTER_NAMED(10.0, suffix, "WARN" << " output"); NODELET_ERROR("ERROR output"); NODELET_ERROR_STREAM("ERROR" << " output"); NODELET_ERROR_ONCE("ERROR output"); NODELET_ERROR_STREAM_ONCE("ERROR" << " output"); NODELET_ERROR_COND(1 == 1, "ERROR output"); NODELET_ERROR_STREAM_COND(1 == 1, "ERROR" << " output"); NODELET_ERROR_COND(1 == 0, "ERROR output unseen"); NODELET_ERROR_STREAM_COND(1 == 0, "ERROR" << " output unseen"); NODELET_ERROR_THROTTLE(10.0, "ERROR output"); NODELET_ERROR_STREAM_THROTTLE(10.0, "ERROR" << " output"); //TODO TEST FILTERS //NODELET_ERROR_FILTER(10.0, "ERROR output"); //NODELET_ERROR_STREAM_FILTER(10.0, "ERROR" << " output"); NODELET_ERROR_NAMED(suffix, "ERROR output"); NODELET_ERROR_STREAM_NAMED(suffix, "ERROR" << " output"); NODELET_ERROR_ONCE_NAMED(suffix, "ERROR output"); NODELET_ERROR_STREAM_ONCE_NAMED(suffix, "ERROR" << " output"); NODELET_ERROR_COND_NAMED(1 == 1, suffix, "ERROR output"); NODELET_ERROR_STREAM_COND_NAMED(1 == 1, suffix, "ERROR" << " output"); NODELET_ERROR_COND_NAMED(1 == 0, suffix, "ERROR output unseen"); NODELET_ERROR_STREAM_COND_NAMED(1 == 0, suffix, "ERROR" << " output unseen"); NODELET_ERROR_THROTTLE_NAMED(10.0, suffix, "ERROR output"); NODELET_ERROR_STREAM_THROTTLE_NAMED(10.0, suffix, "ERROR" << " output"); //TODO TEST FILTERS //NODELET_ERROR_FILTER_NAMED(10.0, suffix, "ERROR output"); //NODELET_ERROR_STREAM_FILTER_NAMED(10.0, suffix, "ERROR" << " output"); NODELET_FATAL("FATAL output"); NODELET_FATAL_STREAM("FATAL" << " output"); NODELET_FATAL_ONCE("FATAL output"); NODELET_FATAL_STREAM_ONCE("FATAL" << " output"); NODELET_FATAL_COND(1 == 1, "FATAL output"); NODELET_FATAL_STREAM_COND(1 == 1, "FATAL" << " output"); NODELET_FATAL_COND(1 == 0, "FATAL output unseen"); NODELET_FATAL_STREAM_COND(1 == 0, "FATAL" << " output unseen"); NODELET_FATAL_THROTTLE(10.0, "FATAL output"); NODELET_FATAL_STREAM_THROTTLE(10.0, "FATAL" << " output"); //TODO TEST FILTERS //NODELET_FATAL_FILTER(10.0, "FATAL output"); //NODELET_FATAL_STREAM_FILTER(10.0, "FATAL" << " output"); NODELET_FATAL_NAMED(suffix, "FATAL output"); NODELET_FATAL_STREAM_NAMED(suffix, "FATAL" << " named output"); NODELET_FATAL_ONCE_NAMED(suffix, "FATAL named output"); NODELET_FATAL_STREAM_ONCE_NAMED(suffix, "FATAL" << " named output"); NODELET_FATAL_COND_NAMED(1 == 1, suffix, "FATAL named output"); NODELET_FATAL_STREAM_COND_NAMED(1 == 1, suffix, "FATAL" << " named output"); NODELET_FATAL_COND_NAMED(1 == 0, suffix, "FATAL named output unseen"); NODELET_FATAL_STREAM_COND_NAMED(1 == 0, suffix, "FATAL" << " named output unseen"); NODELET_FATAL_THROTTLE_NAMED(10.0, suffix, "FATAL named output"); NODELET_FATAL_STREAM_THROTTLE_NAMED(10.0, suffix, "FATAL" << " named output"); //TODO TEST FILTERS //NODELET_FATAL_FILTER_NAMED(10.0, suffix, "FATAL named output"); //NODELET_FATAL_STREAM_FILTER_NAMED(10.0, suffix, "FATAL" << " named output"); } }; PLUGINLIB_EXPORT_CLASS(test_nodelet::ConsoleTest, nodelet::Nodelet) } ros-nodelet-core-1.9.16/test_nodelet/src/create_instance_cb_error.cpp000066400000000000000000000044001336731060300257610ustar00rootroot00000000000000/* * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ // Helper for issue #23: nodelet loader hides load error // should generate a helpful error message containing "NODELET_TEST_FAILURE" #include #include #include boost::shared_ptr create_instance(const std::string&) { throw std::runtime_error("NODELET_TEST_FAILURE"); } int main(int argc, char** argv) { ros::init(argc, argv, "simple_loader"); nodelet::Loader loader(boost::bind(&create_instance, _1)); std::map remappings; std::vector my_argv; if(!loader.load("/fail", "test_nodelet/FailingNodelet", remappings, my_argv)) return 1; return 0; } ros-nodelet-core-1.9.16/test_nodelet/src/failing_nodelet.cpp000066400000000000000000000037461336731060300241140ustar00rootroot00000000000000/* * Copyright (c) 2014, Open Source Robotics Foundation, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include namespace test_nodelet { class FailingNodelet : public nodelet::Nodelet { public: FailingNodelet() {} private: virtual void onInit() { throw std::runtime_error("Initialization error"); } }; PLUGINLIB_EXPORT_CLASS(test_nodelet::FailingNodelet, nodelet::Nodelet) } ros-nodelet-core-1.9.16/test_nodelet/src/nodehandles.cpp000066400000000000000000000014561336731060300232510ustar00rootroot00000000000000#include #include #include #include #include #include #include namespace test_nodelet { class NodehandleTest : public nodelet::Nodelet { public: NodehandleTest(){}; virtual void onInit() { ros::NodeHandle nh = this->getNodeHandle(); ros::NodeHandle pnh = this->getPrivateNodeHandle(); global_pub_ = nh.advertise("/global", 1000); namespaced_pub_ = nh.advertise("namespaced", 1000); private_pub_ = pnh.advertise("private", 1000); } private: ros::Publisher global_pub_, namespaced_pub_, private_pub_; }; } // namespace test_nodelet PLUGINLIB_EXPORT_CLASS(test_nodelet::NodehandleTest, nodelet::Nodelet); ros-nodelet-core-1.9.16/test_nodelet/src/plus.cpp000066400000000000000000000047511336731060300217510ustar00rootroot00000000000000/* * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include #include //fabs namespace test_nodelet { class Plus : public nodelet::Nodelet { public: Plus() : value_(0) {} private: virtual void onInit() { ros::NodeHandle& private_nh = getPrivateNodeHandle(); private_nh.getParam("value", value_); pub = private_nh.advertise("out", 10); sub = private_nh.subscribe("in", 10, &Plus::callback, this); } void callback(const std_msgs::Float64::ConstPtr& input) { std_msgs::Float64Ptr output(new std_msgs::Float64()); output->data = input->data + value_; NODELET_DEBUG("Adding %f to get %f", value_, output->data); pub.publish(output); } ros::Publisher pub; ros::Subscriber sub; double value_; }; PLUGINLIB_EXPORT_CLASS(test_nodelet::Plus, nodelet::Nodelet) } ros-nodelet-core-1.9.16/test_nodelet/src/test_callback_queue_manager.cpp000066400000000000000000000120501336731060300264460ustar00rootroot00000000000000/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include #include #include #include #include #include using namespace nodelet; using namespace nodelet::detail; class SingleThreadedCallback : public ros::CallbackInterface { public: SingleThreadedCallback(boost::barrier* bar) : success(true) , calls(0) , inited_(false) , barrier_(bar) {} ros::CallbackInterface::CallResult call() { ros::WallDuration(0.1).sleep(); barrier_->wait(); { boost::mutex::scoped_lock lock(mutex_); if (!inited_) { initial_call_id = boost::this_thread::get_id(); inited_ = true; } if (initial_call_id != boost::this_thread::get_id()) { success = false; } ++calls; } return Success; } bool success; uint32_t calls; boost::thread::id initial_call_id; private: bool inited_; boost::mutex mutex_; boost::barrier* barrier_; }; typedef boost::shared_ptr SingleThreadedCallbackPtr; TEST(CallbackQueueManager, singleThreaded) { CallbackQueueManager man; CallbackQueuePtr queue(new CallbackQueue(&man)); man.addQueue(queue, false); boost::barrier bar(1); SingleThreadedCallbackPtr cb(new SingleThreadedCallback(&bar)); for (uint32_t i = 0; i < 10; ++i) { queue->addCallback(cb, 0); } while (cb->calls < 10) { ros::WallDuration(0.01).sleep(); } EXPECT_EQ(cb->calls, 10U); ASSERT_TRUE(cb->success); } TEST(CallbackQueueManager, multipleSingleThreaded) { uint32_t thread_count = boost::thread::hardware_concurrency(); // Need at least 2 threads here if (thread_count == 1) { thread_count = 2; } CallbackQueueManager man(thread_count); CallbackQueuePtr queue1(new CallbackQueue(&man)); CallbackQueuePtr queue2(new CallbackQueue(&man)); man.addQueue(queue1, false); man.addQueue(queue2, false); boost::barrier bar(2); SingleThreadedCallbackPtr cb1(new SingleThreadedCallback(&bar)); SingleThreadedCallbackPtr cb2(new SingleThreadedCallback(&bar)); for (uint32_t i = 0; i < 10; ++i) { queue1->addCallback(cb1, 1); queue2->addCallback(cb2, 1); } while (cb1->calls < 10 || cb2->calls < 10) { ros::WallDuration(0.01).sleep(); } EXPECT_EQ(cb1->calls, 10U); EXPECT_EQ(cb2->calls, 10U); EXPECT_TRUE(cb1->success); EXPECT_TRUE(cb2->success); EXPECT_NE(cb1->initial_call_id, cb2->initial_call_id); } class MultiThreadedCallback : public ros::CallbackInterface { public: MultiThreadedCallback(boost::barrier* bar) : barrier_(bar) {} ros::CallbackInterface::CallResult call() { barrier_->wait(); return Success; } private: boost::barrier* barrier_; }; typedef boost::shared_ptr MultiThreadedCallbackPtr; TEST(CallbackQueueManager, multiThreaded) { for (uint32_t j = 0; j < 1000; ++j) { //ROS_INFO_COND(j % 1000 == 0, "%d", j); CallbackQueueManager man(1); CallbackQueuePtr queue(new CallbackQueue(&man)); man.addQueue(queue, true); uint32_t num_threads = man.getNumWorkerThreads(); boost::barrier bar(num_threads + 1); MultiThreadedCallbackPtr cb(new MultiThreadedCallback(&bar)); for (uint32_t i = 0; i < num_threads; ++i) { queue->addCallback(cb, 0); } bar.wait(); queue->removeByID(0); } } int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ros-nodelet-core-1.9.16/test_nodelet/test/000077500000000000000000000000001336731060300204435ustar00rootroot00000000000000ros-nodelet-core-1.9.16/test_nodelet/test/plus_local.py000077500000000000000000000065311336731060300231620ustar00rootroot00000000000000#!/usr/bin/env python # Copyright (c) 2009, Willow Garage, Inc. # All rights reserved. # # 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 the 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. import roslib; roslib.load_manifest('test_nodelet') import rospy from std_msgs.msg import Float64 import unittest import rostest import random class PlusTester: def __init__(self, topic_in, topic_out, delta): self.pub = rospy.Publisher(topic_in, Float64) self.sub = rospy.Subscriber(topic_out, Float64, self.callback) self.expected_delta = delta self.send_value = random.random() self.recieved = False self.result = False self.delta = delta def run(self, cycles = 10): for i in range(1, cycles): self.pub.publish(Float64(self.send_value)) rospy.loginfo("Sent %f"%self.send_value); if self.recieved == True: break rospy.sleep(1.0) return self.result def callback(self, data): rospy.loginfo(rospy.get_name()+" I heard %s which was a change of %f",data.data, data.data-self.send_value) if data.data == self.send_value + self.delta: self.result = True self.recieved = True class TestPlus(unittest.TestCase): def test_param(self): pb = PlusTester("Plus/in", "Plus/out", 2.1) self.assertTrue(pb.run()) def test_default_param(self): pb = PlusTester("Plus2/in", "Plus2/out", 10.0) self.assertTrue(pb.run()) def test_standalone(self): pb = PlusTester("Plus2/out", "Plus3/out", 2.5) self.assertTrue(pb.run()) def test_remap(self): pb = PlusTester("plus_remap/in", "remapped_output", 2.1) self.assertTrue(pb.run()) def test_chain(self): pb = PlusTester("Plus2/in", "Plus3/out", 12.5) self.assertTrue(pb.run()) if __name__ == '__main__': rospy.init_node('plus_local') rostest.unitrun('test_nodelet', 'test_plus', TestPlus) ros-nodelet-core-1.9.16/test_nodelet/test/test_bond_break_on_shutdown.launch000066400000000000000000000003261336731060300274140ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test/test_bond_break_on_shutdown.py000077500000000000000000000043451336731060300266020ustar00rootroot00000000000000#!/usr/bin/env python import roslib; roslib.load_manifest('test_nodelet') import rospy import unittest import rostest import signal import subprocess import time from nodelet.srv import * class TestBondBreakOnShutdown(unittest.TestCase): def test_bond_break_on_shutdown(self): ''' Test that the bond is broken cleanly when closing a nodelet loader (#50). This relies on a debug message printed by the bondcpp package in case of error. ''' # start nodelet manager proc_manager = subprocess.Popen(["rosrun", "nodelet", "nodelet", "manager", "__name:=nodelet_manager"], stdout=subprocess.PIPE, stderr=subprocess.PIPE, bufsize=-1 ) # wait for nodelet manager to be ready try: rospy.wait_for_service('/nodelet_manager/load_nodelet', timeout=2) except: self.fail("Could not determine that nodelet manager has started") # load a nodelet proc_nodelet = subprocess.Popen(["rosrun", "nodelet", "nodelet", "load", "test_nodelet/Plus", "nodelet_manager", "__name:=test"], stdout=subprocess.PIPE, stderr=subprocess.PIPE, bufsize=-1 ) # wait for it to be ready try: rospy.wait_for_service('test/get_loggers', timeout=2) except: self.fail("Could not determine that nodelet has started") time.sleep(1) # stop the nodelet loader via signal (similar to roslaunch killing it) proc_nodelet.send_signal(signal.SIGINT) (n_out, n_err) = proc_nodelet.communicate() # stop the nodelet manager, too proc_manager.send_signal(signal.SIGINT) (m_out, m_err) = proc_manager.communicate() # check that nodelet unloaded and there was no error with bond breaking self.assertIn('Unloading nodelet /test from manager nodelet_manager', n_out) self.assertNotIn('Bond failed to break on destruction', m_out) self.assertNotIn('Bond failed to break on destruction', n_out) if __name__ == '__main__': rospy.init_node('test_bond_break_on_shutdown') rostest.unitrun('test_bond_break_on_shutdown', 'test_bond_break_on_shutdown', TestBondBreakOnShutdown) ros-nodelet-core-1.9.16/test_nodelet/test/test_console.cpp000066400000000000000000000042711336731060300236540ustar00rootroot00000000000000/* * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * 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 the 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. */ #include #include "nodelet/nodelet.h" #include "nodelet/loader.h" #include "ros/ros.h" TEST(NodeletConsole, TEST_CONSOLE) { nodelet::Loader n(false); ros::M_string remappings; //Remappings are already applied by ROS no need to generate them. std::string nodelet_name = "test_console"; std::string nodelet_type = "test_nodelet/ConsoleTest"; std::vector argvs; EXPECT_TRUE(n.load(nodelet_name, nodelet_type, remappings, argvs)); } int main(int argc, char** argv) { ros::init(argc, argv, "test_console"); ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ros-nodelet-core-1.9.16/test_nodelet/test/test_console.launch000066400000000000000000000001361336731060300243400ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test/test_loader.py000077500000000000000000000077071336731060300233400ustar00rootroot00000000000000#!/usr/bin/env python # Copyright (c) 2009, Willow Garage, Inc. # All rights reserved. # # 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 the 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. import roslib; roslib.load_manifest('test_nodelet') import rospy import unittest import rostest import random import subprocess from nodelet.srv import * class TestLoader(unittest.TestCase): def test_loader(self): load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad) unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload) list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList) load.wait_for_service() unload.wait_for_service() list.wait_for_service() req = NodeletLoadRequest() req.name = "/my_nodelet" req.type = "test_nodelet/Plus" res = load.call(req) self.assertTrue(res.success) req = NodeletListRequest() res = list.call(req) self.assertTrue("/my_nodelet" in res.nodelets) req = NodeletUnloadRequest() req.name = "/my_nodelet" res = unload.call(req) self.assertTrue(res.success) def test_loader_failed_initialization(self): load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad) unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload) list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList) load.wait_for_service() unload.wait_for_service() list.wait_for_service() req = NodeletLoadRequest() req.name = "/my_nodelet" req.type = "test_nodelet/FailingNodelet" self.assertRaises(rospy.ServiceException, load.call, req) # If the Nodelet failed to initialize, it shouldn't be stored in the # nodelet map req = NodeletListRequest() res = list.call(req) self.assertFalse("/my_nodelet" in res.nodelets) req = NodeletUnloadRequest() req.name = "/my_nodelet" self.assertRaises(rospy.ServiceException, unload.call, req) def test_loader_error_message(self): proc = subprocess.Popen(["rosrun", "test_nodelet", "create_instance_cb_error"], stderr=subprocess.PIPE ) # The load should fail self.assertEqual(proc.wait(), 1) # And the loader should print our error message out = proc.stderr.read() self.assertIn('NODELET_TEST_FAILURE', out) if __name__ == '__main__': rospy.init_node('test_loader') rostest.unitrun('test_loader', 'test_loader', TestLoader) ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_different_namespaces.cpp000066400000000000000000000131271336731060300307230ustar00rootroot00000000000000/********************************************************************* * test_nodehandles_different_namespaces.cpp * * Software License Agreement (BSD License) * * Copyright (c) 2016, University of Patras * All rights reserved. * * 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 University of Patras 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. * * Authors: Aris Synodinos *********************************************************************/ #include #include #include #include #include #include #include #include TEST(DifferentNamespaces, NodeletPrivateNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Bool") == 0) { found_topic = true; EXPECT_STREQ("/nodelet_namespace/nodehandle_test/private", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(DifferentNamespaces, NodeletNamespacedNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Byte") == 0) { found_topic = true; EXPECT_STREQ("/nodelet_namespace/namespaced", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(DifferentNamespaces, NodeletGlobalNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Time") == 0) { found_topic = true; EXPECT_STREQ("/global", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(DifferentNamespaces, NodePrivateNodehandle) { ros::NodeHandle nh("~"); ros::Publisher pub = nh.advertise("private", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Empty") == 0) { found_topic = true; EXPECT_STREQ("/test_namespace/test_nodehandles/private", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(DifferentNamespaces, NodeNamespacedNodehandle) { ros::NodeHandle nh; ros::Publisher pub = nh.advertise("namespaced", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/String") == 0) { found_topic = true; EXPECT_STREQ("/test_namespace/namespaced", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(DifferentNamespaces, NodeGlobalNodehandle) { ros::NodeHandle nh; ros::Publisher pub = nh.advertise("/public", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Float32") == 0) { found_topic = true; EXPECT_STREQ("/public", info.name.c_str()); } } EXPECT_TRUE(found_topic); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "test_nodehandles_different_namespaces"); return RUN_ALL_TESTS(); } ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_different_namespaces.test000066400000000000000000000007551336731060300311230ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_manager_namespaced.cpp000066400000000000000000000131701336731060300303460ustar00rootroot00000000000000/********************************************************************* * test_nodehandles_same_namespaces.cpp * * Software License Agreement (BSD License) * * Copyright (c) 2016, University of Patras * All rights reserved. * * 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 University of Patras 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. * * Authors: Aris Synodinos *********************************************************************/ #include #include #include #include #include #include #include TEST(ManagerNamespaced, NodeletPrivateNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Bool") == 0) { found_topic = true; EXPECT_STREQ("/nodehandle_test/private", info.name.c_str()); } } EXPECT_TRUE(found_topic); } // TODO(mikaelarguedas) reenable this once // https://github.com/ros/nodelet_core/issues/7 is fixed // TEST(ManagerNamespaced, NodeletNamespacedNodehandle) { // ros::NodeHandle nh; // ros::Duration(2).sleep(); // ros::master::V_TopicInfo master_topics; // ros::master::getTopics(master_topics); // bool found_topic = false; // // for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { // const ros::master::TopicInfo& info = *it; // if (info.datatype.compare("std_msgs/Byte") == 0) { // found_topic = true; // EXPECT_STREQ("/namespaced", info.name.c_str()); // } // } // EXPECT_TRUE(found_topic); // } TEST(ManagerNamespaced, NodeletGlobalNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Time") == 0) { found_topic = true; EXPECT_STREQ("/global", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(ManagerNamespaced, NodePrivateNodehandle) { ros::NodeHandle nh("~"); ros::Publisher pub = nh.advertise("private", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Empty") == 0) { found_topic = true; EXPECT_STREQ("/test_nodehandles/private", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(ManagerNamespaced, NodeNamespacedNodehandle) { ros::NodeHandle nh; ros::Publisher pub = nh.advertise("namespaced", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/String") == 0) { found_topic = true; EXPECT_STREQ("/namespaced", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(ManagerNamespaced, NodeGlobalNodehandle) { ros::NodeHandle nh; ros::Publisher pub = nh.advertise("/public", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Float32") == 0) { found_topic = true; EXPECT_STREQ("/public", info.name.c_str()); } } EXPECT_TRUE(found_topic); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "test_nodehandles_manager_namespaced"); return RUN_ALL_TESTS(); } ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_manager_namespaced.test000066400000000000000000000006221336731060300305410ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_same_namespaces.cpp000066400000000000000000000130231336731060300276750ustar00rootroot00000000000000/********************************************************************* * test_nodehandles_same_namespaces.cpp * * Software License Agreement (BSD License) * * Copyright (c) 2016, University of Patras * All rights reserved. * * 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 University of Patras 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. * * Authors: Aris Synodinos *********************************************************************/ #include #include #include #include #include #include #include TEST(SameNamespaces, NodeletPrivateNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Bool") == 0) { found_topic = true; EXPECT_STREQ("/common_namespace/nodehandle_test/private", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(SameNamespaces, NodeletNamespacedNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Byte") == 0) { found_topic = true; EXPECT_STREQ("/common_namespace/namespaced", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(SameNamespaces, NodeletGlobalNodehandle) { ros::NodeHandle nh; ros::Duration(2).sleep(); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Time") == 0) { found_topic = true; EXPECT_STREQ("/global", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(SameNamespaces, NodePrivateNodehandle) { ros::NodeHandle nh("~"); ros::Publisher pub = nh.advertise("private", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Empty") == 0) { found_topic = true; EXPECT_STREQ("/common_namespace/test_nodehandles/private", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(SameNamespaces, NodeNamespacedNodehandle) { ros::NodeHandle nh; ros::Publisher pub = nh.advertise("namespaced", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/String") == 0) { found_topic = true; EXPECT_STREQ("/common_namespace/namespaced", info.name.c_str()); } } EXPECT_TRUE(found_topic); } TEST(SameNamespaces, NodeGlobalNodehandle) { ros::NodeHandle nh; ros::Publisher pub = nh.advertise("/public", 10); ros::master::V_TopicInfo master_topics; ros::master::getTopics(master_topics); bool found_topic = false; for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) { const ros::master::TopicInfo& info = *it; if (info.datatype.compare("std_msgs/Float32") == 0) { found_topic = true; EXPECT_STREQ("/public", info.name.c_str()); } } EXPECT_TRUE(found_topic); } int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "test_nodehandles_same_namespaces"); return RUN_ALL_TESTS(); } ros-nodelet-core-1.9.16/test_nodelet/test/test_nodehandles_same_namespaces.test000066400000000000000000000005771336731060300301040ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test/test_unload_called_twice.launch000066400000000000000000000001641336731060300266600ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test/test_unload_called_twice.py000077500000000000000000000043241336731060300260430ustar00rootroot00000000000000#!/usr/bin/env python import roslib; roslib.load_manifest('test_nodelet') import rospy import unittest import rostest import signal import subprocess import time from nodelet.srv import * class TestUnloadCalledTwice(unittest.TestCase): def test_unload_called_twice(self): ''' Test that when a nodelet loader is stopped and requests unloading, the unload() call in LoaderROS is not run twice (#50). ''' # start nodelet manager proc_manager = subprocess.Popen(["rosrun", "nodelet", "nodelet", "manager", "__name:=nodelet_manager"], stdout=subprocess.PIPE, stderr=subprocess.PIPE, bufsize=-1 ) # wait for nodelet manager to be ready try: rospy.wait_for_service('/nodelet_manager/load_nodelet', timeout=2) except: self.fail("Could not determine that nodelet manager has started") # load nodelet proc_nodelet = subprocess.Popen(["rosrun", "nodelet", "nodelet", "load", "test_nodelet/Plus", "nodelet_manager", "__name:=test"], stdout=subprocess.PIPE, stderr=subprocess.PIPE ) # wait for nodelet to be ready try: rospy.wait_for_service('test/get_loggers', timeout=2) except: self.fail("Could not determine that nodelet has started") time.sleep(1) # stop the nodelet loader via signal (similar to roslaunch killing it) proc_nodelet.send_signal(signal.SIGINT) (n_out, n_err) = proc_nodelet.communicate() # stop the nodelet manager, too proc_manager.send_signal(signal.SIGINT) (m_out, m_err) = proc_manager.communicate() # check that nodelet unloaded and that LoaderROS::unload() does not # complain about nodelet not being found (an indication that it was called # again after the nodelet was already unloaded) self.assertIn('Unloading nodelet /test from manager nodelet_manager', n_out) self.assertNotIn('Failed to find nodelet with name', m_err) if __name__ == '__main__': rospy.init_node('test_unload_called_twice') rostest.unitrun('test_unload_called_twice', 'test_unload_called_twice', TestUnloadCalledTwice) ros-nodelet-core-1.9.16/test_nodelet/test_loader.launch000066400000000000000000000002741336731060300231700ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test_local.launch000066400000000000000000000020261336731060300230110ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet/test_nodelet.xml000066400000000000000000000015411336731060300227000ustar00rootroot00000000000000 A node to add a value and republish. Test nodelet rosconsole macros. A node that fails to initialize properly. A node that creates public and private nodehandles. ros-nodelet-core-1.9.16/test_nodelet_topic_tools/000077500000000000000000000000001336731060300221025ustar00rootroot00000000000000ros-nodelet-core-1.9.16/test_nodelet_topic_tools/CHANGELOG.rst000066400000000000000000000061041336731060300241240ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package test_nodelet_topic_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.9.16 (2018-04-27) ------------------- 1.9.15 (2018-03-16) ------------------- * use new pluginlib headers (`#73 `_) * Contributors: Mikael Arguedas 1.9.14 (2017-11-15) ------------------- * update to use non deprecated pluginlib macro (`#69 `_) * Contributors: Mikael Arguedas 1.9.13 (2017-10-27) ------------------- 1.9.12 (2017-08-04) ------------------- 1.9.11 (2017-07-27) ------------------- * remove trailing whitespaces (`#62 `_) * switch to package format 2 (`#63 `_) * Test laziness after disconnection (`#60 `_) * Contributors: Kentaro Wada, Mikael Arguedas 1.9.10 (2017-03-27) ------------------- 1.9.9 (2017-02-17) ------------------ 1.9.8 (2016-11-15) ------------------ 1.9.7 (2016-10-24) ------------------ 1.9.6 (2016-09-20) ------------------ * Add NodeletLazy abstract class for lazy transport (`#45 `_) * Add NodeletLazy abstract class for lazy transport * Add test for NodeletLazy with checking its lazy-ness * Fix ROS logging format supporting `ros/ros_comm#875 `_ * Fix ever_subscribed\_ flag setting location * Clearfy the comment describing advertise method * Parameterize the duration to warn the no connection User can disable this feature by setting -1 to the param. * Contributors: Kentaro Wada 1.9.5 (2016-06-22) ------------------ * fix non-isolated build * Contributors: Dirk Thomas 1.9.4 (2016-03-15) ------------------ * update maintainer * Contributors: Mikael Arguedas 1.9.3 (2015-08-05) ------------------ 1.9.2 (2014-10-30) ------------------ 1.9.1 (2014-10-29) ------------------ 1.9.0 (2014-06-16) ------------------ 1.8.3 (2014-05-08) ------------------ * update changelogs * Update maintainer field * Contributors: Dirk Thomas, Esteve Fernandez 1.8.2 (2014-01-07) ------------------ 1.8.0 (2013-07-11) ------------------ * check for CATKIN_ENABLE_TESTING * use EXPORTED_TARGETS variable instead of explicit target names * update email in package.xml 1.7.15 (2013-03-12) ------------------- 1.7.14 (2013-01-13) ------------------- * remove duplicate dep 1.7.13 (2012-12-27) ------------------- * move nodelet_topic_tools to separate package, fix unit tests 1.7.12 (2012-12-19 01:34) ------------------------- 1.7.11 (2012-12-19 00:58) ------------------------- 1.7.10 (2012-12-14) ------------------- 1.7.9 (2012-12-13) ------------------ 1.7.8 (2012-12-06) ------------------ 1.7.7 (2012-11-01) ------------------ 1.7.6 (2012-10-30) ------------------ 1.7.5 (2012-10-23) ------------------ 1.7.4 (2012-10-08) ------------------ 1.7.3 (2012-10-04) ------------------ 1.7.2 (2012-10-03) ------------------ 1.7.1 (2012-10-02) ------------------ 1.7.0 (2012-10-01) ------------------ ros-nodelet-core-1.9.16/test_nodelet_topic_tools/CMakeLists.txt000066400000000000000000000013041336731060300246400ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(test_nodelet_topic_tools) find_package(catkin REQUIRED COMPONENTS message_filters nodelet nodelet_topic_tools pluginlib roscpp rostest) catkin_package( CATKIN_DEPENDS message_filters nodelet nodelet_topic_tools pluginlib roscpp ) if(CATKIN_ENABLE_TESTING) include_directories(SYSTEM ${catkin_INCLUDE_DIRS}) add_library(test_nodelet_topic_tools test/string_nodelet_lazy.cpp test/string_nodelet_throttle.cpp) target_link_libraries(test_nodelet_topic_tools ${catkin_LIBRARIES}) add_dependencies(test_nodelet_topic_tools ${catkin_EXPORTED_TARGETS}) add_rostest(test/test_nodelet_lazy.launch) add_rostest(test/test_nodelet_throttle.launch) endif() ros-nodelet-core-1.9.16/test_nodelet_topic_tools/package.xml000066400000000000000000000021311336731060300242140ustar00rootroot00000000000000 test_nodelet_topic_tools 1.9.16 A package for nodelet_topic_tools unit tests. Mikael Arguedas BSD http://ros.org/wiki/nodelet_topic_tools https://github.com/ros/nodelet_core/issues https://github.com/ros/nodelet_core Radu Bogdan Rusu Tully Foote catkin rostest message_filters nodelet nodelet_topic_tools pluginlib roscpp std_msgs rospy ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/000077500000000000000000000000001336731060300230615ustar00rootroot00000000000000ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/empty_string_publisher.py000077500000000000000000000044421336731060300302430ustar00rootroot00000000000000#!/usr/bin/env python ############################################################################### # Software License Agreement (BSD License) # # Copyright (c) 2016, JSK Lab, University of Tokyo. # All rights reserved. # # 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/o2r other materials provided # with the distribution. # * Neither the name of the JSK Lab 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. ############################################################################### __author__ = 'Kentaro Wada ' import rospy from std_msgs.msg import String class EmptyStringPublisher(object): def __init__(self): self.pub = rospy.Publisher('~output', String, queue_size=1) self.timer_pub = rospy.Timer( rospy.Duration(0.1), self.publish_callback) def publish_callback(self, event): self.pub.publish(String()) if __name__ == '__main__': rospy.init_node('empty_string_publisher') EmptyStringPublisher() rospy.spin() ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/string_nodelet_lazy.cpp000066400000000000000000000052531336731060300276510ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2016, JSK Lab, University of Tokyo. * All rights reserved. * * 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/o2r other materials provided * with the distribution. * * Neither the name of the JSK Lab 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. *********************************************************************/ /* Author: Kentaro Wada */ #include #include namespace test_nodelet_topic_tools { class NodeletLazyString: public nodelet_topic_tools::NodeletLazy { public: protected: virtual void onInit() { nodelet_topic_tools::NodeletLazy::onInit(); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); } virtual void subscribe() { sub_ = pnh_->subscribe("input", 1, &NodeletLazyString::callback, this); } virtual void unsubscribe() { sub_.shutdown(); } virtual void callback(const std_msgs::String::ConstPtr& msg) { pub_.publish(msg); } ros::Publisher pub_; ros::Subscriber sub_; private: }; } // namespace test_nodelet_topic_tools #include PLUGINLIB_EXPORT_CLASS(test_nodelet_topic_tools::NodeletLazyString, nodelet::Nodelet); ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/string_nodelet_throttle.cpp000066400000000000000000000005241336731060300305330ustar00rootroot00000000000000#include #include #include namespace test_nodelet_topic_tools { typedef nodelet_topic_tools::NodeletThrottle NodeletThrottleString; } PLUGINLIB_EXPORT_CLASS(test_nodelet_topic_tools::NodeletThrottleString, nodelet::Nodelet) ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_lazy.py000077500000000000000000000101661336731060300254600ustar00rootroot00000000000000#!/usr/bin/env python ############################################################################### # Software License Agreement (BSD License) # # Copyright (c) 2016, JSK Lab, University of Tokyo. # All rights reserved. # # 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/o2r other materials provided # with the distribution. # * Neither the name of the JSK Lab 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. ############################################################################### __author__ = 'Kentaro Wada ' import os import sys import unittest import rosgraph import rospy import rosmsg import roslib PKG = 'test_nodelet_topic_tools' NAME = 'test_lazy' class TestConnection(unittest.TestCase): def __init__(self, *args): super(TestConnection, self).__init__(*args) rospy.init_node(NAME) self.master = rosgraph.Master(NAME) def test_no_subscribers(self): check_connected_topics = rospy.get_param('~check_connected_topics') # Check assumed topics are not there _, subscriptions, _ = self.master.getSystemState() for check_topic in check_connected_topics: for topic, sub_node in subscriptions: if topic == rospy.get_namespace() + check_topic: raise ValueError('Found topic: {}'.format(check_topic)) def test_subscriber_appears(self): topic_type = rospy.get_param('~input_topic_type') check_connected_topics = rospy.get_param('~check_connected_topics') wait_time = rospy.get_param('~wait_for_connection', 0) msg_class = roslib.message.get_message_class(topic_type) # Subscribe topic and bond connection sub = rospy.Subscriber('~input', msg_class, self._cb_test_subscriber_appears) print('Waiting for connection for {} sec.'.format(wait_time)) rospy.sleep(wait_time) # Check assumed topics are there _, subscriptions, _ = self.master.getSystemState() for check_topic in check_connected_topics: for topic, sub_node in subscriptions: if topic == rospy.get_namespace() + check_topic: break else: raise ValueError('Not found topic: {}'.format(check_topic)) sub.unregister() rospy.sleep(1) # wait for disconnection # Check specified topics do not exist _, subscriptions, _ = self.master.getSystemState() for check_topic in check_connected_topics: for topic, sub_node in subscriptions: if topic == rospy.get_namespace() + check_topic: raise ValueError('Found topic: {}'.format(check_topic)) def _cb_test_subscriber_appears(self, msg): pass if __name__ == "__main__": import rostest rostest.rosrun(PKG, NAME, TestConnection) ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_nodelet_lazy.launch000066400000000000000000000024611336731060300300100ustar00rootroot00000000000000 input_topic_type: std_msgs/String check_connected_topics: [string_nodelet_lazy_0/output, string_nodelet_lazy_1/output] wait_for_connection: 3 ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_nodelet_throttle.launch000066400000000000000000000006541336731060300307000ustar00rootroot00000000000000 ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_nodelets.xml000066400000000000000000000010621336731060300264560ustar00rootroot00000000000000 Throttle strings in nodelet (testing only). Lazy transport strings in nodelet (testing only). ros-nodelet-core-1.9.16/test_nodelet_topic_tools/test/test_throttle.py000077500000000000000000000017641336731060300263520ustar00rootroot00000000000000#!/usr/bin/env python PKG = 'nodelet_topic_tools' import roslib; roslib.load_manifest(PKG) import unittest import threading import rospy from std_msgs.msg import String class TestNodeletThrottle(unittest.TestCase): def __init__(self, *args): super(TestNodeletThrottle, self).__init__(*args) self._lock = threading.RLock() self._msgs_rec = 0 self._pub = rospy.Publisher('string_in', String) self._sub = rospy.Subscriber('string_out', String, self._cb) def _cb(self, msg): with self._lock: self._msgs_rec += 1 def test_nodelet_throttle(self): for i in range(0,10): self._pub.publish(String('hello, world')) rospy.sleep(1.0) self.assert_(self._msgs_rec > 0, "No messages received from nodelet throttle on topic \"string_out\"") if __name__ == '__main__': rospy.init_node('test_nodelet_throttle') import rostest rostest.rosrun(PKG, 'test_nodelet_throttle', TestNodeletThrottle)