Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
server_handler.cpp
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 #include <memory>
18 #include <thread>
19 
20 #include "server_handler.hpp"
21 
22 using namespace std::chrono_literals; // NOLINT
23 using namespace std::chrono; // NOLINT
24 
25 namespace nav2_system_tests
26 {
27 
28 
29 ServerHandler::ServerHandler()
30 : is_active_(false)
31 {
32  node_ = rclcpp::Node::make_shared("behavior_tree_tester");
33 
34  clear_local_costmap_server = std::make_unique<DummyService<nav2_msgs::srv::ClearEntireCostmap>>(
35  node_, "local_costmap/clear_entirely_local_costmap");
36  clear_global_costmap_server = std::make_unique<DummyService<nav2_msgs::srv::ClearEntireCostmap>>(
37  node_, "global_costmap/clear_entirely_global_costmap");
38  compute_path_to_pose_server = std::make_unique<DummyComputePathToPoseActionServer>(node_);
39  follow_path_server = std::make_unique<DummyFollowPathActionServer>(node_);
40  spin_server = std::make_unique<DummyActionServer<nav2_msgs::action::Spin>>(
41  node_, "spin");
42  wait_server = std::make_unique<DummyActionServer<nav2_msgs::action::Wait>>(
43  node_, "wait");
44  backup_server = std::make_unique<DummyActionServer<nav2_msgs::action::BackUp>>(
45  node_, "backup");
46  compute_route_server = std::make_unique<DummyActionServer<nav2_msgs::action::ComputeRoute>>(
47  node_, "compute_route");
48  smoother_server = std::make_unique<DummyActionServer<nav2_msgs::action::SmoothPath>>(
49  node_, "smooth_path");
50  drive_on_heading_server = std::make_unique<DummyActionServer<nav2_msgs::action::DriveOnHeading>>(
51  node_, "drive_on_heading");
52  ntp_server = std::make_unique<DummyActionServer<nav2_msgs::action::ComputePathThroughPoses>>(
53  node_, "compute_path_through_poses");
54 }
55 
56 ServerHandler::~ServerHandler()
57 {
58  if (is_active_) {
59  deactivate();
60  }
61 }
62 
63 void ServerHandler::activate()
64 {
65  if (is_active_) {
66  throw std::runtime_error("Trying to activate while already activated");
67  }
68 
69  is_active_ = true;
70  server_thread_ =
71  std::make_shared<std::thread>(std::bind(&ServerHandler::spinThread, this));
72 
73  std::cout << "Server handler is active!" << std::endl;
74 }
75 
76 void ServerHandler::deactivate()
77 {
78  if (!is_active_) {
79  throw std::runtime_error("Trying to deactivate while already inactive");
80  }
81 
82  is_active_ = false;
83  server_thread_->join();
84 
85  std::cout << "Server handler has been deactivated!" << std::endl;
86 }
87 
88 void ServerHandler::reset() const
89 {
90  clear_global_costmap_server->reset();
91  clear_local_costmap_server->reset();
92  compute_path_to_pose_server->reset();
93  follow_path_server->reset();
94  spin_server->reset();
95  wait_server->reset();
96  backup_server->reset();
97  drive_on_heading_server->reset();
98 }
99 
100 void ServerHandler::spinThread()
101 {
102  rclcpp::spin(node_);
103 }
104 
105 } // namespace nav2_system_tests