Easy Navigation
Loading...
Searching...
No Matches
SystemNode.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_SYSTEM__SYSTEMNODE_HPP_
24#define EASYNAV_SYSTEM__SYSTEMNODE_HPP_
25
26#include "rclcpp/rclcpp.hpp"
27#include "rclcpp/macros.hpp"
28#include "rclcpp_lifecycle/lifecycle_node.hpp"
29
30#include "geometry_msgs/msg/twist.hpp"
31#include "geometry_msgs/msg/twist_stamped.hpp"
32#include "std_msgs/msg/string.hpp"
33
41
42namespace easynav
43{
44
50{
51 rclcpp_lifecycle::LifecycleNode::SharedPtr node_ptr;
52 rclcpp::CallbackGroup::SharedPtr realtime_cbg;
53};
54
62class SystemNode : public rclcpp_lifecycle::LifecycleNode
63{
64public:
65 RCLCPP_SMART_PTR_DEFINITIONS(SystemNode)
66 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
67
72 explicit SystemNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
73
75 ~SystemNode();
76
82 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
83
89 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
90
96 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
97
103 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
104
110 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
111
117 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
118
123 rclcpp::CallbackGroup::SharedPtr get_real_time_cbg();
124
129 std::map<std::string, SystemNodeInfo> get_system_nodes();
130
134 void system_cycle_rt();
135
139 void system_cycle();
140
141private:
143 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
144
146 ControllerNode::SharedPtr controller_node_;
147
149 LocalizerNode::SharedPtr localizer_node_;
150
152 MapsManagerNode::SharedPtr maps_manager_node_;
153
155 PlannerNode::SharedPtr planner_node_;
156
158 SensorsNode::SharedPtr sensors_node_;
159
161 std::shared_ptr<NavState> nav_state_;
162
164 GoalManager::SharedPtr goal_manager_;
165
167 bool use_cmd_vel_stamped_ {false};
168
170 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr navstate_pub_;
171
173 rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr vel_pub_stamped_;
174
176 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr vel_pub_;
177};
178
179} // namespace easynav
180
181#endif // EASYNAV_SYSTEM__SYSTEMNODE_HPP_
Declaration of the ControllerNode class, a ROS 2 lifecycle node for speed computation in Easy Navigat...
Declaration of the GoalManager class.
Declaration of the LocalizerNode class, a ROS 2 lifecycle node for localization tasks in Easy Navigat...
Declaration of the MapsManagerNode class, a ROS 2 lifecycle node for map handling in Easy Navigation.
A blackboard-like structure to hold the current state of the navigation system.
Declaration of the PlannerNode class, a ROS 2 lifecycle node for computing navigation paths in Easy N...
Declaration of the SensorsNode class, a ROS 2 lifecycle node for sensor fusion tasks in Easy Navigati...
ROS 2 lifecycle node that manages calculating speeds for the Easy Navigation system.
Definition ControllerNode.hpp:46
Handles navigation goals, their lifecycle, and command interface.
Definition GoalManager.hpp:48
ROS 2 lifecycle node that manages localization in Easy Navigation.
Definition LocalizerNode.hpp:44
ROS 2 lifecycle node that manages map-related plugins in Easy Navigation.
Definition MapsManagerNode.hpp:42
A generic, type-safe, thread-safe blackboard to hold runtime state.
Definition NavState.hpp:87
ROS 2 lifecycle node that manages path planning in Easy Navigation.
Definition PlannerNode.hpp:43
ROS 2 lifecycle node that manages sensor fusion in Easy Navigation.
Definition SensorsNode.hpp:47
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition SystemNode.cpp:144
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition SystemNode.cpp:94
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition SystemNode.cpp:193
std::map< std::string, SystemNodeInfo > get_system_nodes()
Get all system nodes managed by this coordinator.
Definition SystemNode.cpp:267
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition SystemNode.cpp:186
rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()
Get the real-time callback group.
Definition SystemNode.cpp:207
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition error.
Definition SystemNode.cpp:200
SystemNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition SystemNode.cpp:42
void system_cycle()
Non-real-time system cycle.
Definition SystemNode.cpp:243
void system_cycle_rt()
Real-time system cycle.
Definition SystemNode.cpp:213
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition SystemNode.hpp:66
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition SystemNode.cpp:165
Definition CircularBuffer.hpp:28
Definition PointPerception.hpp:54
Structure holding runtime information for a subnode.
Definition SystemNode.hpp:50
rclcpp::CallbackGroup::SharedPtr realtime_cbg
Associated real-time callback group.
Definition SystemNode.hpp:52
rclcpp_lifecycle::LifecycleNode::SharedPtr node_ptr
Shared pointer to the managed lifecycle node.
Definition SystemNode.hpp:51