Nav2 Navigation Stack - rolling  main
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 #include "nav2_msgs/action/compute_route.hpp"
35 #include "nav2_msgs/action/smooth_path.hpp"
36 
37 #include "geometry_msgs/msg/point_stamped.hpp"
38 
39 #include "rclcpp/rclcpp.hpp"
40 
41 #include "dummy_action_server.hpp"
42 #include "dummy_service.hpp"
43 
44 namespace nav2_system_tests
45 {
46 
48  : public DummyActionServer<nav2_msgs::action::ComputePathToPose>
49 {
50 public:
51  explicit DummyComputePathToPoseActionServer(const rclcpp::Node::SharedPtr & node)
52  : DummyActionServer(node, "compute_path_to_pose")
53  {
54  geometry_msgs::msg::PoseStamped pose;
55  pose.header.stamp = node->get_clock()->now();
56  pose.header.frame_id = "map";
57  pose.pose.position.x = 0.0;
58  pose.pose.position.y = 0.0;
59  pose.pose.position.z = 0.0;
60  pose.pose.orientation.x = 0.0;
61  pose.pose.orientation.y = 0.0;
62  pose.pose.orientation.z = 0.0;
63  pose.pose.orientation.w = 1.0;
64 
65  result_->path.header.stamp = node->now();
66  result_->path.header.frame_id = pose.header.frame_id;
67  for (int i = 0; i < 6; ++i) {
68  result_->path.poses.push_back(pose);
69  }
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  result->error_msg = "Timeout";
79  }
80 };
81 
82 class DummyFollowPathActionServer : public DummyActionServer<nav2_msgs::action::FollowPath>
83 {
84 public:
85  explicit DummyFollowPathActionServer(const rclcpp::Node::SharedPtr & node)
86  : DummyActionServer(node, "follow_path") {}
87 
88 protected:
89  void updateResultForFailure(
90  std::shared_ptr<nav2_msgs::action::FollowPath::Result>
91  & result) override
92  {
93  result->error_code = nav2_msgs::action::FollowPath::Result::NO_VALID_CONTROL;
94  result->error_msg = "No valid control";
95  }
96 };
97 
98 
100 {
101 public:
102  ServerHandler();
103  ~ServerHandler();
104 
105  void activate();
106 
107  void deactivate();
108 
109  bool isActive() const
110  {
111  return is_active_;
112  }
113 
114  void reset() const;
115 
116 public:
117  std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_local_costmap_server;
118  std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_global_costmap_server;
119  std::unique_ptr<DummyComputePathToPoseActionServer> compute_path_to_pose_server;
120  std::unique_ptr<DummyFollowPathActionServer> follow_path_server;
121  std::unique_ptr<DummyActionServer<nav2_msgs::action::Spin>> spin_server;
122  std::unique_ptr<DummyActionServer<nav2_msgs::action::Wait>> wait_server;
123  std::unique_ptr<DummyActionServer<nav2_msgs::action::BackUp>> backup_server;
124  std::unique_ptr<DummyActionServer<nav2_msgs::action::ComputeRoute>> compute_route_server;
125  std::unique_ptr<DummyActionServer<nav2_msgs::action::SmoothPath>> smoother_server;
126  std::unique_ptr<DummyActionServer<nav2_msgs::action::DriveOnHeading>> drive_on_heading_server;
127  std::unique_ptr<DummyActionServer<nav2_msgs::action::ComputePathThroughPoses>> ntp_server;
128 
129 private:
130  void spinThread();
131 
132  bool is_active_;
133  rclcpp::Node::SharedPtr node_;
134  std::shared_ptr<std::thread> server_thread_;
135 };
136 
137 } // namespace nav2_system_tests
138 
139 #endif // BEHAVIOR_TREE__SERVER_HANDLER_HPP_