Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
dummy_planner.cpp
1 // Copyright (c) 2018 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <chrono>
16 #include <thread>
17 #include <memory>
18 
19 #include "dummy_planner.hpp"
20 
21 using namespace std::chrono_literals;
22 
23 namespace nav2_system_tests
24 {
25 
26 DummyPlanner::DummyPlanner()
27 : Node("DummyPlanner")
28 {
29  RCLCPP_INFO(get_logger(), "Initializing DummyPlanner...");
30 
31  auto temp_node = std::shared_ptr<rclcpp::Node>(this, [](auto) {});
32 
33  task_server_ =
34  std::make_unique<nav2_behavior_tree::ComputePathToPoseTaskServer>(temp_node, false),
35  task_server_->setExecuteCallback(
36  std::bind(&DummyPlanner::computePlan, this, std::placeholders::_1));
37 
38  // Start listening for incoming ComputePathToPose task requests
39  task_server_->start();
40 
41  RCLCPP_INFO(get_logger(), "Initialized DummyPlanner");
42 }
43 
44 DummyPlanner::~DummyPlanner()
45 {
46  RCLCPP_INFO(get_logger(), "Shutting down DummyPlanner");
47 }
48 
49 void
50 DummyPlanner::computePlan(const nav2_behavior_tree::ComputePathToPoseCommand::SharedPtr cmd)
51 {
52  RCLCPP_INFO(
53  get_logger(), "Attempting to a find path from (%.2f, %.2f) to "
54  "(%.2f, %.2f).", cmd->start.position.x, cmd->start.position.y,
55  cmd->goal.position.x, cmd->goal.position.y);
56 
57  // Dummy path computation time
58  std::this_thread::sleep_for(500ms);
59 
60  if (task_server_->cancelRequested()) {
61  RCLCPP_INFO(get_logger(), "Cancelled planning task.");
62  task_server_->setCanceled();
63  return;
64  }
65 
66  RCLCPP_INFO(get_logger(), "Found a dummy path");
67 
68  nav2_behavior_tree::ComputePathToPoseResult result;
69  // set succeeded
70  task_server_->setResult(result);
71 }
72 
73 } // namespace nav2_system_tests