1+ // Copyright 2025 Intelligent Robotics Lab
2+ //
3+ // This file is part of the project Easy Navigation (EasyNav in sh0rt)
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+
20+ // / \file
21+ // / \brief Definition of the GridmapMapsBuilderNode class.
22+
123#ifndef EASYNAV_OUTDOOR_MAPS_BUILDER__GRIDMAPMAPSBUILDERNODE_HPP_
224#define EASYNAV_OUTDOOR_MAPS_BUILDER__GRIDMAPMAPSBUILDERNODE_HPP_
325
@@ -15,12 +37,11 @@ namespace easynav
1537
1638/* *
1739 * @class GridmapMapsBuilderNode
18- * @brief Lifecycle node that subscribes to point cloud sensor data and manages map building .
40+ * @brief Lifecycle node that subscribes to point cloud sensor data and builds a grid map .
1941 *
20- * This node handles perception data (point clouds) using multiple MapsBuilder instances
21- * to generate outdoor maps. It supports ROS2 lifecycle management with clean startup,
22- * activation, deactivation, and cleanup phases. The node also publishes processed maps
23- * (e.g., filtered point clouds) for downstream consumption.
42+ * This node processes perception data (point clouds) to generate a single outdoor grid map.
43+ * It uses ROS 2 lifecycle management for clean startup, activation, deactivation, and cleanup.
44+ * The node publishes the resulting grid map for downstream use.
2445 */
2546class GridmapMapsBuilderNode : public rclcpp_lifecycle ::LifecycleNode
2647{
@@ -69,10 +90,10 @@ class GridmapMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
6990 CallbackReturnT on_cleanup (const rclcpp_lifecycle::State & state) override ;
7091
7192 /* *
72- * @brief Perform a processing cycle on the perception data and update maps .
93+ * @brief Perform a processing cycle on the perception data and update the grid map .
7394 *
7495 * This method should be called periodically (e.g., in a timer or main loop) to process
75- * incoming sensor data, update the internal map representations , and publish outputs.
96+ * incoming sensor data, update the internal grid map representation , and publish outputs.
7697 */
7798 void cycle ();
7899
@@ -92,7 +113,7 @@ class GridmapMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
92113 // / Default frame ID used for perception data and published messages.
93114 std::string perception_default_frame_;
94115
95- // / Publisher for processed gridmap map data .
116+ // / Publisher for the processed grid map.
96117 rclcpp_lifecycle::LifecyclePublisher<grid_map_msgs::msg::GridMap>::SharedPtr pub_;
97118};
98119
0 commit comments