23#ifndef EASYNAV_SYSTEM__SYSTEMNODE_HPP_
24#define EASYNAV_SYSTEM__SYSTEMNODE_HPP_
26#include "rclcpp/rclcpp.hpp"
27#include "rclcpp/macros.hpp"
28#include "rclcpp_lifecycle/lifecycle_node.hpp"
30#include "geometry_msgs/msg/twist.hpp"
31#include "geometry_msgs/msg/twist_stamped.hpp"
50 rclcpp_lifecycle::LifecycleNode::SharedPtr
node_ptr;
65 using
CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
71 explicit
SystemNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
142 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
145 rclcpp::TimerBase::SharedPtr system_main_nort_timer_;
169 rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr vel_pub_stamped_;
172 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr vel_pub_;
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:49
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, lock-free blackboard to hold runtime state.
Definition NavState.hpp:62
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:48
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition SystemNode.cpp:129
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition SystemNode.cpp:106
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition SystemNode.cpp:182
std::map< std::string, SystemNodeInfo > get_system_nodes()
Get all system nodes managed by this coordinator.
Definition SystemNode.cpp:249
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition SystemNode.cpp:175
rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()
Get the real-time callback group.
Definition SystemNode.cpp:196
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition error.
Definition SystemNode.cpp:189
SystemNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition SystemNode.cpp:46
void system_cycle()
Non-real-time system cycle.
Definition SystemNode.cpp:235
void system_cycle_rt()
Real-time system cycle.
Definition SystemNode.cpp:202
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition SystemNode.hpp:65
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition SystemNode.cpp:152
Definition RTTFBuffer.hpp:30
Definition PointPerception.hpp:56
Structure holding runtime information for a subnode.
Definition SystemNode.hpp:49
rclcpp::CallbackGroup::SharedPtr realtime_cbg
Associated real-time callback group.
Definition SystemNode.hpp:51
rclcpp_lifecycle::LifecycleNode::SharedPtr node_ptr
Shared pointer to the managed lifecycle node.
Definition SystemNode.hpp:50