gtest_async_action_node.cpp
Go to the documentation of this file.
3 
4 #include <chrono>
5 #include <condition_variable>
6 #include <future>
7 #include <mutex>
8 #include <stdexcept>
9 #include <string>
10 #include <thread>
11 
12 #include <gtest/gtest.h>
13 #include <gmock/gmock.h>
14 
15 // The mocked version of the base.
17 {
20 
21  // Tick while the node is running.
23  {
24  do
25  {
26  executeTick();
27  } while(status() == BT::NodeStatus::RUNNING);
28  return status();
29  }
30 
31  // Expose the setStatus method.
33 };
34 
35 // The fixture taking care of the node-setup.
36 struct MockedThreadedActionFixture : public testing::Test
37 {
41  {}
42 };
43 
44 // Parameters for the terminal node states.
45 struct NodeStatusFixture : public testing::WithParamInterface<BT::NodeStatus>,
47 {
48 };
49 
51  testing::Values(BT::NodeStatus::SUCCESS,
53 
54 TEST_P(NodeStatusFixture, normal_routine)
55 {
56  // Test verifies the "normal" operation: We correctly propagate the result
57  // from the tick to the caller.
58  const BT::NodeStatus state = GetParam();
59 
60  // Setup the mock-expectations.
61  EXPECT_CALL(sn, tick()).WillOnce(testing::Invoke([&]() {
62  std::this_thread::sleep_for(std::chrono::milliseconds(10));
63  return state;
64  }));
65 
66  // Spin the node and check the final status.
67  ASSERT_EQ(sn.spinUntilDone(), state);
68 }
69 
71 {
72  // Test verifies that halt returns immediately, if the node is idle. It
73  // further checks if the halt-flag is resetted correctly.
74  sn.halt();
75  ASSERT_TRUE(sn.isHaltRequested());
76 
77  // Below we further verify that the halt flag is cleaned up properly.
79  EXPECT_CALL(sn, tick()).WillOnce(testing::Return(state));
80 
81  // Spin the node and check.
82  ASSERT_EQ(sn.spinUntilDone(), state);
83  ASSERT_FALSE(sn.isHaltRequested());
84 }
85 
87 {
88  // Test verifies that calling halt() is blocking.
89  bool release = false;
90  std::mutex m;
91  std::condition_variable cv;
92 
94  EXPECT_CALL(sn, tick()).WillOnce(testing::Invoke([&]() {
95  // Sleep until we send the release signal.
96  std::unique_lock<std::mutex> l(m);
97  while(!release)
98  cv.wait(l);
99 
100  return state;
101  }));
102 
103  // Start the execution.
104  sn.executeTick();
105 
106  // Try to halt the node (cv will block it...)
107  std::future<void> halted = std::async(std::launch::async, [&]() { sn.halt(); });
108  ASSERT_EQ(halted.wait_for(std::chrono::milliseconds(10)), std::future_status::timeout);
109  ASSERT_EQ(sn.status(), BT::NodeStatus::RUNNING);
110 
111  // Release the method.
112  {
113  std::unique_lock<std::mutex> l(m);
114  release = true;
115  cv.notify_one();
116  }
117 
118  // Wait for the future to return.
119  halted.wait();
120  ASSERT_EQ(sn.status(), state);
121 }
122 
124 {
125  // Verifies that we can recover from the exceptions in the tick method:
126  // 1) catch the exception, 2) re-raise it in the caller thread.
127 
128  // Setup the mock.
129  EXPECT_CALL(sn, tick()).WillOnce(testing::Invoke([&]() {
130  throw std::runtime_error("This is not good!");
132  }));
133 
134  ASSERT_ANY_THROW(sn.spinUntilDone());
135  testing::Mock::VerifyAndClearExpectations(&sn);
136 
137  // Now verify that the exception is cleared up (we succeed).
138  sn.setStatus(BT::NodeStatus::IDLE);
140  EXPECT_CALL(sn, tick()).WillOnce(testing::Return(state));
141  ASSERT_EQ(sn.spinUntilDone(), state);
142 }
basic_types.h
MockedThreadedAction::spinUntilDone
BT::NodeStatus spinUntilDone()
Definition: gtest_async_action_node.cpp:22
mutex
static pthread_mutex_t mutex
Definition: minitrace.cpp:77
BT::TreeNode::status
NodeStatus status() const
Definition: tree_node.cpp:279
BT::NodeStatus::FAILURE
@ FAILURE
BT::TreeNode::setStatus
void setStatus(NodeStatus new_status)
setStatus changes the status of the node. it will throw if you try to change the status to IDLE,...
Definition: tree_node.cpp:154
action_node.h
MockedThreadedAction
Definition: gtest_async_action_node.cpp:16
MockedThreadedActionFixture::sn
MockedThreadedAction sn
Definition: gtest_async_action_node.cpp:39
BT::ThreadedAction::ThreadedAction
ThreadedAction(const std::string &name, const NodeConfig &config)
Definition: action_node.h:119
BT::TreeNode::tick
virtual BT::NodeStatus tick()=0
Method to be implemented by the user.
BT::NodeStatus::SUCCESS
@ SUCCESS
TEST_P
TEST_P(NodeStatusFixture, normal_routine)
Definition: gtest_async_action_node.cpp:54
TEST_F
TEST_F(MockedThreadedActionFixture, no_halt)
Definition: gtest_async_action_node.cpp:70
BT::NodeStatus::RUNNING
@ RUNNING
MockedThreadedActionFixture
Definition: gtest_async_action_node.cpp:36
MockedThreadedActionFixture::config
BT::NodeConfig config
Definition: gtest_async_action_node.cpp:38
BT::NodeStatus::IDLE
@ IDLE
BT::ThreadedAction
The ThreadedAction executes the tick in a different thread.
Definition: action_node.h:116
BT::ThreadedAction::executeTick
virtual NodeStatus executeTick() override final
The method that should be used to invoke tick() and setStatus();.
Definition: action_node.cpp:189
MockedThreadedActionFixture::MockedThreadedActionFixture
MockedThreadedActionFixture()
Definition: gtest_async_action_node.cpp:40
BT::NodeConfig
Definition: tree_node.h:73
NodeStatusFixture
Definition: gtest_async_action_node.cpp:45
MockedThreadedAction::MOCK_METHOD0
MOCK_METHOD0(tick, BT::NodeStatus())
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
INSTANTIATE_TEST_SUITE_P
INSTANTIATE_TEST_SUITE_P(, NodeStatusFixture, testing::Values(BT::NodeStatus::SUCCESS, BT::NodeStatus::FAILURE))


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:07