23#ifndef EASYNAV_PLANNER__DUMMYPLANNER_HPP_
24#define EASYNAV_PLANNER__DUMMYPLANNER_HPP_
28#include "nav_msgs/msg/path.hpp"
29#include "easynav_core/PlannerMethodBase.hpp"
53 virtual std::expected<void, std::string>
on_initialize()
override;
63 nav_msgs::msg::Path path_;
65 double cycle_time_rt_ {0.0};
66 double cycle_time_nort_ {0.0};
DummyPlanner()=default
Default constructor.
virtual void update(NavState &nav_state) override
Dummy update method.
Definition DummyPlanner.cpp:48
virtual std::expected< void, std::string > on_initialize() override
Initialization hook.
Definition DummyPlanner.cpp:30
~DummyPlanner()=default
Destructor.
A generic, type-safe, lock-free blackboard to hold runtime state.
Definition NavState.hpp:62
Definition RTTFBuffer.hpp:30