23#ifndef EASYNAV_SENSORS__SENSORNODE_HPP_
24#define EASYNAV_SENSORS__SENSORNODE_HPP_
26#include <unordered_map>
28#include "rclcpp/rclcpp.hpp"
29#include "rclcpp/macros.hpp"
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
32#include "sensor_msgs/msg/point_cloud2.hpp"
50 using
CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
59 const
std::
string & group,
68 explicit
SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
137 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
140 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
143 sensor_msgs::msg::PointCloud2 perecption_msg_;
149 std::
string tf_prefix_;
167 const
std::
string & group,
177 template<
std::
size_t I = 0>
178 void populate_group_to_handler_map();
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, thread-safe blackboard to hold runtime state.
Definition NavState.hpp:87
Abstract base interface for group-specific perception handlers.
Definition Perceptions.hpp:121
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition SensorsNode.cpp:305
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition SensorsNode.cpp:240
void cycle(std::shared_ptr< NavState > nav_state)
Run one non-real-time processing cycle.
Definition SensorsNode.cpp:374
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition SensorsNode.cpp:332
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition SensorsNode.cpp:325
SensorsNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition SensorsNode.cpp:132
bool cycle_rt(std::shared_ptr< NavState > nav_state, bool trigger=false)
Run one real-time sensor processing cycle.
Definition SensorsNode.cpp:352
rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()
Get the callback group for real-time tasks.
Definition SensorsNode.cpp:346
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition errors.
Definition SensorsNode.cpp:339
void register_handler(std::shared_ptr< PerceptionHandler > handler)
Definition SensorsNode.cpp:413
void(*)( const std::string &group, const std::vector< easynav::PerceptionPtr > &perceptions, ::easynav::NavState &ns) SensorsHandlerFn
Function pointer type used to handle sensor groups.
Definition SensorsNode.hpp:58
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition SensorsNode.hpp:50
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition SensorsNode.cpp:315
Definition CircularBuffer.hpp:28
Definition PointPerception.hpp:54
Represents a perception entry with its state and ROS subscription.
Definition Perceptions.hpp:72