forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtime_synchronizer_nodelet.cpp
608 lines (543 loc) · 22.2 KB
/
time_synchronizer_nodelet.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
// Copyright 2023 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* @brief PointCloudDataSynchronizerComponent class
*
* subscribe: pointclouds, twists
* publish: timestamp "synchronized" pointclouds
*
* @author Yoshi Ri
*/
#include "pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp"
#include <pcl_ros/transforms.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <algorithm>
#include <memory>
#include <string>
#include <utility>
#include <vector>
// postfix for output topics
#define DEFAULT_SYNC_TOPIC_POSTFIX "_synchronized"
//////////////////////////////////////////////////////////////////////////////////////////////
namespace pointcloud_preprocessor
{
PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
const rclcpp::NodeOptions & node_options)
: Node("point_cloud_time_synchronizer_component", node_options),
input_twist_topic_type_(declare_parameter<std::string>("input_twist_topic_type", "twist"))
{
// initialize debug tool
{
using tier4_autoware_utils::DebugPublisher;
using tier4_autoware_utils::StopWatch;
stop_watch_ptr_ = std::make_unique<StopWatch<std::chrono::milliseconds>>();
debug_publisher_ = std::make_unique<DebugPublisher>(this, "time_synchronizer");
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}
// Set parameters
std::string synchronized_pointcloud_postfix;
{
output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
if (output_frame_.empty()) {
RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!");
return;
}
declare_parameter("input_topics", std::vector<std::string>());
input_topics_ = get_parameter("input_topics").as_string_array();
if (input_topics_.empty()) {
RCLCPP_ERROR(get_logger(), "Need a 'input_topics' parameter to be set before continuing!");
return;
}
if (input_topics_.size() == 1) {
RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue.");
return;
}
// output topic name postfix
synchronized_pointcloud_postfix =
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");
// Optional parameters
maximum_queue_size_ = static_cast<int>(declare_parameter("max_queue_size", 5));
timeout_sec_ = static_cast<double>(declare_parameter("timeout_sec", 0.1));
input_offset_ = declare_parameter("input_offset", std::vector<double>{});
if (!input_offset_.empty() && input_topics_.size() != input_offset_.size()) {
RCLCPP_ERROR(get_logger(), "The number of topics does not match the number of offsets.");
return;
}
}
// Initialize not_subscribed_topic_names_
{
for (const std::string & e : input_topics_) {
not_subscribed_topic_names_.insert(e);
}
}
// Initialize offset map
{
for (size_t i = 0; i < input_offset_.size(); ++i) {
offset_map_[input_topics_[i]] = input_offset_[i];
}
}
// tf2 listener
{
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
tf2_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
}
// Subscribers
{
RCLCPP_INFO_STREAM(
get_logger(), "Subscribing to " << input_topics_.size() << " user given topics as inputs:");
for (auto & input_topic : input_topics_) {
RCLCPP_INFO_STREAM(get_logger(), " - " << input_topic);
}
// Subscribe to the filters
filters_.resize(input_topics_.size());
// First input_topics_.size () filters are valid
for (size_t d = 0; d < input_topics_.size(); ++d) {
cloud_stdmap_.insert(std::make_pair(input_topics_[d], nullptr));
cloud_stdmap_tmp_ = cloud_stdmap_;
// CAN'T use auto type here.
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)> cb = std::bind(
&PointCloudDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1,
input_topics_[d]);
filters_[d].reset();
filters_[d] = this->create_subscription<sensor_msgs::msg::PointCloud2>(
input_topics_[d], rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), cb);
}
// Subscribe to the twist
if (input_twist_topic_type_ == "twist") {
auto twist_cb = std::bind(
&PointCloudDataSynchronizerComponent::twist_callback, this, std::placeholders::_1);
sub_twist_ = this->create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"~/input/twist", rclcpp::QoS{100}, twist_cb);
} else if (input_twist_topic_type_ == "odom") {
auto odom_cb =
std::bind(&PointCloudDataSynchronizerComponent::odom_callback, this, std::placeholders::_1);
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>(
"~/input/odom", rclcpp::QoS{100}, odom_cb);
} else {
RCLCPP_ERROR_STREAM(
get_logger(), "input_twist_topic_type is invalid: " << input_twist_topic_type_);
throw std::runtime_error("input_twist_topic_type is invalid: " + input_twist_topic_type_);
}
}
// Transformed Raw PointCloud2 Publisher
{
for (auto & topic : input_topics_) {
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix);
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
transformed_raw_pc_publisher_map_.insert({topic, publisher});
}
}
// Set timer
{
const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(timeout_sec_));
timer_ = rclcpp::create_timer(
this, get_clock(), period_ns,
std::bind(&PointCloudDataSynchronizerComponent::timer_callback, this));
}
// Diagnostic Updater
{
updater_.setHardwareID("synchronize_data_checker");
updater_.add("concat_status", this, &PointCloudDataSynchronizerComponent::checkSyncStatus);
}
}
std::string PointCloudDataSynchronizerComponent::replaceSyncTopicNamePostfix(
const std::string & original_topic_name, const std::string & postfix)
{
std::string replaced_topic_name;
// separate the topic name by '/' and replace the last element with the new postfix
size_t pos = original_topic_name.find_last_of("/");
if (pos == std::string::npos) {
// not found '/': this is not a namespaced topic
RCLCPP_WARN_STREAM(
get_logger(),
"The topic name is not namespaced. The postfix will be added to the end of the topic name.");
return original_topic_name + postfix;
} else {
// replace the last element with the new postfix
replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix;
}
// if topic name is the same with original topic name, add postfix to the end of the topic name
if (replaced_topic_name == original_topic_name) {
RCLCPP_WARN_STREAM(
get_logger(), "The topic name "
<< original_topic_name
<< " have the same postfix with synchronized pointcloud. We use the postfix "
"to the end of the topic name.");
replaced_topic_name = original_topic_name + DEFAULT_SYNC_TOPIC_POSTFIX;
}
return replaced_topic_name;
}
//////////////////////////////////////////////////////////////////////////////////////////////
// overloaded functions
void PointCloudDataSynchronizerComponent::transformPointCloud(
const PointCloud2::ConstSharedPtr & in, PointCloud2::SharedPtr & out)
{
transformPointCloud(in, out, output_frame_);
}
void PointCloudDataSynchronizerComponent::transformPointCloud(
const PointCloud2::ConstSharedPtr & in, PointCloud2::SharedPtr & out,
const std::string & target_frame)
{
// Transform the point clouds into the specified output frame
if (target_frame != in->header.frame_id) {
// TODO(YamatoAndo): use TF2
if (!pcl_ros::transformPointCloud(target_frame, *in, *out, *tf2_buffer_)) {
RCLCPP_ERROR(
this->get_logger(),
"[transformPointCloud] Error converting first input dataset from %s to %s.",
in->header.frame_id.c_str(), target_frame.c_str());
return;
}
} else {
out = std::make_shared<PointCloud2>(*in);
}
}
/**
* @brief compute transform to adjust for old timestamp
*
* @param old_stamp
* @param new_stamp
* @return Eigen::Matrix4f: transformation matrix from new_stamp to old_stamp
*/
Eigen::Matrix4f PointCloudDataSynchronizerComponent::computeTransformToAdjustForOldTimestamp(
const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp)
{
// return identity if no twist is available or old_stamp is newer than new_stamp
if (twist_ptr_queue_.empty() || old_stamp > new_stamp) {
return Eigen::Matrix4f::Identity();
}
auto old_twist_ptr_it = std::lower_bound(
std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), old_stamp,
[](const geometry_msgs::msg::TwistStamped::ConstSharedPtr & x_ptr, const rclcpp::Time & t) {
return rclcpp::Time(x_ptr->header.stamp) < t;
});
old_twist_ptr_it =
old_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : old_twist_ptr_it;
auto new_twist_ptr_it = std::lower_bound(
std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), new_stamp,
[](const geometry_msgs::msg::TwistStamped::ConstSharedPtr & x_ptr, const rclcpp::Time & t) {
return rclcpp::Time(x_ptr->header.stamp) < t;
});
new_twist_ptr_it =
new_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : new_twist_ptr_it;
auto prev_time = old_stamp;
double x = 0.0;
double y = 0.0;
double yaw = 0.0;
for (auto twist_ptr_it = old_twist_ptr_it; twist_ptr_it != new_twist_ptr_it + 1; ++twist_ptr_it) {
const double dt =
(twist_ptr_it != new_twist_ptr_it)
? (rclcpp::Time((*twist_ptr_it)->header.stamp) - rclcpp::Time(prev_time)).seconds()
: (rclcpp::Time(new_stamp) - rclcpp::Time(prev_time)).seconds();
if (std::fabs(dt) > 0.1) {
RCLCPP_WARN_STREAM_THROTTLE(
get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(),
"Time difference is too large. Cloud not interpolate. Please confirm twist topic and "
"timestamp");
break;
}
const double dis = (*twist_ptr_it)->twist.linear.x * dt;
yaw += (*twist_ptr_it)->twist.angular.z * dt;
x += dis * std::cos(yaw);
y += dis * std::sin(yaw);
prev_time = (*twist_ptr_it)->header.stamp;
}
Eigen::AngleAxisf rotation_x(0, Eigen::Vector3f::UnitX());
Eigen::AngleAxisf rotation_y(0, Eigen::Vector3f::UnitY());
Eigen::AngleAxisf rotation_z(yaw, Eigen::Vector3f::UnitZ());
Eigen::Translation3f translation(x, y, 0);
Eigen::Matrix4f rotation_matrix = (translation * rotation_z * rotation_y * rotation_x).matrix();
return rotation_matrix;
}
std::map<std::string, sensor_msgs::msg::PointCloud2::SharedPtr>
PointCloudDataSynchronizerComponent::synchronizeClouds()
{
// map for storing the transformed point clouds
std::map<std::string, sensor_msgs::msg::PointCloud2::SharedPtr> transformed_clouds;
// Step1. gather stamps and sort it
std::vector<rclcpp::Time> pc_stamps;
for (const auto & e : cloud_stdmap_) {
transformed_clouds[e.first] = nullptr;
if (e.second != nullptr) {
if (e.second->data.size() == 0) {
continue;
}
pc_stamps.push_back(rclcpp::Time(e.second->header.stamp));
}
}
if (pc_stamps.empty()) {
return transformed_clouds;
}
// sort stamps and get oldest stamp
std::sort(pc_stamps.begin(), pc_stamps.end());
std::reverse(pc_stamps.begin(), pc_stamps.end());
const auto oldest_stamp = pc_stamps.back();
// Step2. Calculate compensation transform and concatenate with the oldest stamp
for (const auto & e : cloud_stdmap_) {
if (e.second != nullptr) {
// transform pointcloud
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr(
new sensor_msgs::msg::PointCloud2());
sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr(
new sensor_msgs::msg::PointCloud2());
if (e.second->data.size() == 0) {
// gather transformed clouds
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;
continue;
}
// transform pointcloud to output frame
transformPointCloud(e.second, transformed_cloud_ptr);
// calculate transforms to oldest stamp and transform pointcloud to oldest stamp
Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity();
rclcpp::Time transformed_stamp = rclcpp::Time(e.second->header.stamp);
for (const auto & stamp : pc_stamps) {
const auto new_to_old_transform =
computeTransformToAdjustForOldTimestamp(stamp, transformed_stamp);
adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform;
transformed_stamp = std::min(transformed_stamp, stamp);
}
pcl_ros::transformPointCloud(
adjust_to_old_data_transform, *transformed_cloud_ptr,
*transformed_delay_compensated_cloud_ptr);
// gather transformed clouds
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;
} else {
not_subscribed_topic_names_.insert(e.first);
}
}
return transformed_clouds;
}
void PointCloudDataSynchronizerComponent::publish()
{
stop_watch_ptr_->toc("processing_time", true);
not_subscribed_topic_names_.clear();
const auto & transformed_raw_points = PointCloudDataSynchronizerComponent::synchronizeClouds();
// publish transformed raw pointclouds
for (const auto & e : transformed_raw_points) {
if (e.second) {
auto output = std::make_unique<sensor_msgs::msg::PointCloud2>(*e.second);
transformed_raw_pc_publisher_map_[e.first]->publish(std::move(output));
} else {
RCLCPP_WARN(
this->get_logger(), "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.",
e.first.c_str());
}
}
updater_.force_update();
cloud_stdmap_ = cloud_stdmap_tmp_;
std::for_each(std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_), [](auto & e) {
e.second = nullptr;
});
// add processing time for debug
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
}
}
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void PointCloudDataSynchronizerComponent::convertToXYZICloud(
const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr,
sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr)
{
output_ptr->header = input_ptr->header;
PointCloud2Modifier<PointXYZI> output_modifier{*output_ptr, input_ptr->header.frame_id};
output_modifier.reserve(input_ptr->width);
bool has_intensity = std::any_of(
input_ptr->fields.begin(), input_ptr->fields.end(),
[](auto & field) { return field.name == "intensity"; });
sensor_msgs::PointCloud2Iterator<float> it_x(*input_ptr, "x");
sensor_msgs::PointCloud2Iterator<float> it_y(*input_ptr, "y");
sensor_msgs::PointCloud2Iterator<float> it_z(*input_ptr, "z");
if (has_intensity) {
sensor_msgs::PointCloud2Iterator<float> it_i(*input_ptr, "intensity");
for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i) {
PointXYZI point;
point.x = *it_x;
point.y = *it_y;
point.z = *it_z;
point.intensity = *it_i;
output_modifier.push_back(std::move(point));
}
} else {
for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) {
PointXYZI point;
point.x = *it_x;
point.y = *it_y;
point.z = *it_z;
point.intensity = 0.0f;
output_modifier.push_back(std::move(point));
}
}
}
void PointCloudDataSynchronizerComponent::setPeriod(const int64_t new_period)
{
if (!timer_) {
return;
}
int64_t old_period = 0;
rcl_ret_t ret = rcl_timer_get_period(timer_->get_timer_handle().get(), &old_period);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't get old period");
}
ret = rcl_timer_exchange_period(timer_->get_timer_handle().get(), new_period, &old_period);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't exchange_period");
}
}
void PointCloudDataSynchronizerComponent::cloud_callback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name)
{
std::lock_guard<std::mutex> lock(mutex_);
auto input = std::make_shared<sensor_msgs::msg::PointCloud2>(*input_ptr);
sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2());
if (input->data.size() > 0) {
convertToXYZICloud(input, xyzi_input_ptr);
}
const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr);
const bool is_already_subscribed_tmp = std::any_of(
std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_),
[](const auto & e) { return e.second != nullptr; });
if (is_already_subscribed_this) {
cloud_stdmap_tmp_[topic_name] = xyzi_input_ptr;
if (!is_already_subscribed_tmp) {
auto period = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(timeout_sec_));
try {
setPeriod(period.count());
} catch (rclcpp::exceptions::RCLError & ex) {
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what());
}
timer_->reset();
}
} else {
cloud_stdmap_[topic_name] = xyzi_input_ptr;
const bool is_subscribed_all = std::all_of(
std::begin(cloud_stdmap_), std::end(cloud_stdmap_),
[](const auto & e) { return e.second != nullptr; });
if (is_subscribed_all) {
for (const auto & e : cloud_stdmap_tmp_) {
if (e.second != nullptr) {
cloud_stdmap_[e.first] = e.second;
}
}
std::for_each(std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_), [](auto & e) {
e.second = nullptr;
});
timer_->cancel();
publish();
} else if (offset_map_.size() > 0) {
timer_->cancel();
auto period = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(timeout_sec_ - offset_map_[topic_name]));
try {
setPeriod(period.count());
} catch (rclcpp::exceptions::RCLError & ex) {
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what());
}
timer_->reset();
}
}
}
void PointCloudDataSynchronizerComponent::timer_callback()
{
using std::chrono_literals::operator""ms;
timer_->cancel();
if (mutex_.try_lock()) {
publish();
mutex_.unlock();
} else {
try {
std::chrono::nanoseconds period = 10ms;
setPeriod(period.count());
} catch (rclcpp::exceptions::RCLError & ex) {
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what());
}
timer_->reset();
}
}
void PointCloudDataSynchronizerComponent::twist_callback(
const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input)
{
// if rosbag restart, clear buffer
if (!twist_ptr_queue_.empty()) {
if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > rclcpp::Time(input->header.stamp)) {
twist_ptr_queue_.clear();
}
}
// pop old data
while (!twist_ptr_queue_.empty()) {
if (
rclcpp::Time(twist_ptr_queue_.front()->header.stamp) + rclcpp::Duration::from_seconds(1.0) >
rclcpp::Time(input->header.stamp)) {
break;
}
twist_ptr_queue_.pop_front();
}
auto twist_ptr = std::make_shared<geometry_msgs::msg::TwistStamped>();
twist_ptr->header.stamp = input->header.stamp;
twist_ptr->twist = input->twist.twist;
twist_ptr_queue_.push_back(twist_ptr);
}
void PointCloudDataSynchronizerComponent::odom_callback(
const nav_msgs::msg::Odometry::ConstSharedPtr input)
{
// if rosbag restart, clear buffer
if (!twist_ptr_queue_.empty()) {
if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > rclcpp::Time(input->header.stamp)) {
twist_ptr_queue_.clear();
}
}
// pop old data
while (!twist_ptr_queue_.empty()) {
if (
rclcpp::Time(twist_ptr_queue_.front()->header.stamp) + rclcpp::Duration::from_seconds(1.0) >
rclcpp::Time(input->header.stamp)) {
break;
}
twist_ptr_queue_.pop_front();
}
auto twist_ptr = std::make_shared<geometry_msgs::msg::TwistStamped>();
twist_ptr->header.stamp = input->header.stamp;
twist_ptr->twist = input->twist.twist;
twist_ptr_queue_.push_back(twist_ptr);
}
void PointCloudDataSynchronizerComponent::checkSyncStatus(
diagnostic_updater::DiagnosticStatusWrapper & stat)
{
for (const std::string & e : input_topics_) {
const std::string subscribe_status = not_subscribed_topic_names_.count(e) ? "NG" : "OK";
stat.add(e, subscribe_status);
}
const int8_t level = not_subscribed_topic_names_.empty()
? diagnostic_msgs::msg::DiagnosticStatus::OK
: diagnostic_msgs::msg::DiagnosticStatus::WARN;
const std::string message = not_subscribed_topic_names_.empty()
? "Concatenate all topics"
: "Some topics are not concatenated";
stat.summary(level, message);
}
} // namespace pointcloud_preprocessor
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PointCloudDataSynchronizerComponent)