test/abstract_execution_base.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
3 
4 #include <boost/chrono.hpp>
5 
6 using namespace mbf_abstract_nav;
7 
8 // our dummy implementation of the AbstractExecutionBase
9 // it basically runs until we cancel it.
11 {
12  DummyExecutionBase(const std::string& _name) : AbstractExecutionBase(_name)
13  {
14  }
15 
16  // implement the required interfaces
17  bool cancel()
18  {
19  cancel_ = true;
20  condition_.notify_all();
21  return true;
22  }
23 
24 protected:
25  void run()
26  {
27  boost::mutex mutex;
28  boost::unique_lock<boost::mutex> lock(mutex);
29 
30  // wait until someone says we are done (== cancel or stop)
31  // we set a timeout, since we might miss the cancel call (especially if we
32  // run on an environment with high CPU load)
33  condition_.wait_for(lock, boost::chrono::seconds(1));
34  outcome_ = 0;
35  }
36 };
37 
38 // shortcuts...
39 using testing::Test;
40 
41 // the fixture owning the instance of the DummyExecutionBase
42 struct AbstractExecutionFixture : public Test
43 {
45 
46  AbstractExecutionFixture() : impl_("foo")
47  {
48  }
49 };
50 
52 {
53  // start the thread
54  impl_.start();
55 
56  // make sure that we timeout and dont alter the outcome
57  EXPECT_EQ(impl_.waitForStateUpdate(boost::chrono::microseconds(60)), boost::cv_status::timeout);
58  EXPECT_EQ(impl_.getOutcome(), 255);
59 }
60 
62 {
63  // start the thread
64  impl_.start();
65  EXPECT_EQ(impl_.waitForStateUpdate(boost::chrono::microseconds(60)), boost::cv_status::timeout);
66 
67  // cancel, so we set the outcome to 0
68  impl_.cancel();
69  impl_.join();
70  EXPECT_EQ(impl_.getOutcome(), 0);
71 }
72 
74 {
75  // call start multiple times without waiting for its termination
76  for (size_t ii = 0; ii != 10; ++ii)
77  impl_.start();
78 }
79 
81 {
82  // call stop/terminate multiple times. this should be a noop
83  for (size_t ii = 0; ii != 10; ++ii)
84  {
85  impl_.stop();
86  impl_.join();
87  }
88 }
89 
90 int main(int argc, char** argv)
91 {
92  testing::InitGoogleTest(&argc, argv);
93  return RUN_ALL_TESTS();
94 }
DummyExecutionBase::run
void run()
Definition: test/abstract_execution_base.cpp:25
DummyExecutionBase::cancel
bool cancel()
Cancel the plugin execution.
Definition: test/abstract_execution_base.cpp:17
mbf_abstract_nav
Definition: abstract_controller_execution.h:58
AbstractExecutionFixture::AbstractExecutionFixture
AbstractExecutionFixture()
Definition: test/abstract_execution_base.cpp:46
TEST_F
TEST_F(AbstractExecutionFixture, timeout)
Definition: test/abstract_execution_base.cpp:51
DummyExecutionBase::DummyExecutionBase
DummyExecutionBase(const std::string &_name)
Definition: test/abstract_execution_base.cpp:12
AbstractExecutionFixture::impl_
DummyExecutionBase impl_
Definition: test/abstract_execution_base.cpp:44
AbstractExecutionFixture
Definition: test/abstract_execution_base.cpp:42
DummyExecutionBase
Definition: test/abstract_execution_base.cpp:10
main
int main(int argc, char **argv)
Definition: test/abstract_execution_base.cpp:90
abstract_execution_base.h
mbf_abstract_nav::AbstractExecutionBase
Base class for running concurrent navigation tasks.
Definition: abstract_execution_base.h:57


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