|
1 | 1 | // Copyright 2025 Intelligent Robotics Lab |
2 | 2 | // |
3 | | -// This file is part of the project Easy Navigation (EasyNav in sh0rt) |
| 3 | +// This file is part of the project Easy Navigation (EasyNav in short) |
4 | 4 | // licensed under the GNU General Public License v3.0. |
5 | 5 | // See <http://www.gnu.org/licenses/> for details. |
6 | 6 | // |
|
17 | 17 | // You should have received a copy of the GNU General Public License |
18 | 18 | // along with this program. If not, see <http://www.gnu.org/licenses/>. |
19 | 19 |
|
| 20 | + |
20 | 21 | /// \file |
21 | 22 | /// \brief Definition of the PointcloudMapsBuilderNode class. |
22 | 23 |
|
23 | | -#ifndef EASYNAV_OUTDOOR_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_ |
24 | | -#define EASYNAV_OUTDOOR_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_ |
| 24 | +#ifndef EASYNAV_POINTCLOUD_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_ |
| 25 | +#define EASYNAV_POINTCLOUD_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_ |
| 26 | + |
| 27 | +#include <string> |
| 28 | +#include <memory> |
| 29 | +#include <map> |
| 30 | +#include <vector> |
25 | 31 |
|
26 | 32 | #include "rclcpp/rclcpp.hpp" |
27 | 33 | #include "rclcpp/macros.hpp" |
|
33 | 39 | namespace easynav |
34 | 40 | { |
35 | 41 |
|
36 | | -/** |
37 | | - * @class PointcloudMapsBuilderNode |
38 | | - * @brief Lifecycle node that subscribes to point cloud sensor data and manages point cloud map building. |
39 | | - * |
40 | | - * This node processes perception data (point clouds) to build and update point cloud maps. |
41 | | - * It leverages ROS 2 lifecycle for clean startup, activation, deactivation, and cleanup phases. |
42 | | - * The node publishes processed (filtered or downsampled) point cloud maps for downstream use. |
43 | | - */ |
| 42 | + /** |
| 43 | + * @class PointcloudMapsBuilderNode |
| 44 | + * @brief Lifecycle node that subscribes to point cloud sensor data and manages point cloud map building. |
| 45 | + * |
| 46 | + * This node processes perception data (point clouds) to build and update point cloud maps. |
| 47 | + * It leverages ROS 2 lifecycle for clean startup, activation, deactivation, and cleanup phases. |
| 48 | + * The node publishes processed (filtered or downsampled) point cloud maps for downstream use. |
| 49 | + */ |
44 | 50 | class PointcloudMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode |
45 | 51 | { |
46 | 52 | public: |
47 | 53 | RCLCPP_SMART_PTR_DEFINITIONS(PointcloudMapsBuilderNode) |
48 | | - |
49 | 54 | using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; |
50 | 55 |
|
51 | | - /** |
52 | | - * @brief Constructor. |
53 | | - * @param options Node initialization options. |
54 | | - */ |
| 56 | + /** |
| 57 | + * @brief Constructor. |
| 58 | + * @param options Node initialization options. |
| 59 | + */ |
55 | 60 | explicit PointcloudMapsBuilderNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); |
56 | 61 |
|
57 | | - /** |
58 | | - * @brief Destructor. |
59 | | - */ |
| 62 | + /** |
| 63 | + * @brief Destructor. |
| 64 | + */ |
60 | 65 | ~PointcloudMapsBuilderNode(); |
61 | 66 |
|
62 | | - /** |
63 | | - * @brief Lifecycle configure callback. |
64 | | - * @param state Current lifecycle state. |
65 | | - * @return CallbackReturnT indicating success or failure. |
66 | | - */ |
| 67 | + /** |
| 68 | + * @brief Lifecycle configure callback. |
| 69 | + * @param state Current lifecycle state. |
| 70 | + * @return CallbackReturnT indicating success or failure. |
| 71 | + */ |
67 | 72 | CallbackReturnT on_configure(const rclcpp_lifecycle::State & state) override; |
68 | 73 |
|
69 | | - /** |
70 | | - * @brief Lifecycle activate callback. |
71 | | - * @param state Current lifecycle state. |
72 | | - * @return CallbackReturnT indicating success or failure. |
73 | | - */ |
| 74 | + /** |
| 75 | + * @brief Lifecycle activate callback. |
| 76 | + * @param state Current lifecycle state. |
| 77 | + * @return CallbackReturnT indicating success or failure. |
| 78 | + */ |
74 | 79 | CallbackReturnT on_activate(const rclcpp_lifecycle::State & state) override; |
75 | 80 |
|
76 | | - /** |
77 | | - * @brief Lifecycle deactivate callback. |
78 | | - * @param state Current lifecycle state. |
79 | | - * @return CallbackReturnT indicating success or failure. |
80 | | - */ |
| 81 | + /** |
| 82 | + * @brief Lifecycle deactivate callback. |
| 83 | + * @param state Current lifecycle state. |
| 84 | + * @return CallbackReturnT indicating success or failure. |
| 85 | + */ |
81 | 86 | CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state) override; |
82 | 87 |
|
83 | | - /** |
84 | | - * @brief Lifecycle cleanup callback. |
85 | | - * @param state Current lifecycle state. |
86 | | - * @return CallbackReturnT indicating success or failure. |
87 | | - */ |
| 88 | + /** |
| 89 | + * @brief Lifecycle cleanup callback. |
| 90 | + * @param state Current lifecycle state. |
| 91 | + * @return CallbackReturnT indicating success or failure. |
| 92 | + */ |
88 | 93 | CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state) override; |
89 | 94 |
|
90 | | - /** |
91 | | - * @brief Perform a processing cycle on perception data and update the point cloud map. |
92 | | - * |
93 | | - * This should be called periodically (e.g., in a timer or main loop) to process incoming sensor data, |
94 | | - * update internal map representations, and publish outputs. |
95 | | - */ |
| 95 | + /** |
| 96 | + * @brief Perform a processing cycle on perception data and update the point cloud map. |
| 97 | + * |
| 98 | + * This should be called periodically (e.g., in a timer or main loop) to process incoming sensor data, |
| 99 | + * update internal map representations, and publish outputs. |
| 100 | + */ |
96 | 101 | void cycle(); |
97 | 102 |
|
98 | | -private: |
99 | | - /// Sensor topic name to subscribe to point clouds. |
100 | | - std::string sensor_topic_; |
101 | | - |
102 | | - /// Perception data container. |
103 | | - Perceptions perceptions_; |
| 103 | + /** |
| 104 | + * @brief Registers a perception handler. |
| 105 | + * @param handler Shared pointer to a PerceptionHandler instance. |
| 106 | + */ |
| 107 | + void register_handler(std::shared_ptr<PerceptionHandler> handler); |
104 | 108 |
|
105 | | - /// Callback group for subscription and timers. |
| 109 | +private: |
| 110 | + /// Callback group used for subscriptions and timers. |
106 | 111 | rclcpp::CallbackGroup::SharedPtr cbg_; |
107 | 112 |
|
108 | | - /// Downsampling resolution for point clouds. |
| 113 | + /// Downsampling resolution for point clouds. |
109 | 114 | double downsample_resolution_; |
110 | 115 |
|
111 | | - /// Default frame ID for perception and publishing. |
| 116 | + /// Default frame ID used for perception and publishing. |
112 | 117 | std::string perception_default_frame_; |
113 | 118 |
|
114 | | - /// Publisher for processed point cloud map. |
| 119 | + /// Lifecycle publisher for the processed point cloud map. |
115 | 120 | rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_; |
| 121 | + |
| 122 | + /// Map of perception data grouped by sensor name. |
| 123 | + std::map<std::string, std::vector<PerceptionPtr>> perceptions_; |
| 124 | + |
| 125 | + /// Registered perception handlers by sensor name. |
| 126 | + std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_; |
116 | 127 | }; |
117 | 128 |
|
118 | 129 | } // namespace easynav |
119 | 130 |
|
120 | | -#endif // EASYNAV_OUTDOOR_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_ |
| 131 | +#endif // EASYNAV_POINTCLOUD_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_ |
0 commit comments