19 #include "dummy_planner.hpp"
21 using namespace std::chrono_literals;
23 namespace nav2_system_tests
26 DummyPlanner::DummyPlanner()
27 : Node(
"DummyPlanner")
29 RCLCPP_INFO(get_logger(),
"Initializing DummyPlanner...");
31 auto temp_node = std::shared_ptr<rclcpp::Node>(
this, [](
auto) {});
34 std::make_unique<nav2_behavior_tree::ComputePathToPoseTaskServer>(temp_node,
false),
35 task_server_->setExecuteCallback(
36 std::bind(&DummyPlanner::computePlan,
this, std::placeholders::_1));
39 task_server_->start();
41 RCLCPP_INFO(get_logger(),
"Initialized DummyPlanner");
44 DummyPlanner::~DummyPlanner()
46 RCLCPP_INFO(get_logger(),
"Shutting down DummyPlanner");
50 DummyPlanner::computePlan(
const nav2_behavior_tree::ComputePathToPoseCommand::SharedPtr cmd)
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);
58 std::this_thread::sleep_for(500ms);
60 if (task_server_->cancelRequested()) {
61 RCLCPP_INFO(get_logger(),
"Cancelled planning task.");
62 task_server_->setCanceled();
66 RCLCPP_INFO(get_logger(),
"Found a dummy path");
68 nav2_behavior_tree::ComputePathToPoseResult result;
70 task_server_->setResult(result);