Easy Navigation
Loading...
Searching...
No Matches
PlannerNode.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
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
17
18#ifndef EASYNAV_PLANNER__PLANNERNODE_HPP_
19#define EASYNAV_PLANNER__PLANNERNODE_HPP_
20
21#include "rclcpp/macros.hpp"
22#include "rclcpp_lifecycle/lifecycle_node.hpp"
23#include "easynav_core/PlannerMethodBase.hpp"
24#include "pluginlib/class_loader.hpp"
25#include "nav_msgs/msg/path.hpp"
27
28namespace easynav
29{
30
37class PlannerNode : public rclcpp_lifecycle::LifecycleNode
38{
39public:
40 RCLCPP_SMART_PTR_DEFINITIONS(PlannerNode)
41 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
42
47 explicit PlannerNode(
48 const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
49
51 ~PlannerNode();
52
58 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
59
65 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
66
72 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
73
79 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
80
86 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
87
93 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
94
99 [[nodiscard]] nav_msgs::msg::Path get_path() const;
100
106 void cycle(std::shared_ptr<NavState> nav_state, bool trigger = false);
107
112 const rclcpp::Time get_last_rt_execution_ts() const;
113
118 const rclcpp::Time get_last_execution_ts() const;
119
120private:
122 std::unique_ptr<pluginlib::ClassLoader<PlannerMethodBase>> planner_loader_;
123
125 std::shared_ptr<PlannerMethodBase> planner_method_ {nullptr};
126};
127
128} // namespace easynav
129
130#endif // EASYNAV_PLANNER__PLANNERNODE_HPP_
A blackboard-like structure to hold the current state of the navigation system.
A generic, type-safe, thread-safe blackboard to hold runtime state.
Definition NavState.hpp:82
void cycle(std::shared_ptr< NavState > nav_state, bool trigger=false)
Execute a non-real-time cycle.
Definition PlannerNode.cpp:136
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition PlannerNode.cpp:106
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition PlannerNode.cpp:62
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition PlannerNode.cpp:124
const rclcpp::Time get_last_execution_ts() const
Get the timestamp of the last non-RT execution.
Definition PlannerNode.cpp:156
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Clean up the node.
Definition PlannerNode.cpp:118
nav_msgs::msg::Path get_path() const
Get the current planned path.
const rclcpp::Time get_last_rt_execution_ts() const
Get the timestamp of the last real-time execution.
Definition PlannerNode.cpp:148
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition errors.
Definition PlannerNode.cpp:130
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition PlannerNode.hpp:41
PlannerNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition PlannerNode.cpp:30
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition PlannerNode.cpp:112
Definition CircularBuffer.hpp:23
Definition PointPerception.hpp:49