35 #include <gmock/gmock.h>
37 using ::testing::StrictMock;
39 using ::testing::DoAll;
40 using ::testing::InvokeWithoutArgs;
41 using ::testing::Return;
61 TEST(ControllerBaseAPI, DefaultStateTest)
63 StrictMock<ControllerMock> controller;
65 ASSERT_FALSE(controller.isInitialized());
66 ASSERT_FALSE(controller.isRunning());
67 ASSERT_FALSE(controller.isStopped());
68 ASSERT_FALSE(controller.isWaiting());
69 ASSERT_FALSE(controller.isAborted());
72 TEST(ControllerBaseAPI, IsInitializedTest)
74 StrictMock<ControllerMock> controller;
81 EXPECT_CALL(controller, initRequest(_, _, _, _))
87 ASSERT_FALSE(controller.isInitialized());
89 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
90 ASSERT_TRUE(controller.isInitialized());
93 TEST(ControllerBaseAPI, IsRunningTest)
95 StrictMock<ControllerMock> controller;
102 EXPECT_CALL(controller, starting(_)).Times(1);
103 EXPECT_CALL(controller, stopping(_)).Times(1);
104 EXPECT_CALL(controller, initRequest(_, _, _, _))
110 ASSERT_FALSE(controller.isRunning());
112 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
113 ASSERT_TRUE(controller.startRequest(time));
114 ASSERT_TRUE(controller.isRunning());
116 ASSERT_TRUE(controller.stopRequest(time));
117 ASSERT_FALSE(controller.isRunning());
120 TEST(ControllerBaseAPI, IsStoppedTest)
122 StrictMock<ControllerMock> controller;
129 EXPECT_CALL(controller, starting(_)).Times(1);
130 EXPECT_CALL(controller, stopping(_)).Times(1);
131 EXPECT_CALL(controller, initRequest(_, _, _, _))
137 ASSERT_FALSE(controller.isStopped());
139 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
140 ASSERT_TRUE(controller.stopRequest(time));
141 ASSERT_TRUE(controller.isStopped());
143 ASSERT_TRUE(controller.startRequest(time));
144 ASSERT_FALSE(controller.isStopped());
147 TEST(ControllerBaseAPI, IsWaitingTest)
149 StrictMock<ControllerMock> controller;
156 EXPECT_CALL(controller, starting(_)).Times(1);
157 EXPECT_CALL(controller, waiting(_)).Times(1);
158 EXPECT_CALL(controller, initRequest(_, _, _, _))
164 ASSERT_FALSE(controller.isWaiting());
166 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
167 ASSERT_TRUE(controller.waitRequest(time));
168 ASSERT_TRUE(controller.isWaiting());
170 ASSERT_TRUE(controller.startRequest(time));
171 ASSERT_FALSE(controller.isWaiting());
174 TEST(ControllerBaseAPI, StartRequestTest)
176 StrictMock<ControllerMock> controller;
183 EXPECT_CALL(controller, starting(_)).Times(2);
184 EXPECT_CALL(controller, initRequest(_, _, _, _))
190 ASSERT_FALSE(controller.startRequest(time));
192 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
193 ASSERT_TRUE(controller.startRequest(time));
196 ASSERT_TRUE(controller.startRequest(time));
199 TEST(ControllerBaseAPI, StopRequestTest)
201 StrictMock<ControllerMock> controller;
208 EXPECT_CALL(controller, stopping(_)).Times(2);
209 EXPECT_CALL(controller, initRequest(_, _, _, _))
215 ASSERT_FALSE(controller.stopRequest(time));
217 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
218 ASSERT_TRUE(controller.stopRequest(time));
221 ASSERT_TRUE(controller.stopRequest(time));
224 TEST(ControllerBaseAPI, WaitRequestTest)
226 StrictMock<ControllerMock> controller;
233 EXPECT_CALL(controller, waiting(_)).Times(2);
234 EXPECT_CALL(controller, initRequest(_, _, _, _))
240 ASSERT_FALSE(controller.waitRequest(time));
242 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
243 ASSERT_TRUE(controller.waitRequest(time));
246 ASSERT_TRUE(controller.waitRequest(time));
249 TEST(ControllerBaseAPI, AbortRequestTest)
251 StrictMock<ControllerMock> controller;
258 EXPECT_CALL(controller, aborting(_)).Times(2);
259 EXPECT_CALL(controller, initRequest(_, _, _, _))
265 ASSERT_FALSE(controller.abortRequest(time));
267 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
268 ASSERT_TRUE(controller.abortRequest(time));
271 ASSERT_TRUE(controller.abortRequest(time));
274 TEST(ControllerBaseAPI, UpdateRequestTest)
276 StrictMock<ControllerMock> controller;
284 EXPECT_CALL(controller, starting(_)).Times(1);
285 EXPECT_CALL(controller,
update(_, _)).Times(1);
286 EXPECT_CALL(controller, initRequest(_, _, _, _))
292 controller.updateRequest(time, period);
294 ASSERT_TRUE(controller.initRequest(robot_hw, *node_handle, *node_handle, resources));
295 ASSERT_TRUE(controller.startRequest(time));
297 controller.updateRequest(time, period);
300 int main(
int argc,
char** argv)
302 testing::InitGoogleTest(&argc, argv);
304 int ret = RUN_ALL_TESTS();