Classes | Namespaces | Typedefs | Functions | Variables
test_callback_queue.cpp File Reference
#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/bind.hpp>
#include <boost/thread.hpp>
#include <boost/function.hpp>
#include "fake_message.h"
Include dependency graph for test_callback_queue.cpp:

Go to the source code of this file.

Classes

class  BlockingCallback
 
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< BlockingCallbackBlockingCallbackPtr
 
typedef boost::shared_ptr< CountingCallbackCountingCallbackPtr
 
typedef boost::shared_ptr< CountingSubscriptionQueueCountingSubscriptionQueuePtr
 
typedef boost::shared_ptr< RecursiveCallbackRecursiveCallbackPtr
 
typedef boost::shared_ptr< SelfRemovingCallbackSelfRemovingCallbackPtr
 
typedef boost::shared_ptr< TimerRecursionCallbackTimerRecursionCallbackPtr
 

Functions

void callAvailableThread (CallbackQueue *queue, bool &done, boost::atomic< size_t > *num_calls, ros::WallDuration call_timeout=ros::WallDuration(0.1))
 
void callOneThread (CallbackQueue *queue, bool &done, boost::atomic< size_t > *num_calls, ros::WallDuration timeout=ros::WallDuration(0.1))
 
void dummyTimer (const ros::TimerEvent &)
 
 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)
 
void recursiveTimer (const ros::TimerEvent &)
 
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))
 
 TEST (CallbackQueue, multipleCallbacksCallAvailable)
 
 TEST (CallbackQueue, multipleCallbacksCallOne)
 
 TEST (CallbackQueue, raceConditionCallback)
 
 TEST (CallbackQueue, recursive1)
 
 TEST (CallbackQueue, recursive2)
 
 TEST (CallbackQueue, recursive3)
 
 TEST (CallbackQueue, recursive4)
 
 TEST (CallbackQueue, recursiveTimer)
 
 TEST (CallbackQueue, remove)
 
 TEST (CallbackQueue, removeCallbackWhileExecuting)
 
 TEST (CallbackQueue, removeSelf)
 
 TEST (CallbackQueue, singleCallback)
 
 TEST (CallbackQueue, threadedCallAvailable)
 
 TEST (CallbackQueue, threadedCallOne)
 
 TEST_P (CallbackQueueParamTest, threadedCallOneSlow)
 

Variables

CallbackQueueInterfacerecursiveTimerQueue
 

Typedef Documentation

◆ BlockingCallbackPtr

Definition at line 219 of file test_callback_queue.cpp.

◆ CountingCallbackPtr

Definition at line 72 of file test_callback_queue.cpp.

◆ CountingSubscriptionQueuePtr

Definition at line 450 of file test_callback_queue.cpp.

◆ RecursiveCallbackPtr

Definition at line 305 of file test_callback_queue.cpp.

◆ SelfRemovingCallbackPtr

Definition at line 180 of file test_callback_queue.cpp.

◆ TimerRecursionCallbackPtr

Definition at line 589 of file test_callback_queue.cpp.

Function Documentation

◆ callAvailableThread()

void callAvailableThread ( CallbackQueue queue,
bool &  done,
boost::atomic< size_t > *  num_calls,
ros::WallDuration  call_timeout = ros::WallDuration(0.1) 
)

Definition at line 74 of file test_callback_queue.cpp.

◆ callOneThread()

void callOneThread ( CallbackQueue queue,
bool &  done,
boost::atomic< size_t > *  num_calls,
ros::WallDuration  timeout = ros::WallDuration(0.1) 
)

Definition at line 407 of file test_callback_queue.cpp.

◆ dummyTimer()

void dummyTimer ( const ros::TimerEvent )

Definition at line 552 of file test_callback_queue.cpp.

◆ INSTANTIATE_TEST_CASE_P()

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 693 of file test_callback_queue.cpp.

◆ recursiveTimer()

void recursiveTimer ( const ros::TimerEvent )

Definition at line 558 of file test_callback_queue.cpp.

◆ runThreadedTest()

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 355 of file test_callback_queue.cpp.

◆ TEST() [1/14]

TEST ( CallbackQueue  ,
multipleCallbacksCallAvailable   
)

Definition at line 113 of file test_callback_queue.cpp.

◆ TEST() [2/14]

TEST ( CallbackQueue  ,
multipleCallbacksCallOne   
)

Definition at line 127 of file test_callback_queue.cpp.

◆ TEST() [3/14]

TEST ( CallbackQueue  ,
raceConditionCallback   
)

Definition at line 668 of file test_callback_queue.cpp.

◆ TEST() [4/14]

TEST ( CallbackQueue  ,
recursive1   
)

Definition at line 307 of file test_callback_queue.cpp.

◆ TEST() [5/14]

TEST ( CallbackQueue  ,
recursive2   
)

Definition at line 319 of file test_callback_queue.cpp.

◆ TEST() [6/14]

TEST ( CallbackQueue  ,
recursive3   
)

Definition at line 331 of file test_callback_queue.cpp.

◆ TEST() [7/14]

TEST ( CallbackQueue  ,
recursive4   
)

Definition at line 343 of file test_callback_queue.cpp.

◆ TEST() [8/14]

TEST ( CallbackQueue  ,
recursiveTimer   
)

Definition at line 591 of file test_callback_queue.cpp.

◆ TEST() [9/14]

TEST ( CallbackQueue  ,
remove   
)

Definition at line 143 of file test_callback_queue.cpp.

◆ TEST() [10/14]

TEST ( CallbackQueue  ,
removeCallbackWhileExecuting   
)

Definition at line 223 of file test_callback_queue.cpp.

◆ TEST() [11/14]

TEST ( CallbackQueue  ,
removeSelf   
)

Definition at line 182 of file test_callback_queue.cpp.

◆ TEST() [12/14]

TEST ( CallbackQueue  ,
singleCallback   
)

Definition at line 92 of file test_callback_queue.cpp.

◆ TEST() [13/14]

TEST ( CallbackQueue  ,
threadedCallAvailable   
)

Definition at line 399 of file test_callback_queue.cpp.

◆ TEST() [14/14]

TEST ( CallbackQueue  ,
threadedCallOne   
)

Definition at line 424 of file test_callback_queue.cpp.

◆ TEST_P()

TEST_P ( CallbackQueueParamTest  ,
threadedCallOneSlow   
)

Definition at line 463 of file test_callback_queue.cpp.

Variable Documentation

◆ recursiveTimerQueue

CallbackQueueInterface* recursiveTimerQueue

Definition at line 556 of file test_callback_queue.cpp.



test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Tue May 20 2025 03:00:30