test/abstract_planner_execution.cpp
Go to the documentation of this file.
1 #include <gmock/gmock.h>
2 #include <gtest/gtest.h>
3 #include <ros/ros.h>
4 
7 
8 // too long namespaces...
9 using geometry_msgs::PoseStamped;
11 
12 // mocked version of a planner
13 // we will control the output of it
15 {
16  MOCK_METHOD6(makePlan, uint32_t(const PoseStamped&, const PoseStamped&, double, std::vector<PoseStamped>&, double&,
17  std::string&));
18 
19  MOCK_METHOD0(cancel, bool());
20 };
21 
23 using mbf_abstract_nav::MoveBaseFlexConfig;
24 using testing::_;
25 using testing::Return;
26 using testing::Test;
27 
28 // setup the test-fixture
30 {
31  PoseStamped pose; // dummy pose to call start
32 
34  : AbstractPlannerExecution("foo", AbstractPlanner::Ptr{ new AbstractPlannerMock() }, TFPtr(), MoveBaseFlexConfig{})
35  {
36  }
37 
38  void TearDown() override
39  {
40  // we have to stop the thread when the test is done
41  join();
42  }
43 };
44 
46 {
47  // the good case - we succeed
48  // setup the expectation
49  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
50  EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).WillOnce(Return(0));
51 
52  // call and wait
53  ASSERT_TRUE(start(pose, pose, 0));
54 
55  // check result
56  ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
57  ASSERT_EQ(getState(), FOUND_PLAN);
58 }
59 
60 ACTION_P(Wait, cv)
61 {
62  boost::mutex m;
63  boost::unique_lock<boost::mutex> lock(m);
64  cv->wait(lock);
65  return 11;
66 }
67 
69 {
70  // the cancel case. we simulate that we cancel the execution
71  // setup the expectation
72  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
73  boost::condition_variable cv;
74  // makePlan may or may not be called
75  ON_CALL(mock, makePlan(_, _, _, _, _, _)).WillByDefault(Wait(&cv));
76  EXPECT_CALL(mock, cancel()).Times(1).WillOnce(Return(true));
77 
78  // now call the method
79  ASSERT_TRUE(start(pose, pose, 0));
80  ASSERT_TRUE(cancel());
81 
82  // wake up run-thread
83  cv.notify_all();
84 
85  // check result
86  waitForStateUpdate(boost::chrono::seconds(1));
87  ASSERT_EQ(getState(), CANCELED);
88 }
89 
91 {
92  // we expect that if the planner fails for max_retries times, that
93  // the class returns MAX_RETRIES
94 
95  // configure the class
96  MoveBaseFlexConfig config;
97  config.planner_max_retries = 5;
98  config.planner_patience = 100; // set a high patience
99  reconfigure(config);
100 
101  // setup the expectations
102  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
103 
104  EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(config.planner_max_retries + 1).WillRepeatedly(Return(11));
105 
106  // call and wait
107  ASSERT_TRUE(start(pose, pose, 0));
108 
109  // check result
110  ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
111  ASSERT_EQ(getState(), MAX_RETRIES);
112 }
113 
115 {
116  // if no retries and no patience are configured, we return NO_PLAN_FOUND on
117  // planner failure
118 
119  // configure the class
120  MoveBaseFlexConfig config;
121  config.planner_max_retries = 0;
122  config.planner_patience = 0;
123  reconfigure(config);
124 
125  // setup the expectations
126  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
127  EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(1).WillOnce(Return(11));
128 
129  // call and wait
130  ASSERT_TRUE(start(pose, pose, 0));
131 
132  // check result
133  ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
134  ASSERT_EQ(getState(), NO_PLAN_FOUND);
135 }
136 
137 using testing::DoAll;
138 using testing::SetArgReferee;
139 
141 {
142  // simulate the case when the planner returns zero cost
143  std::vector<geometry_msgs::PoseStamped> plan(4);
144  for (size_t ii = 0; ii != plan.size(); ++ii)
145  plan.at(ii).pose.position.x = ii;
146  double cost = 0;
147 
148  // call the planner
149  // the good case - we succeed
150  // setup the expectation
151  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
152  EXPECT_CALL(mock, makePlan(_, _, _, _, _, _))
153  .WillOnce(DoAll(SetArgReferee<3>(plan), SetArgReferee<4>(cost), Return(0)));
154 
155  // call and wait
156  ASSERT_TRUE(start(pose, pose, 0));
157 
158  // check result
159  ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
160  ASSERT_EQ(getState(), FOUND_PLAN);
161  ASSERT_EQ(getCost(), 3);
162 }
163 
165 {
166  // if no retries and no patience are configured, we return NO_PLAN_FOUND on
167  // planner failure
168 
169  // configure the class
170  MoveBaseFlexConfig config;
171  config.planner_max_retries = 0;
172  config.planner_patience = 0.1;
173  reconfigure(config);
174 
175  // setup the expectations
176  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
177  boost::condition_variable cv;
178  EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(1).WillOnce(Wait(&cv));
179 
180  // call and wait
181  ASSERT_TRUE(start(pose, pose, 0));
182 
183  // wait for the patience to elapse
184  boost::this_thread::sleep_for(boost::chrono::milliseconds{ 200 });
185  cv.notify_all();
186 
187  // check result
188  waitForStateUpdate(boost::chrono::seconds(1));
189  ASSERT_EQ(getState(), PAT_EXCEEDED);
190 }
191 
192 ACTION(ThrowException)
193 {
194  throw std::runtime_error("bad planner");
195 }
196 
198 {
199  // if we throw an exception, we expect that we can recover from it
200  // setup the expectations
201  AbstractPlannerMock& mock = dynamic_cast<AbstractPlannerMock&>(*planner_);
202  EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(1).WillOnce(ThrowException());
203 
204  // call and wait
205  ASSERT_TRUE(start(pose, pose, 0));
206 
207  // check result
208  ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
209  ASSERT_EQ(getState(), INTERNAL_ERROR);
210 }
211 
212 int main(int argc, char** argv)
213 {
214  ros::init(argc, argv, "read_types");
215  ros::NodeHandle nh;
216  // suppress the logging since we don't want warnings to polute the test-outcome
218  {
220  }
221  testing::InitGoogleTest(&argc, argv);
222  return RUN_ALL_TESTS();
223 }
mbf_abstract_nav::AbstractExecutionBase::join
void join()
Definition: src/abstract_execution_base.cpp:76
ACTION_P
ACTION_P(Wait, cv)
Definition: test/abstract_planner_execution.cpp:60
mbf_abstract_core::AbstractPlanner::cancel
virtual bool cancel()=0
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
AbstractPlannerMock::MOCK_METHOD0
MOCK_METHOD0(cancel, bool())
AbstractPlannerExecutionFixture::pose
PoseStamped pose
Definition: test/abstract_planner_execution.cpp:31
main
int main(int argc, char **argv)
Definition: test/abstract_planner_execution.cpp:212
AbstractPlannerMock::MOCK_METHOD6
MOCK_METHOD6(makePlan, uint32_t(const PoseStamped &, const PoseStamped &, double, std::vector< PoseStamped > &, double &, std::string &))
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
AbstractPlannerExecutionFixture::TearDown
void TearDown() override
Definition: test/abstract_planner_execution.cpp:38
abstract_planner.h
EXPECT_CALL
EXPECT_CALL(action_server, publishResult(_, Field(&mbf_msgs::GetPathResult::outcome, Eq(mbf_msgs::GetPathResult::SUCCESS)))) .Times(1) .WillOnce(Notify(&done_condition_))
start
ROSCPP_DECL void start()
ros::console::levels::Fatal
Fatal
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
ACTION
ACTION(ThrowException)
Definition: test/abstract_planner_execution.cpp:192
mbf_abstract_core::AbstractPlanner
mbf_abstract_core::AbstractPlanner::makePlan
virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)=0
TEST_F
TEST_F(AbstractPlannerExecutionFixture, success)
Definition: test/abstract_planner_execution.cpp:45
AbstractPlannerExecutionFixture
Definition: test/abstract_planner_execution.cpp:29
mbf_abstract_nav::AbstractPlannerExecution
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...
Definition: abstract_planner_execution.h:74
AbstractPlannerExecutionFixture::AbstractPlannerExecutionFixture
AbstractPlannerExecutionFixture()
Definition: test/abstract_planner_execution.cpp:33
AbstractPlannerMock
Definition: test/abstract_planner_execution.cpp:14
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
ros::NodeHandle
abstract_planner_execution.h


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47