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 "rclcpp/rclcpp.hpp"
27#include "rclcpp/macros.hpp"
28#include "rclcpp_lifecycle/lifecycle_node.hpp"
29
30#include "tf2_ros/buffer.h"
31#include "tf2_ros/transform_listener.h"
32
33#include "sensor_msgs/msg/point_cloud2.hpp"
34
37
38namespace easynav
39{
40
47class SensorsNode : public rclcpp_lifecycle::LifecycleNode
48{
49public:
50 RCLCPP_SMART_PTR_DEFINITIONS(SensorsNode)
51 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
52
57 explicit SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
58
60 ~SensorsNode();
61
67 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
68
74 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
75
81 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
82
88 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
89
95 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
96
102 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
103
108 rclcpp::CallbackGroup::SharedPtr get_real_time_cbg();
109
115 bool cycle_rt(std::shared_ptr<NavState> nav_state, bool trigger = false);
116
120 void cycle(std::shared_ptr<NavState> nav_state);
121
122 void register_handler(std::shared_ptr<PerceptionHandler> handler);
123
124private:
126 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
127
129 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
130
132 sensor_msgs::msg::PointCloud2 perecption_msg_;
133
135 double forget_time_;
136
138 std::string perception_default_frame_;
139
140 std::shared_ptr<NavState> nav_state_;
141
142 std::map<std::string, std::vector<PerceptionPtr>> perceptions_;
143 std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_;
144};
145
146} // namespace easynav
147
148#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, 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