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

Commit 4949f7f

Browse files
committed
support blackboard, update cmake
1 parent 3c030c9 commit 4949f7f

7 files changed

Lines changed: 187 additions & 113 deletions

File tree

README.md

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,3 +36,25 @@ Run the lifecycle node:
3636
```bash
3737
ros2 run easynav_pointcloud_maps_builder pointcloud_maps_builder_node
3838
```
39+
## Test
40+
41+
1. Create a parameter YAML file (e.g., `params.yaml`) with the following content:
42+
43+
```yaml
44+
pointcloud_maps_builder_node:
45+
ros__parameters:
46+
use_sim_time: true
47+
sensors: [map]
48+
downsample_resolution: 0.1
49+
perception_default_frame: map
50+
map:
51+
topic: map
52+
type: sensor_msgs/msg/PointCloud2
53+
group: points
54+
```
55+
56+
2. Run the node using the parameter file with this command:
57+
```
58+
ros2 run easynav_pointcloud_maps_builder pointcloud_maps_builder_main \
59+
--ros-args --params-file src/easynav_pointcloud_stack/params.yaml
60+
```

easynav_pointcloud_maps_builder/CMakeLists.txt

Lines changed: 20 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -16,26 +16,30 @@ find_package(rclcpp_lifecycle REQUIRED)
1616
find_package(sensor_msgs REQUIRED)
1717
find_package(easynav_common REQUIRED)
1818

19-
set(dependencies
20-
rclcpp
21-
rclcpp_lifecycle
22-
sensor_msgs
23-
easynav_common
24-
)
25-
2619
include_directories(include)
2720

2821
# Library
2922
add_library(${PROJECT_NAME} SHARED
3023
src/easynav_pointcloud_maps_builder/PointcloudMapsBuilderNode.cpp
24+
)
3125

26+
target_link_libraries(${PROJECT_NAME} PUBLIC
27+
rclcpp::rclcpp
28+
rclcpp_lifecycle::rclcpp_lifecycle
29+
sensor_msgs::sensor_msgs_library
30+
easynav_common::easynav_common
3231
)
33-
ament_target_dependencies(${PROJECT_NAME} ${dependencies})
3432

3533
# Executable
3634
add_executable(pointcloud_maps_builder_main src/pointcloud_maps_builder_main.cpp)
37-
ament_target_dependencies(pointcloud_maps_builder_main ${dependencies})
38-
target_link_libraries(pointcloud_maps_builder_main ${PROJECT_NAME})
35+
36+
target_link_libraries(pointcloud_maps_builder_main PUBLIC
37+
${PROJECT_NAME}
38+
rclcpp::rclcpp
39+
rclcpp_lifecycle::rclcpp_lifecycle
40+
sensor_msgs::sensor_msgs_library
41+
easynav_common::easynav_common
42+
)
3943

4044
# Install headers
4145
install(DIRECTORY include/
@@ -54,8 +58,6 @@ install(TARGETS
5458
# Tests
5559
if(BUILD_TESTING)
5660
find_package(ament_lint_auto REQUIRED)
57-
set(ament_cmake_copyright_FOUND TRUE)
58-
set(ament_cmake_cpplint_FOUND TRUE)
5961
ament_lint_auto_find_test_dependencies()
6062

6163
find_package(ament_cmake_gtest REQUIRED)
@@ -65,6 +67,11 @@ endif()
6567
# Export
6668
ament_export_include_directories(include)
6769
ament_export_libraries(${PROJECT_NAME})
68-
ament_export_dependencies(${dependencies})
70+
ament_export_dependencies(
71+
rclcpp
72+
rclcpp_lifecycle
73+
sensor_msgs
74+
easynav_common
75+
)
6976

7077
ament_package()
Lines changed: 67 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
// Copyright 2025 Intelligent Robotics Lab
22
//
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)
44
// licensed under the GNU General Public License v3.0.
55
// See <http://www.gnu.org/licenses/> for details.
66
//
@@ -17,11 +17,17 @@
1717
// You should have received a copy of the GNU General Public License
1818
// along with this program. If not, see <http://www.gnu.org/licenses/>.
1919

20+
2021
/// \file
2122
/// \brief Definition of the PointcloudMapsBuilderNode class.
2223

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>
2531

2632
#include "rclcpp/rclcpp.hpp"
2733
#include "rclcpp/macros.hpp"
@@ -33,88 +39,93 @@
3339
namespace easynav
3440
{
3541

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+
*/
4450
class PointcloudMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
4551
{
4652
public:
4753
RCLCPP_SMART_PTR_DEFINITIONS(PointcloudMapsBuilderNode)
48-
4954
using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
5055

51-
/**
52-
* @brief Constructor.
53-
* @param options Node initialization options.
54-
*/
56+
/**
57+
* @brief Constructor.
58+
* @param options Node initialization options.
59+
*/
5560
explicit PointcloudMapsBuilderNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
5661

57-
/**
58-
* @brief Destructor.
59-
*/
62+
/**
63+
* @brief Destructor.
64+
*/
6065
~PointcloudMapsBuilderNode();
6166

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+
*/
6772
CallbackReturnT on_configure(const rclcpp_lifecycle::State & state) override;
6873

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+
*/
7479
CallbackReturnT on_activate(const rclcpp_lifecycle::State & state) override;
7580

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+
*/
8186
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state) override;
8287

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+
*/
8893
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state) override;
8994

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+
*/
96101
void cycle();
97102

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);
104108

105-
/// Callback group for subscription and timers.
109+
private:
110+
/// Callback group used for subscriptions and timers.
106111
rclcpp::CallbackGroup::SharedPtr cbg_;
107112

108-
/// Downsampling resolution for point clouds.
113+
/// Downsampling resolution for point clouds.
109114
double downsample_resolution_;
110115

111-
/// Default frame ID for perception and publishing.
116+
/// Default frame ID used for perception and publishing.
112117
std::string perception_default_frame_;
113118

114-
/// Publisher for processed point cloud map.
119+
/// Lifecycle publisher for the processed point cloud map.
115120
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_;
116127
};
117128

118129
} // namespace easynav
119130

120-
#endif // EASYNAV_OUTDOOR_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_
131+
#endif // EASYNAV_POINTCLOUD_MAPS_BUILDER__POINTCLOUDMAPSBUILDERNODE_HPP_

0 commit comments

Comments
 (0)