18#ifndef EASYNAV_SENSORS__SENSORNODE_HPP_
19#define EASYNAV_SENSORS__SENSORNODE_HPP_
21#include <unordered_map>
23#include "rclcpp/rclcpp.hpp"
24#include "rclcpp/macros.hpp"
25#include "rclcpp_lifecycle/lifecycle_node.hpp"
27#include "sensor_msgs/msg/point_cloud2.hpp"
45 using
CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
54 const
std::
string & group,
63 explicit
SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
132 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
135 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
138 sensor_msgs::msg::PointCloud2 perecption_msg_;
144 std::
string tf_prefix_;
162 const
std::
string & group,
172 template<
std::
size_t I = 0>
173 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:82
Abstract base interface for group-specific perception handlers.
Definition Perceptions.hpp:116
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition SensorsNode.cpp:300
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition SensorsNode.cpp:235
void cycle(std::shared_ptr< NavState > nav_state)
Run one non-real-time processing cycle.
Definition SensorsNode.cpp:369
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition SensorsNode.cpp:327
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition SensorsNode.cpp:320
SensorsNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition SensorsNode.cpp:127
bool cycle_rt(std::shared_ptr< NavState > nav_state, bool trigger=false)
Run one real-time sensor processing cycle.
Definition SensorsNode.cpp:347
rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()
Get the callback group for real-time tasks.
Definition SensorsNode.cpp:341
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition errors.
Definition SensorsNode.cpp:334
void register_handler(std::shared_ptr< PerceptionHandler > handler)
Definition SensorsNode.cpp:408
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:53
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition SensorsNode.hpp:45
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition SensorsNode.cpp:310
Definition CircularBuffer.hpp:23
Definition PointPerception.hpp:49
Represents a perception entry with its state and ROS subscription.
Definition Perceptions.hpp:67