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
32namespace easynav
33{
34
41class SensorsNode : public rclcpp_lifecycle::LifecycleNode
42{
43public:
44 RCLCPP_SMART_PTR_DEFINITIONS(SensorsNode)
45 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
46
53 using SensorsHandlerFn = void(*)(
54 const std::string & group,
55 const std::vector<easynav::PerceptionPtr> & perceptions,
56 ::easynav::NavState & ns
57 );
58
63 explicit SensorsNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
64
66 ~SensorsNode();
67
73 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
74
80 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
81
87 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
88
94 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
95
101 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
102
108 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
109
114 rclcpp::CallbackGroup::SharedPtr get_real_time_cbg();
115
121 bool cycle_rt(std::shared_ptr<NavState> nav_state, bool trigger = false);
122
126 void cycle(std::shared_ptr<NavState> nav_state);
127
128 void register_handler(std::shared_ptr<PerceptionHandler> handler);
129
130private:
132 rclcpp::CallbackGroup::SharedPtr realtime_cbg_;
133
135 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr percept_pub_;
136
138 sensor_msgs::msg::PointCloud2 perecption_msg_;
139
141 double forget_time_;
142
144 std::string tf_prefix_;
145
147 std::shared_ptr<NavState> nav_state_;
148
149 std::map<std::string, std::vector<PerceptionPtr>> perceptions_;
150 std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_;
151
153 std::unordered_map<std::string, SensorsHandlerFn> group_to_handler_;
154
161 bool set_by_group(
162 const std::string & group,
163 const std::vector<PerceptionPtr> & perceptions,
164 ::easynav::NavState & ns
165 );
166
172 template<std::size_t I = 0>
173 void populate_group_to_handler_map();
174};
175
176} // namespace easynav
177
178#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: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