Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
dummy_action_server.hpp
1 // Copyright (c) 2020 Sarthak Mittal
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #ifndef BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_
16 #define BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <utility>
21 #include <vector>
22 #include <chrono>
23 
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "rclcpp/rclcpp.hpp"
26 
27 namespace nav2_system_tests
28 {
29 
30 using namespace std::chrono_literals; // NOLINT
31 using namespace std::chrono; // NOLINT
32 using namespace std::placeholders; // NOLINT
33 
34 using Range = std::pair<unsigned int, unsigned int>;
35 using Ranges = std::vector<Range>;
36 
37 template<class ActionT>
39 {
40 public:
41  explicit DummyActionServer(
42  const rclcpp::Node::SharedPtr & node,
43  std::string action_name)
44  : action_name_(action_name),
45  goal_count_(0),
46  result_(std::make_shared<typename ActionT::Result>())
47  {
48  action_server_ = rclcpp_action::create_server<ActionT>(
49  node->get_node_base_interface(),
50  node->get_node_clock_interface(),
51  node->get_node_logging_interface(),
52  node->get_node_waitables_interface(),
53  action_name,
54  std::bind(&DummyActionServer::handle_goal, this, _1, _2),
55  std::bind(&DummyActionServer::handle_cancel, this, _1),
56  std::bind(&DummyActionServer::handle_accepted, this, _1));
57  }
58 
59  virtual ~DummyActionServer() = default;
60  void setFailureRanges(const Ranges & failureRanges)
61  {
62  failure_ranges_ = failureRanges;
63  }
64 
65  void setRunningRanges(const Ranges & runningRanges)
66  {
67  running_ranges_ = runningRanges;
68  }
69 
70  void reset()
71  {
72  failure_ranges_.clear();
73  running_ranges_.clear();
74  goal_count_ = 0;
75  updateResultForSuccess(result_);
76  }
77 
78  int getGoalCount() const
79  {
80  return goal_count_;
81  }
82 
83  std::shared_ptr<typename ActionT::Result> getResult(void)
84  {
85  return result_;
86  }
87 
88 protected:
89  virtual void updateResultForFailure(std::shared_ptr<typename ActionT::Result> & result)
90  {
91  result->error_code = ActionT::Result::UNKNOWN;
92  result->error_msg = "Unknown Failure";
93  }
94 
95  virtual void updateResultForSuccess(std::shared_ptr<typename ActionT::Result> & result)
96  {
97  result->error_code = ActionT::Result::NONE;
98  result->error_msg = "";
99  }
100 
101  virtual rclcpp_action::GoalResponse handle_goal(
102  const rclcpp_action::GoalUUID &,
103  std::shared_ptr<const typename ActionT::Goal>/*goal*/)
104  {
105  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
106  }
107 
108  virtual rclcpp_action::CancelResponse handle_cancel(
109  const typename std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>>)
110  {
111  return rclcpp_action::CancelResponse::ACCEPT;
112  }
113 
114  void execute(
115  const typename std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> goal_handle)
116  {
117  goal_count_++;
118 
119  // if current goal index exists in running range, the thread sleeps for 1 second
120  // to simulate a long running action
121  for (auto & index : running_ranges_) {
122  if (goal_count_ >= index.first && goal_count_ <= index.second) {
123  std::this_thread::sleep_for(1s);
124  break;
125  }
126  }
127 
128  // if current goal index exists in failure range, the goal will be aborted
129  for (auto & index : failure_ranges_) {
130  if (goal_count_ >= index.first && goal_count_ <= index.second) {
131  updateResultForFailure(result_);
132  goal_handle->abort(result_);
133  return;
134  }
135  }
136 
137  // goal succeeds for all other indices
138  updateResultForSuccess(result_);
139  goal_handle->succeed(result_);
140  }
141 
142  void handle_accepted(
143  const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> goal_handle)
144  {
145  using namespace std::placeholders; // NOLINT
146  // this needs to return quickly to avoid blocking the executor, so spin up a new thread
147  std::thread{std::bind(&DummyActionServer::execute, this, _1), goal_handle}.detach();
148  }
149 
150 protected:
151  typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
152  std::string action_name_;
153 
154  // contains pairs of indices which define a range for which the
155  // requested action goal will return running for 1s or be aborted
156  // for all other indices, the action server will return success
157  Ranges failure_ranges_;
158  Ranges running_ranges_;
159 
160  unsigned int goal_count_;
161  std::shared_ptr<typename ActionT::Result> result_;
162 };
163 } // namespace nav2_system_tests
164 
165 #endif // BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_