23#ifndef EASYNAV_SENSORS__SENSORNODE_HPP_
24#define EASYNAV_SENSORS__SENSORNODE_HPP_
26#include "rclcpp/rclcpp.hpp"
27#include "rclcpp/macros.hpp"
28#include "rclcpp_lifecycle/lifecycle_node.hpp"
30#include "tf2_ros/buffer.h"
31#include "tf2_ros/transform_listener.h"
33#include "sensor_msgs/msg/point_cloud2.hpp"
51 using
CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
57 explicit
SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
126 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
129 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
132 sensor_msgs::msg::PointCloud2 perecption_msg_;
138 std::
string perception_default_frame_;
A blackboard-like structure to hold the current state of the navigation system.
Defines data structures and utilities for representing and processing sensor perceptions.
A generic, type-safe, lock-free blackboard to hold runtime state.
Definition NavState.hpp:62
Abstract base interface for group-specific perception handlers.
Definition Perceptions.hpp:87
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition SensorsNode.cpp:123
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition SensorsNode.cpp:79
void cycle(std::shared_ptr< NavState > nav_state)
Run one non-real-time processing cycle.
Definition SensorsNode.cpp:190
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition SensorsNode.cpp:150
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition SensorsNode.cpp:143
SensorsNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition SensorsNode.cpp:44
bool cycle_rt(std::shared_ptr< NavState > nav_state, bool trigger=false)
Run one real-time sensor processing cycle.
Definition SensorsNode.cpp:170
rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()
Get the callback group for real-time tasks.
Definition SensorsNode.cpp:164
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition errors.
Definition SensorsNode.cpp:157
void register_handler(std::shared_ptr< PerceptionHandler > handler)
Definition SensorsNode.cpp:218
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition SensorsNode.hpp:51
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition SensorsNode.cpp:133
Definition RTTFBuffer.hpp:30
Definition PointPerception.hpp:56
Represents a perception entry with its state and ROS subscription.
Definition Perceptions.hpp:73