Easy Navigation
Loading...
Searching...
No Matches
PlannerNode.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// This file is part of the project Easy Navigation (EasyNav in short)
4// licensed under the GNU General Public License v3.0.
5// See <http://www.gnu.org/licenses/> for details.
6//
7// Easy Navigation program is free software: you can redistribute it and/or modify
8// it under the terms of the GNU General Public License as published by
9// the Free Software Foundation, either version 3 of the License, or
10// (at your option) any later version.
11//
12// This program is distributed in the hope that it will be useful,
13// but WITHOUT ANY WARRANTY; without even the implied warranty of
14// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15// GNU General Public License for more details.
16//
17// You should have received a copy of the GNU General Public License
18// along with this program. If not, see <http://www.gnu.org/licenses/>.
19
22
23#ifndef EASYNAV_PLANNER__PLANNERNODE_HPP_
24#define EASYNAV_PLANNER__PLANNERNODE_HPP_
25
26#include "rclcpp/macros.hpp"
27#include "rclcpp_lifecycle/lifecycle_node.hpp"
28#include "easynav_core/PlannerMethodBase.hpp"
29#include "pluginlib/class_loader.hpp"
30#include "nav_msgs/msg/path.hpp"
32
33namespace easynav
34{
35
42class PlannerNode : public rclcpp_lifecycle::LifecycleNode
43{
44public:
45 RCLCPP_SMART_PTR_DEFINITIONS(PlannerNode)
46 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
47
52 explicit PlannerNode(
53 const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
54
56 ~PlannerNode();
57
63 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
64
70 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
71
77 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
78
84 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
85
91 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
92
98 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
99
104 [[nodiscard]] nav_msgs::msg::Path get_path() const;
105
110 void cycle(std::shared_ptr<NavState> nav_state);
111
112private:
114 std::unique_ptr<pluginlib::ClassLoader<PlannerMethodBase>> planner_loader_;
115
117 std::shared_ptr<PlannerMethodBase> planner_method_ {nullptr};
118};
119
120} // namespace easynav
121
122#endif // EASYNAV_PLANNER__PLANNERNODE_HPP_
A blackboard-like structure to hold the current state of the navigation system.
A generic, type-safe, lock-free blackboard to hold runtime state.
Definition NavState.hpp:62
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition PlannerNode.cpp:116
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition PlannerNode.cpp:70
void cycle(std::shared_ptr< NavState > nav_state)
Execute a non-real-time cycle.
Definition PlannerNode.cpp:153
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition PlannerNode.cpp:139
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Clean up the node.
Definition PlannerNode.cpp:132
nav_msgs::msg::Path get_path() const
Get the current planned path.
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition errors.
Definition PlannerNode.cpp:146
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition PlannerNode.hpp:46
PlannerNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition PlannerNode.cpp:38
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition PlannerNode.cpp:124
Definition RTTFBuffer.hpp:30
Definition PointPerception.hpp:56