1 #include <gmock/gmock.h> 
    2 #include <gtest/gtest.h> 
    9 using geometry_msgs::PoseStamped;
 
   16   MOCK_METHOD6(
makePlan, uint32_t(
const PoseStamped&, 
const PoseStamped&, 
double, std::vector<PoseStamped>&, 
double&,
 
   23 using mbf_abstract_nav::MoveBaseFlexConfig;
 
   25 using testing::Return;
 
   50   EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).WillOnce(Return(0));
 
   53   ASSERT_TRUE(
start(pose, pose, 0));
 
   56   ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
 
   57   ASSERT_EQ(getState(), FOUND_PLAN);
 
   63   boost::unique_lock<boost::mutex> lock(m);
 
   73   boost::condition_variable cv;
 
   75   ON_CALL(mock, makePlan(_, _, _, _, _, _)).WillByDefault(Wait(&cv));
 
   76   EXPECT_CALL(mock, cancel()).Times(1).WillOnce(Return(
true));
 
   79   ASSERT_TRUE(
start(pose, pose, 0));
 
   80   ASSERT_TRUE(cancel());
 
   86   waitForStateUpdate(boost::chrono::seconds(1));
 
   87   ASSERT_EQ(getState(), CANCELED);
 
   96   MoveBaseFlexConfig config;
 
   97   config.planner_max_retries = 5;
 
   98   config.planner_patience = 100;  
 
  104   EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(config.planner_max_retries + 1).WillRepeatedly(Return(11));
 
  107   ASSERT_TRUE(
start(pose, pose, 0));
 
  110   ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
 
  111   ASSERT_EQ(getState(), MAX_RETRIES);
 
  120   MoveBaseFlexConfig config;
 
  121   config.planner_max_retries = 0;
 
  122   config.planner_patience = 0;
 
  127   EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(1).WillOnce(Return(11));
 
  130   ASSERT_TRUE(
start(pose, pose, 0));
 
  133   ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
 
  134   ASSERT_EQ(getState(), NO_PLAN_FOUND);
 
  137 using testing::DoAll;
 
  138 using testing::SetArgReferee;
 
  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;
 
  153       .WillOnce(DoAll(SetArgReferee<3>(plan), SetArgReferee<4>(cost), Return(0)));
 
  156   ASSERT_TRUE(
start(pose, pose, 0));
 
  159   ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
 
  160   ASSERT_EQ(getState(), FOUND_PLAN);
 
  161   ASSERT_EQ(getCost(), 3);
 
  170   MoveBaseFlexConfig config;
 
  171   config.planner_max_retries = 0;
 
  172   config.planner_patience = 0.1;
 
  177   boost::condition_variable cv;
 
  178   EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(1).WillOnce(Wait(&cv));
 
  181   ASSERT_TRUE(
start(pose, pose, 0));
 
  184   boost::this_thread::sleep_for(boost::chrono::milliseconds{ 200 });
 
  188   waitForStateUpdate(boost::chrono::seconds(1));
 
  189   ASSERT_EQ(getState(), PAT_EXCEEDED);
 
  194   throw std::runtime_error(
"bad planner");
 
  202   EXPECT_CALL(mock, makePlan(_, _, _, _, _, _)).Times(1).WillOnce(ThrowException());
 
  205   ASSERT_TRUE(
start(pose, pose, 0));
 
  208   ASSERT_EQ(waitForStateUpdate(boost::chrono::seconds(1)), boost::cv_status::no_timeout);
 
  209   ASSERT_EQ(getState(), INTERNAL_ERROR);
 
  212 int main(
int argc, 
char** argv)
 
  221   testing::InitGoogleTest(&argc, argv);
 
  222   return RUN_ALL_TESTS();