45 #include <gtest/gtest.h>
49 #include <boost/thread.hpp>
62 ros::init(argc_, argv_, "test_spinners"); \
64 ros::WallTimer t = nh.createWallTimer(ros::WallDuration(2.0), \
76 boost::thread th(boost::bind(&
ros::spin));
79 EXPECT_THROW(
ros::spin(), std::runtime_error);
82 EXPECT_THROW(
ros::spin(ss), std::runtime_error);
83 EXPECT_THROW(ss.
spin(), std::runtime_error);
86 EXPECT_THROW(
ros::spin(ms), std::runtime_error);
87 EXPECT_THROW(ms.
spin(), std::runtime_error);
90 EXPECT_THROW(as.
start(), std::runtime_error);
99 boost::thread th(boost::bind(&
ros::spin, ss));
102 EXPECT_THROW(
ros::spin(), std::runtime_error);
105 EXPECT_THROW(
ros::spin(ss2), std::runtime_error);
106 EXPECT_THROW(ss2.
spin(), std::runtime_error);
109 EXPECT_THROW(
ros::spin(ms), std::runtime_error);
110 EXPECT_THROW(ms.
spin(), std::runtime_error);
113 EXPECT_THROW(as.
start(), std::runtime_error);
129 boost::thread th(boost::bind(&
ros::spin, ms));
133 EXPECT_THROW(
ros::spin(ss2), std::runtime_error);
134 EXPECT_THROW(ss2.
spin(), std::runtime_error);
153 EXPECT_THROW(
ros::spin(ss), std::runtime_error);
154 EXPECT_THROW(ss.
spin(), std::runtime_error);
167 testing::InitGoogleTest(&argc, argv);
170 return RUN_ALL_TESTS();