15 #ifndef BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_
16 #define BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "rclcpp/rclcpp.hpp"
27 namespace nav2_system_tests
30 using namespace std::chrono_literals;
31 using namespace std::chrono;
32 using namespace std::placeholders;
34 using Range = std::pair<unsigned int, unsigned int>;
35 using Ranges = std::vector<Range>;
37 template<
class ActionT>
42 const rclcpp::Node::SharedPtr & node,
43 std::string action_name)
44 : action_name_(action_name),
46 result_(std::make_shared<typename ActionT::Result>())
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(),
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));
60 void setFailureRanges(
const Ranges & failureRanges)
62 failure_ranges_ = failureRanges;
65 void setRunningRanges(
const Ranges & runningRanges)
67 running_ranges_ = runningRanges;
72 failure_ranges_.clear();
73 running_ranges_.clear();
75 updateResultForSuccess(result_);
78 int getGoalCount()
const
83 std::shared_ptr<typename ActionT::Result> getResult(
void)
89 virtual void updateResultForFailure(std::shared_ptr<typename ActionT::Result> & result)
91 result->error_code = ActionT::Result::UNKNOWN;
92 result->error_msg =
"Unknown Failure";
95 virtual void updateResultForSuccess(std::shared_ptr<typename ActionT::Result> & result)
97 result->error_code = ActionT::Result::NONE;
98 result->error_msg =
"";
101 virtual rclcpp_action::GoalResponse handle_goal(
102 const rclcpp_action::GoalUUID &,
103 std::shared_ptr<const typename ActionT::Goal>)
105 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
108 virtual rclcpp_action::CancelResponse handle_cancel(
109 const typename std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>>)
111 return rclcpp_action::CancelResponse::ACCEPT;
115 const typename std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> goal_handle)
121 for (
auto & index : running_ranges_) {
122 if (goal_count_ >= index.first && goal_count_ <= index.second) {
123 std::this_thread::sleep_for(1s);
129 for (
auto & index : failure_ranges_) {
130 if (goal_count_ >= index.first && goal_count_ <= index.second) {
131 updateResultForFailure(result_);
132 goal_handle->abort(result_);
138 updateResultForSuccess(result_);
139 goal_handle->succeed(result_);
142 void handle_accepted(
143 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> goal_handle)
145 using namespace std::placeholders;
147 std::thread{std::bind(&DummyActionServer::execute,
this, _1), goal_handle}.detach();
151 typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
152 std::string action_name_;
157 Ranges failure_ranges_;
158 Ranges running_ranges_;
160 unsigned int goal_count_;
161 std::shared_ptr<typename ActionT::Result> result_;