Skip to content

Commit e9000c1

Browse files
committed
Update blackboard
1 parent 01d67d6 commit e9000c1

3 files changed

Lines changed: 102 additions & 37 deletions

File tree

README.md

Lines changed: 23 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ source ~/ros2_ws/install/setup.bash
2424
```
2525
Run the lifecycle node:
2626
```bash
27-
ros2 run easynav_gridmap_maps_builder gridmap_maps_builder_node
27+
ros2 run easynav_gridmap_maps_builder gridmap_maps_builder_main
2828
```
2929

3030
## Parameters
@@ -34,3 +34,25 @@ ros2 run easynav_gridmap_maps_builder gridmap_maps_builder_node
3434
| `sensor_topic` | string | `"points"` | Topic name to subscribe for point cloud data. |
3535
| `downsample_resolution` | double | `1.0` | Resolution used for downsampling the point cloud. |
3636
| `perception_default_frame` | string | `"map"` | Default frame ID for the output grid map. |
37+
38+
## Test
39+
40+
1. Create a parameter YAML file (e.g., `params.yaml`) with the following content:
41+
42+
```yaml
43+
pointcloud_maps_builder_node:
44+
ros__parameters:
45+
use_sim_time: true
46+
sensors: [map]
47+
downsample_resolution: 0.1
48+
perception_default_frame: map
49+
map:
50+
topic: map
51+
type: sensor_msgs/msg/PointCloud2
52+
group: points
53+
```
54+
55+
2. Run the node using the parameter file with this command:
56+
```
57+
ros2 run easynav_gridmap_maps_builder gridmap_maps_builder_main \
58+
--ros-args --params-file src/easynav_gridmap_stack/params.yaml

easynav_gridmap_maps_builder/include/easynav_gridmap_maps_builder/GridmapMapsBuilderNode.hpp

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -97,12 +97,18 @@ class GridmapMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
9797
*/
9898
void cycle();
9999

100+
/**
101+
* @brief Registers a perception handler.
102+
* @param handler Shared pointer to a PerceptionHandler instance.
103+
*/
104+
void register_handler(std::shared_ptr<PerceptionHandler> handler);
105+
100106
private:
101107
/// Name of the sensor topic to subscribe to (e.g., point clouds).
102108
std::string sensor_topic_;
103109

104-
/// Collection of perception data managed by this node.
105-
Perceptions perceptions_;
110+
/// Map of perception data grouped by sensor name.
111+
std::map<std::string, std::vector<PerceptionPtr>> perceptions_;
106112

107113
/// Callback group for concurrency management of subscriptions and timers.
108114
rclcpp::CallbackGroup::SharedPtr cbg_;
@@ -115,6 +121,9 @@ class GridmapMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
115121

116122
/// Publisher for the processed grid map.
117123
rclcpp_lifecycle::LifecyclePublisher<grid_map_msgs::msg::GridMap>::SharedPtr pub_;
124+
125+
/// Registered perception handlers by sensor name.
126+
std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_;
118127
};
119128

120129
} // namespace easynav

easynav_gridmap_maps_builder/src/easynav_gridmap_maps_builder/GridmapMapsBuilderNode.cpp

Lines changed: 68 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
#include <grid_map_ros/grid_map_ros.hpp>
3030

3131
#include "easynav_gridmap_maps_builder/GridmapMapsBuilderNode.hpp"
32-
#include "easynav_common/types/Perceptions.hpp"
32+
#include "easynav_common/types/PointPerception.hpp"
3333

3434
namespace easynav
3535
{
@@ -39,33 +39,34 @@ GridmapMapsBuilderNode::GridmapMapsBuilderNode(const rclcpp::NodeOptions & optio
3939
{
4040
cbg_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
4141

42-
if (!has_parameter("sensor_topic")) {
43-
declare_parameter("sensor_topic", "points");
44-
}
45-
4642
if (!has_parameter("downsample_resolution")) {
4743
declare_parameter("downsample_resolution", 1.0);
4844
}
45+
if (!has_parameter("sensors")) {
46+
declare_parameter("sensors", std::vector<std::string>());
47+
}
4948

5049
if (!has_parameter("perception_default_frame")) {
5150
declare_parameter("perception_default_frame", "map");
5251
}
5352

5453
pub_ = this->create_publisher<grid_map_msgs::msg::GridMap>(
55-
"map_builder/gridmap", rclcpp::QoS(1).transient_local().reliable());
54+
"map_builder_gridmap/gridmap", rclcpp::QoS(1).transient_local().reliable());
55+
56+
register_handler(std::make_shared<PointPerceptionHandler>());
5657
}
5758

5859
GridmapMapsBuilderNode::~GridmapMapsBuilderNode()
5960
{
6061
if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
6162
trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVE_SHUTDOWN);
6263
}
63-
if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
64-
trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_INACTIVE_SHUTDOWN);
65-
}
66-
if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) {
67-
trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN);
68-
}
64+
// if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
65+
// trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_INACTIVE_SHUTDOWN);
66+
// }
67+
// if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) {
68+
// trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN);
69+
// }
6970
}
7071

7172
using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
@@ -75,22 +76,46 @@ GridmapMapsBuilderNode::on_configure(const rclcpp_lifecycle::State & state)
7576
{
7677
(void)state;
7778

78-
get_parameter("sensor_topic", sensor_topic_);
79+
std::vector<std::string> sensors;
80+
get_parameter("sensors", sensors);
7981
get_parameter("downsample_resolution", downsample_resolution_);
8082
get_parameter("perception_default_frame", perception_default_frame_);
8183

82-
auto perception_entry = std::make_shared<Perception>();
83-
perception_entry->data.points.clear();
84-
perception_entry->data.clear();
85-
perception_entry->frame_id = "";
86-
perception_entry->stamp = now();
87-
perception_entry->valid = false;
88-
perception_entry->new_data = true;
84+
for (const auto & sensor_id : sensors) {
85+
std::string topic, msg_type, group;
8986

90-
perceptions_.push_back(perception_entry);
87+
if (!has_parameter(sensor_id + ".topic")) {
88+
declare_parameter(sensor_id + ".topic", topic);
89+
}
90+
if (!has_parameter(sensor_id + ".type")) {
91+
declare_parameter(sensor_id + ".type", msg_type);
92+
}
93+
if (!has_parameter(sensor_id + ".group")) {
94+
declare_parameter(sensor_id + ".group", group);
95+
}
9196

92-
perception_entry->subscription = create_typed_subscription<sensor_msgs::msg::PointCloud2>(
93-
*this, sensor_topic_, perception_entry, cbg_);
97+
get_parameter(sensor_id + ".topic", topic);
98+
get_parameter(sensor_id + ".type", msg_type);
99+
get_parameter(sensor_id + ".group", group);
100+
101+
RCLCPP_DEBUG(get_logger(),
102+
"Loaded sensor parameters: id=%s topic=%s type=%s group=%s",
103+
sensor_id.c_str(), topic.c_str(), msg_type.c_str(), group.c_str());
104+
105+
auto handler_it = handlers_.find(group);
106+
if (handler_it == handlers_.end()) {
107+
RCLCPP_WARN(get_logger(), "No handler for group [%s]", group.c_str());
108+
continue;
109+
}
110+
111+
auto ptr = handler_it->second->create(sensor_id);
112+
auto sub = handler_it->second->create_subscription(*this, topic, msg_type, ptr, cbg_);
113+
114+
perceptions_[group].emplace_back(PerceptionPtr{ptr, sub});
115+
116+
RCLCPP_DEBUG(get_logger(), "Creating perception for sensor %s", sensor_id.c_str());
117+
RCLCPP_DEBUG(get_logger(), "Handler group = %s", group.c_str());
118+
}
94119

95120
return CallbackReturnT::SUCCESS;
96121
}
@@ -125,24 +150,26 @@ GridmapMapsBuilderNode::on_cleanup(const rclcpp_lifecycle::State & state)
125150
void GridmapMapsBuilderNode::cycle()
126151
{
127152
// Finish cycle if no new perceptions
128-
if (std::none_of(perceptions_.begin(), perceptions_.end(),
129-
[](const auto & perception)
130-
{return perception && perception->new_data;}))
153+
if (std::none_of(perceptions_["points"].begin(), perceptions_["points"].end(),
154+
[](const auto & p)
155+
{return p.perception->new_data;}))
131156
{
132157
return;
133158
}
134159

135160
if (pub_->get_subscription_count() > 0) {
136-
auto processed_perceptions = PerceptionsOpsView(perceptions_);
161+
auto point_perceptions = get_point_perceptions(perceptions_["points"]);
162+
auto processed_perceptions = PointPerceptionsOpsView(point_perceptions);
137163
// Fuse perceptions if the frame_id is different from default and downsample
138-
if (!perceptions_.empty() && perceptions_[0] &&
139-
perceptions_[0]->frame_id != perception_default_frame_)
164+
if (!point_perceptions.empty() && point_perceptions[0] &&
165+
point_perceptions[0]->frame_id != perception_default_frame_)
140166
{
141167
processed_perceptions.downsample(downsample_resolution_).fuse(perception_default_frame_);
142168
} else {
143169
processed_perceptions.downsample(downsample_resolution_);
144170
}
145171

172+
146173
auto downsampled_points = processed_perceptions.as_points();
147174
if (downsampled_points.empty()) {
148175
return;
@@ -152,8 +179,8 @@ void GridmapMapsBuilderNode::cycle()
152179
grid_map::GridMap map({"elevation"});
153180
map.setFrameId(perception_default_frame_);
154181

155-
if (perceptions_[0]->stamp.nanoseconds() != 0) {
156-
map.setTimestamp(perceptions_[0]->stamp.nanoseconds());
182+
if (point_perceptions[0]->stamp.nanoseconds() != 0) {
183+
map.setTimestamp(point_perceptions[0]->stamp.nanoseconds());
157184
} else {
158185
map.setTimestamp(now().nanoseconds());
159186
}
@@ -201,11 +228,18 @@ void GridmapMapsBuilderNode::cycle()
201228
pub_->publish(std::move(msg));
202229

203230
// Mark perceptions as not new after published
204-
for (auto & perception : perceptions_) {
205-
if (perception->new_data) {
206-
perception->new_data = false;
231+
for (auto & p : perceptions_["points"]) {
232+
if (p.perception->new_data) {
233+
p.perception->new_data = false;
207234
}
208235
}
209236
}
210237
}
238+
239+
void
240+
GridmapMapsBuilderNode::register_handler(std::shared_ptr<PerceptionHandler> handler)
241+
{
242+
handlers_[handler->group()] = handler;
243+
}
244+
211245
} // namespace easynav

0 commit comments

Comments
 (0)