abstract_action_base.cpp
Go to the documentation of this file.
1 #include <gmock/gmock.h>
2 #include <gtest/gtest.h>
3 
4 // dummy message
5 #include <mbf_msgs/GetPathAction.h>
7 
8 #include <mbf_abstract_nav/abstract_action_base.hpp>
10 
11 using namespace mbf_abstract_nav;
12 
13 // mocked version of an execution
16 
17  MockedExecution() : AbstractExecutionBase("mocked_execution") {}
18 
19  MOCK_METHOD0(cancel, bool());
20 
21 protected:
22  MOCK_METHOD0(run, void());
23 };
24 
25 using testing::Test;
26 
27 // fixture with access to the AbstracActionBase's internals
29  : public AbstractActionBase<mbf_msgs::GetPathAction, MockedExecution>,
30  public Test {
31  // required members for the c'tor
33  std::string test_name;
35 
37  : test_name("action_base"),
38  ri(tf_, "global_frame", "local_frame", ros::Duration(0)),
39  AbstractActionBase(test_name, ri)
40  {
41  }
42 
43  void runImpl(GoalHandle &goal_handle, MockedExecution &execution) {}
44 };
45 
47 {
48  unsigned char slot = 1;
49  concurrency_slots_[slot].execution.reset(new MockedExecution());
50  concurrency_slots_[slot].thread_ptr =
51  threads_.create_thread(boost::bind(&AbstractActionBaseFixture::run, this,
52  boost::ref(concurrency_slots_[slot])));
53 }
54 
55 using testing::Return;
56 
58 {
59  // spawn a bunch of threads
60  for (unsigned char slot = 0; slot != 10; ++slot) {
61  concurrency_slots_[slot].execution.reset(new MockedExecution());
62  // set the expectation
63  EXPECT_CALL(*concurrency_slots_[slot].execution, cancel())
64  .WillRepeatedly(Return(true));
65 
66  // set the in_use flag --> this should turn to false
67  concurrency_slots_[slot].in_use = true;
68  concurrency_slots_[slot].thread_ptr = threads_.create_thread(
69  boost::bind(&AbstractActionBaseFixture::run, this,
70  boost::ref(concurrency_slots_[slot])));
71  }
72 
73  // cancel all of slots
74  cancelAll();
75 
76  // check the result
77  for (ConcurrencyMap::iterator slot = concurrency_slots_.begin();
78  slot != concurrency_slots_.end(); ++slot)
79  ASSERT_FALSE(slot->second.in_use);
80 }
81 
82 int main(int argc, char **argv)
83 {
84  // we need this only for kinetic and lunar distros
85  ros::init(argc, argv, "abstract_action_base");
86  ros::NodeHandle nh;
87  testing::InitGoogleTest(&argc, argv);
88  return RUN_ALL_TESTS();
89 }
void run(class_loader::ClassLoader *loader)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(AbstractActionBaseFixture, thread_stop)
EXPECT_CALL(action_server, publishResult(_, Field(&mbf_msgs::GetPathResult::outcome, Eq(mbf_msgs::GetPathResult::SUCCESS)))) .Times(1) .WillOnce(Notify(&done_condition_))
int main(int argc, char **argv)
Base class for running concurrent navigation tasks.
void runImpl(GoalHandle &goal_handle, MockedExecution &execution)
mbf_utility::RobotInformation ri
boost::shared_ptr< MockedExecution > Ptr


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Mon Feb 28 2022 22:49:50