#include <gtest/gtest.h>#include <ros/callback_queue.h>#include <ros/console.h>#include <ros/message_deserializer.h>#include <ros/subscription_queue.h>#include <ros/subscription_callback_helper.h>#include <ros/timer.h>#include <boost/atomic.hpp>#include <boost/shared_ptr.hpp>#include <boost/bind.hpp>#include <boost/thread.hpp>#include <boost/function.hpp>#include "fake_message.h"
Go to the source code of this file.
Classes | |
| class | CallbackQueueParamTest |
| class | ConditionObject |
| class | CountingCallback |
| class | CountingSubscriptionQueue |
| class | ros::NodeHandle |
| class | RaceConditionCallback |
| class | RecursiveCallback |
| class | SelfRemovingCallback |
| struct | ThreadedCallOneSlowParams |
| class | TimerRecursionCallback |
Namespaces | |
| ros | |
Typedefs | |
| typedef boost::shared_ptr< CountingCallback > | CountingCallbackPtr |
| typedef boost::shared_ptr< CountingSubscriptionQueue > | CountingSubscriptionQueuePtr |
| typedef boost::shared_ptr< RecursiveCallback > | RecursiveCallbackPtr |
| typedef boost::shared_ptr< SelfRemovingCallback > | SelfRemovingCallbackPtr |
| typedef boost::shared_ptr< TimerRecursionCallback > | TimerRecursionCallbackPtr |
Variables | |
| CallbackQueueInterface * | recursiveTimerQueue |
Definition at line 72 of file test_callback_queue.cpp.
Definition at line 378 of file test_callback_queue.cpp.
Definition at line 216 of file test_callback_queue.cpp.
Definition at line 162 of file test_callback_queue.cpp.
Definition at line 517 of file test_callback_queue.cpp.
| void callAvailableThread | ( | CallbackQueue * | queue, |
| bool & | done, | ||
| boost::atomic< size_t > * | num_calls, | ||
| ros::WallDuration | call_timeout = ros::WallDuration(0.1) |
||
| ) |
Definition at line 266 of file test_callback_queue.cpp.
| void callOneThread | ( | CallbackQueue * | queue, |
| bool & | done, | ||
| boost::atomic< size_t > * | num_calls, | ||
| ros::WallDuration | timeout = ros::WallDuration(0.1) |
||
| ) |
Definition at line 335 of file test_callback_queue.cpp.
| void dummyTimer | ( | const ros::TimerEvent & | ) |
Definition at line 480 of file test_callback_queue.cpp.
| INSTANTIATE_TEST_CASE_P | ( | slow | , |
| CallbackQueueParamTest | , | ||
| ::testing::Values(ThreadedCallOneSlowParams{ros::WallDuration(1.0), 10, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0)}, ThreadedCallOneSlowParams{ros::WallDuration(1.0), 10, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0.1)}, ThreadedCallOneSlowParams{ros::WallDuration(1.0), 10, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0.001)}, ThreadedCallOneSlowParams{ros::WallDuration(0.1), 10, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0)}, ThreadedCallOneSlowParams{ros::WallDuration(0.001), 10, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0)}, ThreadedCallOneSlowParams{ros::WallDuration(1.0), 1, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0)}, ThreadedCallOneSlowParams{ros::WallDuration(1.0), 2, ros::WallDuration(0.1), ros::WallDuration(2), ros::WallDuration(0)}) | |||
| ) |
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 621 of file test_callback_queue.cpp.
| void recursiveTimer | ( | const ros::TimerEvent & | ) |
Definition at line 486 of file test_callback_queue.cpp.
| size_t runThreadedTest | ( | const CallbackInterfacePtr & | cb, |
| const boost::function< void(CallbackQueue *, bool &, boost::atomic< size_t > *, ros::WallDuration)> & | threadFunc, | ||
| size_t * | num_calls = NULL, |
||
| size_t | num_threads = 10, |
||
| ros::WallDuration | duration = ros::WallDuration(5), |
||
| ros::WallDuration | pause_between_callbacks = ros::WallDuration(0), |
||
| ros::WallDuration | call_one_timeout = ros::WallDuration(0.1) |
||
| ) |
Definition at line 283 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| singleCallback | |||
| ) |
Definition at line 74 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| multipleCallbacksCallAvailable | |||
| ) |
Definition at line 95 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| multipleCallbacksCallOne | |||
| ) |
Definition at line 109 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| remove | |||
| ) |
Definition at line 125 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| removeSelf | |||
| ) |
Definition at line 164 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| recursive1 | |||
| ) |
Definition at line 218 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| recursive2 | |||
| ) |
Definition at line 230 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| recursive3 | |||
| ) |
Definition at line 242 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| recursive4 | |||
| ) |
Definition at line 254 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| threadedCallAvailable | |||
| ) |
Definition at line 327 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| threadedCallOne | |||
| ) |
Definition at line 352 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| recursiveTimer | |||
| ) |
Definition at line 519 of file test_callback_queue.cpp.
| TEST | ( | CallbackQueue | , |
| raceConditionCallback | |||
| ) |
Definition at line 596 of file test_callback_queue.cpp.
| TEST_P | ( | CallbackQueueParamTest | , |
| threadedCallOneSlow | |||
| ) |
Definition at line 391 of file test_callback_queue.cpp.
| CallbackQueueInterface* recursiveTimerQueue |
Definition at line 484 of file test_callback_queue.cpp.