Skip to content
This repository was archived by the owner on Oct 8, 2025. It is now read-only.

Commit 291a097

Browse files
committed
update doxygen
1 parent 2f7c2d5 commit 291a097

1 file changed

Lines changed: 36 additions & 15 deletions

File tree

easynav_pointcloud_maps_builder/include/easynav_pointcloud_maps_builder/PointcloudMapsBuilderNode.hpp

Lines changed: 36 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,25 @@
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 PointcloudMapsBuilderNode class.
22+
123
#ifndef EASYNAV_OUTDOOR_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_
224
#define EASYNAV_OUTDOOR_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_
325

@@ -13,12 +35,11 @@ namespace easynav
1335

1436
/**
1537
* @class PointcloudMapsBuilderNode
16-
* @brief Lifecycle node that subscribes to point cloud sensor data and manages map building.
38+
* @brief Lifecycle node that subscribes to point cloud sensor data and manages point cloud map building.
1739
*
18-
* This node handles perception data (point clouds) using multiple MapsBuilder instances
19-
* to generate outdoor maps. It supports ROS2 lifecycle management with clean startup,
20-
* activation, deactivation, and cleanup phases. The node also publishes processed maps
21-
* (e.g., filtered point clouds) for downstream consumption.
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.
2243
*/
2344
class PointcloudMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
2445
{
@@ -29,7 +50,7 @@ class PointcloudMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
2950

3051
/**
3152
* @brief Constructor.
32-
* @param options Options for node initialization.
53+
* @param options Node initialization options.
3354
*/
3455
explicit PointcloudMapsBuilderNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
3556

@@ -67,30 +88,30 @@ class PointcloudMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
6788
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state) override;
6889

6990
/**
70-
* @brief Perform a processing cycle on the perception data and update maps.
91+
* @brief Perform a processing cycle on perception data and update the point cloud map.
7192
*
72-
* This method should be called periodically (e.g., in a timer or main loop) to process
73-
* incoming sensor data, update the internal map representations, and publish outputs.
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.
7495
*/
7596
void cycle();
7697

7798
private:
78-
/// Name of the sensor topic to subscribe to (e.g., point clouds).
99+
/// Sensor topic name to subscribe to point clouds.
79100
std::string sensor_topic_;
80101

81-
/// Collection of perception data managed by this node.
102+
/// Perception data container.
82103
Perceptions perceptions_;
83104

84-
/// Callback group for concurrency management of subscriptions and timers.
105+
/// Callback group for subscription and timers.
85106
rclcpp::CallbackGroup::SharedPtr cbg_;
86107

87-
/// Downsampling resolution applied to point cloud data.
108+
/// Downsampling resolution for point clouds.
88109
double downsample_resolution_;
89110

90-
/// Default frame ID used for perception data and published messages.
111+
/// Default frame ID for perception and publishing.
91112
std::string perception_default_frame_;
92113

93-
/// Publisher for processed (e.g., filtered or downsampled) point cloud map data.
114+
/// Publisher for processed point cloud map.
94115
rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_;
95116
};
96117

0 commit comments

Comments
 (0)