Nav2 Navigation Stack - humble  humble
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_servers.hpp"
40 
42  : public DummyActionServer<nav2_msgs::action::ComputePathToPose>
43 {
44 public:
45  explicit ComputePathToPoseActionServer(const rclcpp::Node::SharedPtr & node)
46  : DummyActionServer(node, "compute_path_to_pose")
47  {
48  result_ = std::make_shared<nav2_msgs::action::ComputePathToPose::Result>();
49  geometry_msgs::msg::PoseStamped pose;
50  pose.header = result_->path.header;
51  pose.pose.position.x = 0.0;
52  pose.pose.position.y = 0.0;
53  pose.pose.position.z = 0.0;
54  pose.pose.orientation.x = 0.0;
55  pose.pose.orientation.y = 0.0;
56  pose.pose.orientation.z = 0.0;
57  pose.pose.orientation.w = 1.0;
58  for (int i = 0; i < 6; ++i) {
59  result_->path.poses.push_back(pose);
60  }
61  }
62 
63  std::shared_ptr<nav2_msgs::action::ComputePathToPose::Result> fillResult() override
64  {
65  return result_;
66  }
67 
68 private:
69  std::shared_ptr<nav2_msgs::action::ComputePathToPose::Result> result_;
70 };
71 
73 {
74 public:
75  ServerHandler();
76  ~ServerHandler();
77 
78  void activate();
79 
80  void deactivate();
81 
82  bool isActive() const
83  {
84  return is_active_;
85  }
86 
87  void reset() const;
88 
89 public:
90  std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_local_costmap_server;
91  std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_global_costmap_server;
92  std::unique_ptr<ComputePathToPoseActionServer> compute_path_to_pose_server;
93  std::unique_ptr<DummyActionServer<nav2_msgs::action::FollowPath>> follow_path_server;
94  std::unique_ptr<DummyActionServer<nav2_msgs::action::Spin>> spin_server;
95  std::unique_ptr<DummyActionServer<nav2_msgs::action::Wait>> wait_server;
96  std::unique_ptr<DummyActionServer<nav2_msgs::action::BackUp>> backup_server;
97  std::unique_ptr<DummyActionServer<nav2_msgs::action::DriveOnHeading>> drive_on_heading_server;
98  std::unique_ptr<DummyActionServer<nav2_msgs::action::ComputePathThroughPoses>> ntp_server;
99 
100 private:
101  void spinThread();
102 
103  bool is_active_;
104  rclcpp::Node::SharedPtr node_;
105  std::shared_ptr<std::thread> server_thread_;
106 };
107 
108 #endif // BEHAVIOR_TREE__SERVER_HANDLER_HPP_