Easy Navigation
Loading...
Searching...
No Matches
MapsManagerNode.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_MAPSMANAGER__MAPSMANAGERNODE_HPP_
19#define EASYNAV_MAPSMANAGER__MAPSMANAGERNODE_HPP_
20
21#include "rclcpp/macros.hpp"
22#include "rclcpp_lifecycle/lifecycle_node.hpp"
23
24#include "easynav_core/MapsManagerBase.hpp"
25#include "pluginlib/class_loader.hpp"
26
27namespace easynav
28{
29
36class MapsManagerNode : public rclcpp_lifecycle::LifecycleNode
37{
38public:
39 RCLCPP_SMART_PTR_DEFINITIONS(MapsManagerNode)
40 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
41
47 explicit MapsManagerNode(
48 const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
49
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 void cycle(std::shared_ptr<NavState> nav_state);
100
101private:
103 std::unique_ptr<pluginlib::ClassLoader<MapsManagerBase>> maps_manager_loader_;
104
106 std::vector<std::shared_ptr<MapsManagerBase>> maps_managers_;
107};
108
109} // namespace easynav
110
111#endif // EASYNAV_MAPSMANAGER__MAPSMANAGERNODE_HPP_
MapsManagerNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition MapsManagerNode.cpp:30
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition MapsManagerNode.cpp:104
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition MapsManagerNode.cpp:63
void cycle(std::shared_ptr< NavState > nav_state)
Execute one update cycle (non real-time).
Definition MapsManagerNode.cpp:134
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition MapsManagerNode.cpp:122
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition MapsManagerNode.cpp:116
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle errors during lifecycle transitions.
Definition MapsManagerNode.cpp:128
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition MapsManagerNode.hpp:40
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition MapsManagerNode.cpp:110
A generic, type-safe, thread-safe blackboard to hold runtime state.
Definition NavState.hpp:82
Definition CircularBuffer.hpp:23
Definition PointPerception.hpp:49