Easy Navigation
Loading...
Searching...
No Matches
SensorsNode.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
17
18#ifndef EASYNAV_SENSORS__SENSORNODE_HPP_
19#define EASYNAV_SENSORS__SENSORNODE_HPP_
20
21#include <unordered_map>
22
23#include "rclcpp/rclcpp.hpp"
24#include "rclcpp/macros.hpp"
25#include "rclcpp_lifecycle/lifecycle_node.hpp"
26
27#include "sensor_msgs/msg/point_cloud2.hpp"
28
31#include "pluginlib/class_loader.hpp"
32
33namespace easynav
34{
35
44class SensorsNode : public rclcpp_lifecycle::LifecycleNode
45{
46public:
47 RCLCPP_SMART_PTR_DEFINITIONS(SensorsNode)
48 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
49
54 explicit SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
55
57 ~SensorsNode();
58
64 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
65
71 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
72
78 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
79
85 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
86
92 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
93
99 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
100
105 rclcpp::CallbackGroup::SharedPtr get_real_time_cbg();
106
112 bool cycle_rt(std::shared_ptr<NavState> nav_state, bool trigger = false);
113
117 void cycle(std::shared_ptr<NavState> nav_state);
118
119protected:
121 std::map<std::string, std::vector<std::string>> groups_;
123 std::vector<std::shared_ptr<PerceptionHandler>> handler_list_;
124
125private:
127 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
128
130 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
131
133 sensor_msgs::msg::PointCloud2 perecption_msg_;
134
136 double forget_time_;
137
139 std::string tf_prefix_;
140
142 bool groups_initialized = false;
143
145 std::unique_ptr<pluginlib::ClassLoader<PerceptionHandler>> handler_loader_;
146
152 std::unordered_map<std::string, std::string> type_to_plugin_;
153
154};
155
156} // namespace easynav
157
158#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:83
Abstract base class for pluginlib-based sensor perception handlers.
Definition Perceptions.hpp:108
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activate the node.
Definition SensorsNode.cpp:162
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configure the node.
Definition SensorsNode.cpp:81
void cycle(std::shared_ptr< NavState > nav_state)
Run one non-real-time processing cycle.
Definition SensorsNode.cpp:223
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown the node.
Definition SensorsNode.cpp:189
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup the node.
Definition SensorsNode.cpp:182
SensorsNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition SensorsNode.cpp:42
std::map< std::string, std::vector< std::string > > groups_
Sensor groups (set as group of keys in the NavState).
Definition SensorsNode.hpp:121
bool cycle_rt(std::shared_ptr< NavState > nav_state, bool trigger=false)
Run one real-time sensor processing cycle.
Definition SensorsNode.cpp:209
rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()
Get the callback group for real-time tasks.
Definition SensorsNode.cpp:203
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Handle lifecycle transition errors.
Definition SensorsNode.cpp:196
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition SensorsNode.hpp:48
std::vector< std::shared_ptr< PerceptionHandler > > handler_list_
vector of PerceptionHandler instances
Definition SensorsNode.hpp:123
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate the node.
Definition SensorsNode.cpp:172
Definition CircularBuffer.hpp:23
Definition PointPerception.hpp:49