Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
server_handler.hpp
1 // Copyright (c) 2020 Vinny Ruia
2 // Copyright (c) 2020 Sarthak Mittal
3 // Copyright (c) 2018 Intel Corporation
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License. Reserved.
16 
17 #ifndef BEHAVIOR_TREE__SERVER_HANDLER_HPP_
18 #define BEHAVIOR_TREE__SERVER_HANDLER_HPP_
19 
20 #include <memory>
21 #include <string>
22 #include <thread>
23 #include <utility>
24 #include <vector>
25 
26 #include "nav2_msgs/srv/clear_entire_costmap.hpp"
27 #include "nav2_msgs/action/compute_path_to_pose.hpp"
28 #include "nav2_msgs/action/follow_path.hpp"
29 #include "nav2_msgs/action/spin.hpp"
30 #include "nav2_msgs/action/back_up.hpp"
31 #include "nav2_msgs/action/wait.hpp"
32 #include "nav2_msgs/action/drive_on_heading.hpp"
33 #include "nav2_msgs/action/compute_path_through_poses.hpp"
34 
35 #include "geometry_msgs/msg/point_stamped.hpp"
36 
37 #include "rclcpp/rclcpp.hpp"
38 
39 #include "dummy_action_server.hpp"
40 #include "dummy_service.hpp"
41 
42 namespace nav2_system_tests
43 {
44 
46  : public DummyActionServer<nav2_msgs::action::ComputePathToPose>
47 {
48 public:
49  explicit DummyComputePathToPoseActionServer(const rclcpp::Node::SharedPtr & node)
50  : DummyActionServer(node, "compute_path_to_pose")
51  {
52  result_ = std::make_shared<nav2_msgs::action::ComputePathToPose::Result>();
53  geometry_msgs::msg::PoseStamped pose;
54  pose.header = result_->path.header;
55  pose.pose.position.x = 0.0;
56  pose.pose.position.y = 0.0;
57  pose.pose.position.z = 0.0;
58  pose.pose.orientation.x = 0.0;
59  pose.pose.orientation.y = 0.0;
60  pose.pose.orientation.z = 0.0;
61  pose.pose.orientation.w = 1.0;
62  for (int i = 0; i < 6; ++i) {
63  result_->path.poses.push_back(pose);
64  }
65  }
66 
67  std::shared_ptr<nav2_msgs::action::ComputePathToPose::Result> fillResult() override
68  {
69  return result_;
70  }
71 
72 protected:
73  void updateResultForFailure(
74  std::shared_ptr<nav2_msgs::action::ComputePathToPose::Result>
75  & result) override
76  {
77  result->error_code = nav2_msgs::action::ComputePathToPose::Result::TIMEOUT;
78  }
79 
80 private:
81  std::shared_ptr<nav2_msgs::action::ComputePathToPose::Result> result_;
82 };
83 
84 class DummyFollowPathActionServer : public DummyActionServer<nav2_msgs::action::FollowPath>
85 {
86 public:
87  explicit DummyFollowPathActionServer(const rclcpp::Node::SharedPtr & node)
88  : DummyActionServer(node, "follow_path") {}
89 
90 protected:
91  void updateResultForFailure(
92  std::shared_ptr<nav2_msgs::action::FollowPath::Result>
93  & result) override
94  {
95  result->error_code = nav2_msgs::action::FollowPath::Result::NO_VALID_CONTROL;
96  }
97 };
98 
99 
101 {
102 public:
103  ServerHandler();
104  ~ServerHandler();
105 
106  void activate();
107 
108  void deactivate();
109 
110  bool isActive() const
111  {
112  return is_active_;
113  }
114 
115  void reset() const;
116 
117 public:
118  std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_local_costmap_server;
119  std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_global_costmap_server;
120  std::unique_ptr<DummyComputePathToPoseActionServer> compute_path_to_pose_server;
121  std::unique_ptr<DummyFollowPathActionServer> follow_path_server;
122  std::unique_ptr<DummyActionServer<nav2_msgs::action::Spin>> spin_server;
123  std::unique_ptr<DummyActionServer<nav2_msgs::action::Wait>> wait_server;
124  std::unique_ptr<DummyActionServer<nav2_msgs::action::BackUp>> backup_server;
125  std::unique_ptr<DummyActionServer<nav2_msgs::action::DriveOnHeading>> drive_on_heading_server;
126  std::unique_ptr<DummyActionServer<nav2_msgs::action::ComputePathThroughPoses>> ntp_server;
127 
128 private:
129  void spinThread();
130 
131  bool is_active_;
132  rclcpp::Node::SharedPtr node_;
133  std::shared_ptr<std::thread> server_thread_;
134 };
135 
136 } // namespace nav2_system_tests
137 
138 #endif // BEHAVIOR_TREE__SERVER_HANDLER_HPP_