20 #include "server_handler.hpp"
22 using namespace std::chrono_literals;
23 using namespace std::chrono;
25 namespace nav2_system_tests
29 ServerHandler::ServerHandler()
32 node_ = rclcpp::Node::make_shared(
"behavior_tree_tester");
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>>(
42 wait_server = std::make_unique<DummyActionServer<nav2_msgs::action::Wait>>(
44 backup_server = std::make_unique<DummyActionServer<nav2_msgs::action::BackUp>>(
46 drive_on_heading_server = std::make_unique<DummyActionServer<nav2_msgs::action::DriveOnHeading>>(
47 node_,
"drive_on_heading");
48 ntp_server = std::make_unique<DummyActionServer<nav2_msgs::action::ComputePathThroughPoses>>(
49 node_,
"compute_path_through_poses");
52 ServerHandler::~ServerHandler()
59 void ServerHandler::activate()
62 throw std::runtime_error(
"Trying to activate while already activated");
67 std::make_shared<std::thread>(std::bind(&ServerHandler::spinThread,
this));
69 std::cout <<
"Server handler is active!" << std::endl;
72 void ServerHandler::deactivate()
75 throw std::runtime_error(
"Trying to deactivate while already inactive");
79 server_thread_->join();
81 std::cout <<
"Server handler has been deactivated!" << std::endl;
84 void ServerHandler::reset()
const
86 clear_global_costmap_server->reset();
87 clear_local_costmap_server->reset();
88 compute_path_to_pose_server->reset();
89 follow_path_server->reset();
92 backup_server->reset();
93 drive_on_heading_server->reset();
96 void ServerHandler::spinThread()