1 #include <gtest/gtest.h>
2 #include <gmock/gmock.h>
6 #include <mbf_abstract_nav/MoveBaseFlexConfig.h>
9 #include <geometry_msgs/PoseStamped.h>
10 #include <geometry_msgs/TwistStamped.h>
11 #include <geometry_msgs/Twist.h>
13 #include <geometry_msgs/TransformStamped.h>
18 using geometry_msgs::PoseStamped;
19 using geometry_msgs::TransformStamped;
20 using geometry_msgs::Twist;
21 using geometry_msgs::TwistStamped;
24 using mbf_abstract_nav::MoveBaseFlexConfig;
26 using testing::Return;
32 typedef std::vector<PoseStamped>
plan_t;
52 TF_PTR, MoveBaseFlexConfig{})
77 waitForStateUpdate(boost::chrono::seconds(1));
78 ASSERT_EQ(getState(), NO_PLAN);
87 setNewPlan(
plan_t{},
true, 1, 1);
93 waitForStateUpdate(boost::chrono::seconds(1));
94 ASSERT_EQ(getState(), EMPTY_PLAN);
104 EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(
false));
107 setNewPlan(plan,
true, 1, 1);
110 ASSERT_TRUE(
start());
113 waitForStateUpdate(boost::chrono::seconds(1));
114 ASSERT_EQ(getState(), INVALID_PLAN);
124 EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(
true));
128 setNewPlan(plan,
true, 1, 1);
131 global_frame_ =
"global_frame";
132 robot_frame_ =
"not_global_frame";
135 ASSERT_TRUE(
start());
139 waitForStateUpdate(boost::chrono::seconds(2));
140 ASSERT_EQ(getState(), INTERNAL_ERROR);
157 TransformStamped transform;
161 transform.transform.rotation.w = 1;
164 TF_PTR->setTransform(transform,
"mama");
175 EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(
true));
176 EXPECT_CALL(mock, isGoalReached(_, _)).WillOnce(Return(
true));
180 plan.back().header.frame_id = global_frame_;
181 plan.back().pose.orientation.w = 1;
184 setNewPlan(plan,
true, 1e-3, 1e-3);
187 ASSERT_TRUE(
start());
190 waitForStateUpdate(boost::chrono::seconds(1));
191 ASSERT_EQ(getState(), ARRIVED_GOAL);
196 throw std::runtime_error(
"Oh no! Controller throws an Exception");
204 EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(
true));
205 EXPECT_CALL(mock, isGoalReached(_, _)).WillOnce(Return(
false));
206 EXPECT_CALL(mock, computeVelocityCommands(_, _, _, _)).WillOnce(ControllerException());
210 setNewPlan(plan,
true, 1e-3, 1e-3);
213 ASSERT_TRUE(
start());
216 waitForStateUpdate(boost::chrono::seconds(1));
217 ASSERT_EQ(getState(), INTERNAL_ERROR);
228 EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(
true));
229 EXPECT_CALL(mock, isGoalReached(_, _)).WillRepeatedly(Return(
false));
230 EXPECT_CALL(mock, computeVelocityCommands(_, _, _, _)).WillRepeatedly(Return(11));
250 ASSERT_TRUE(
start());
253 waitForStateUpdate(boost::chrono::seconds(1));
254 ASSERT_EQ(getState(), NO_LOCAL_CMD);
258 waitForStateUpdate(boost::chrono::seconds(1));
259 ASSERT_EQ(getState(), MAX_RETRIES);
270 ASSERT_TRUE(
start());
273 waitForStateUpdate(boost::chrono::seconds(1));
274 ASSERT_EQ(getState(), NO_LOCAL_CMD);
287 ASSERT_TRUE(
start());
290 waitForStateUpdate(boost::chrono::seconds(1));
291 ASSERT_EQ(getState(), PAT_EXCEEDED);
294 int main(
int argc,
char** argv)
304 TF_PTR->setUsingDedicatedThread(
true);
311 testing::InitGoogleTest(&argc, argv);
312 return RUN_ALL_TESTS();