Easy Navigation
Loading...
Searching...
No Matches
SensorsNode.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_SENSORS__SENSORNODE_HPP_
24#define EASYNAV_SENSORS__SENSORNODE_HPP_
25
26#include <unordered_map>
27
28#include "rclcpp/rclcpp.hpp"
29#include "rclcpp/macros.hpp"
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
31
32#include "sensor_msgs/msg/point_cloud2.hpp"
33
36
37namespace easynav
38{
39
46class SensorsNode : public rclcpp_lifecycle::LifecycleNode
47{
48public:
49 RCLCPP_SMART_PTR_DEFINITIONS(SensorsNode)
50 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
51
58 using SensorsHandlerFn = void(*)(
59 const std::string & group,
60 const std::vector<easynav::PerceptionPtr> & perceptions,
61 ::easynav::NavState & ns
62 );
63
68 explicit SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
69
71 ~SensorsNode();
72
78 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
79
85 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
86
92 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
93
99 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
100
106 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
107
113 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
114
119 rclcpp::CallbackGroup::SharedPtr get_real_time_cbg();
120
126 bool cycle_rt(std::shared_ptr<NavState> nav_state, bool trigger = false);
127
131 void cycle(std::shared_ptr<NavState> nav_state);
132
133 void register_handler(std::shared_ptr<PerceptionHandler> handler);
134
135private:
137 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
138
140 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
141
143 sensor_msgs::msg::PointCloud2 perecption_msg_;
144
146 double forget_time_;
147
149 std::string tf_prefix_;
150
152 std::shared_ptr<NavState> nav_state_;
153
154 std::map<std::string, std::vector<PerceptionPtr>> perceptions_;
155 std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_;
156
158 std::unordered_map<std::string, SensorsHandlerFn> group_to_handler_;
159
166 bool set_by_group(
167 const std::string & group,
168 const std::vector<PerceptionPtr> & perceptions,
169 ::easynav::NavState & ns
170 );
171
177 template<std::size_t I = 0>
178 void populate_group_to_handler_map();
179};
180
181} // namespace easynav
182
183#endif // EASYNAV_SENSORS__SENSORNODE_HPP_
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