Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045 #include <gtest/gtest.h>
00046 #include "ros/spinner.h"
00047 #include "ros/init.h"
00048 #include "ros/node_handle.h"
00049 #include <boost/thread.hpp>
00050
00051 using namespace ros;
00052
00053 int argc_;
00054 char** argv_;
00055
00056 void fire_shutdown(const ros::WallTimerEvent& event) {
00057 ROS_INFO("Asking for shutdown");
00058 ros::shutdown();
00059 }
00060
00061 #define DOIT() \
00062 ros::init(argc_, argv_, "test_spinners"); \
00063 NodeHandle nh; \
00064 ros::WallTimer t = nh.createWallTimer(ros::WallDuration(2.0), \
00065 &fire_shutdown); \
00066
00067 TEST(Spinners, spin)
00068 {
00069 DOIT();
00070 ros::spin();
00071 }
00072
00073 TEST(Spinners, spinfail)
00074 {
00075 DOIT();
00076 boost::thread th(boost::bind(&ros::spin));
00077 ros::spin();
00078 }
00079
00080 TEST(Spinners, single)
00081 {
00082 DOIT();
00083 SingleThreadedSpinner s;
00084 ros::spin(s);
00085 }
00086
00087 TEST(Spinners, singlefail)
00088 {
00089 DOIT();
00090 boost::thread th(boost::bind(&ros::spin));
00091 SingleThreadedSpinner s;
00092 ros::spin(s);
00093 }
00094
00095 TEST(Spinners, singlefail2)
00096 {
00097 DOIT();
00098 SingleThreadedSpinner s;
00099 boost::thread th(boost::bind(&ros::spin, s));
00100 ros::spin(s);
00101 }
00102
00103 TEST(Spinners, multi)
00104 {
00105 DOIT();
00106 MultiThreadedSpinner s;
00107 ros::spin(s);
00108 }
00109
00110 TEST(Spinners, multifail)
00111 {
00112 DOIT();
00113 boost::thread th(boost::bind(&ros::spin));
00114 MultiThreadedSpinner s;
00115 ros::spin(s);
00116 }
00117
00118 TEST(Spinners, multifail2)
00119 {
00120 DOIT();
00121 MultiThreadedSpinner s;
00122 boost::thread th(boost::bind(&ros::spin, s));
00123 ros::spin(s);
00124 }
00125
00126 TEST(Spinners, async)
00127 {
00128 DOIT();
00129 AsyncSpinner s(2);
00130 s.start();
00131 ros::waitForShutdown();
00132 }
00133
00134 TEST(Spinners, asyncfail)
00135 {
00136 DOIT();
00137 boost::thread th(boost::bind(&ros::spin));
00138 AsyncSpinner s(2);
00139 s.start();
00140 ros::waitForShutdown();
00141 }
00142
00143
00144 int
00145 main(int argc, char** argv)
00146 {
00147 testing::InitGoogleTest(&argc, argv);
00148 argc_ = argc;
00149 argv_ = argv;
00150 return RUN_ALL_TESTS();
00151 }
00152
00153
roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Dec 28 2013 17:35:52