Skip to content

Commit 00a18a9

Browse files
committedFeb 25, 2025
feat(autoware_universe_utils): rework impl
Signed-off-by: Amadeusz Szymko <amadeusz.szymko.2@tier4.jp>
2 parents 600a1d5 + 1e35619 commit 00a18a9

17 files changed

+74
-56
lines changed
 

‎perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,8 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio
118118

119119
pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
120120

121-
managed_tf_buffer_ = std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this);
121+
managed_tf_buffer_ =
122+
std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this->get_clock());
122123

123124
bool use_time_keeper = declare_parameter<bool>("publish_processing_time_detail");
124125
if (use_time_keeper) {
@@ -226,7 +227,9 @@ void RANSACGroundFilterComponent::filter(
226227
std::scoped_lock lock(mutex_);
227228
sensor_msgs::msg::PointCloud2::SharedPtr input_transformed_ptr(new sensor_msgs::msg::PointCloud2);
228229

229-
if (!managed_tf_buffer_->transformPointcloud(base_frame_, *input, *input_transformed_ptr)) {
230+
if (!managed_tf_buffer_->transformPointcloud(
231+
base_frame_, *input, *input_transformed_ptr, input->header.stamp,
232+
rclcpp::Duration::from_seconds(1.0))) {
230233
RCLCPP_ERROR_STREAM_THROTTLE(
231234
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
232235
"Failed transform from " << base_frame_ << " to " << input->header.frame_id);
@@ -311,7 +314,8 @@ void RANSACGroundFilterComponent::filter(
311314
sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_transformed_msg_ptr(
312315
new sensor_msgs::msg::PointCloud2);
313316
if (!managed_tf_buffer_->transformPointcloud(
314-
base_frame_, *no_ground_cloud_msg_ptr, *no_ground_cloud_transformed_msg_ptr)) {
317+
base_frame_, *no_ground_cloud_msg_ptr, *no_ground_cloud_transformed_msg_ptr,
318+
no_ground_cloud_msg_ptr->header.stamp, rclcpp::Duration::from_seconds(1.0))) {
315319
RCLCPP_ERROR_STREAM_THROTTLE(
316320
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
317321
"Failed transform from " << base_frame_ << " to "

‎sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
/**:
22
ros__parameters:
33
debug_mode: false
4-
has_static_tf_only: false
54
rosbag_length: 10.0
65
maximum_queue_size: 5
76
timeout_sec: 0.2

‎sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@
2424
// ROS includes
2525
#include "autoware/point_types/types.hpp"
2626

27-
#include <autoware/universe_utils/ros/managed_transform_buffer.hpp>
2827
#include <diagnostic_updater/diagnostic_updater.hpp>
28+
#include <managed_transform_buffer/managed_transform_buffer.hpp>
2929
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>
3030

3131
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
@@ -65,7 +65,7 @@ class CombineCloudHandler
6565
bool is_motion_compensated_;
6666
bool publish_synchronized_pointcloud_;
6767
bool keep_input_frame_in_synchronized_pointcloud_;
68-
std::unique_ptr<autoware::universe_utils::ManagedTransformBuffer> managed_tf_buffer_{nullptr};
68+
std::unique_ptr<managed_transform_buffer::ManagedTransformBuffer> managed_tf_buffer_{nullptr};
6969

7070
std::deque<geometry_msgs::msg::TwistStamped> twist_queue_;
7171

@@ -92,8 +92,7 @@ class CombineCloudHandler
9292
public:
9393
CombineCloudHandler(
9494
rclcpp::Node & node, std::string output_frame, bool is_motion_compensated,
95-
bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud,
96-
bool has_static_tf_only);
95+
bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud);
9796
void process_twist(
9897
const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg);
9998
void process_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_msg);

‎sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,6 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
6565
{
6666
bool use_naive_approach;
6767
bool debug_mode;
68-
bool has_static_tf_only;
6968
double rosbag_length;
7069
int maximum_queue_size;
7170
double timeout_sec;

‎sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,8 @@ class DistortionCorrectorBase
8686
public:
8787
explicit DistortionCorrectorBase(rclcpp::Node & node) : node_(node)
8888
{
89-
managed_tf_buffer_ = std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(&node);
89+
managed_tf_buffer_ =
90+
std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(node_.get_clock());
9091
}
9192

9293
virtual ~DistortionCorrectorBase() = default;

‎sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,8 @@
2323
#include <autoware_lanelet2_extension/utility/query.hpp>
2424

2525
#include <lanelet2_core/geometry/Polygon.h>
26+
#include <tf2_ros/buffer.h>
27+
#include <tf2_ros/transform_listener.h>
2628

2729
#include <memory>
2830
#include <string>

‎sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json

-6
Original file line numberDiff line numberDiff line change
@@ -11,11 +11,6 @@
1111
"default": false,
1212
"description": "Flag to enables debug mode to display additional logging information."
1313
},
14-
"has_static_tf_only": {
15-
"type": "boolean",
16-
"default": false,
17-
"description": "Flag to indicate if only static TF is used."
18-
},
1914
"rosbag_length": {
2015
"type": "number",
2116
"default": 10.0,
@@ -132,7 +127,6 @@
132127
},
133128
"required": [
134129
"debug_mode",
135-
"has_static_tf_only",
136130
"rosbag_length",
137131
"maximum_queue_size",
138132
"timeout_sec",

‎sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp

+8-5
Original file line numberDiff line numberDiff line change
@@ -32,15 +32,14 @@ namespace autoware::pointcloud_preprocessor
3232

3333
CombineCloudHandler::CombineCloudHandler(
3434
rclcpp::Node & node, std::string output_frame, bool is_motion_compensated,
35-
bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud,
36-
bool has_static_tf_only)
35+
bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud)
3736
: node_(node),
3837
output_frame_(std::move(output_frame)),
3938
is_motion_compensated_(is_motion_compensated),
4039
publish_synchronized_pointcloud_(publish_synchronized_pointcloud),
4140
keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud),
4241
managed_tf_buffer_(
43-
std::make_unique<autoware::universe_utils::ManagedTransformBuffer>(&node_, has_static_tf_only))
42+
std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(node_.get_clock()))
4443
{
4544
}
4645

@@ -219,7 +218,9 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds(
219218
convert_to_xyzirc_cloud(cloud, xyzirc_cloud);
220219

221220
auto transformed_cloud_ptr = std::make_shared<sensor_msgs::msg::PointCloud2>();
222-
managed_tf_buffer_->transformPointcloud(output_frame_, *xyzirc_cloud, *transformed_cloud_ptr);
221+
managed_tf_buffer_->transformPointcloud(
222+
output_frame_, *xyzirc_cloud, *transformed_cloud_ptr, xyzirc_cloud->header.stamp,
223+
rclcpp::Duration::from_seconds(1.0));
223224

224225
concatenate_cloud_result.topic_to_original_stamp_map[topic] =
225226
rclcpp::Time(cloud->header.stamp).seconds();
@@ -251,7 +252,9 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds(
251252
std::make_shared<sensor_msgs::msg::PointCloud2>();
252253
managed_tf_buffer_->transformPointcloud(
253254
cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr,
254-
*transformed_cloud_ptr_in_sensor_frame);
255+
*transformed_cloud_ptr_in_sensor_frame,
256+
transformed_delay_compensated_cloud_ptr->header.stamp,
257+
rclcpp::Duration::from_seconds(1.0));
255258
transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp;
256259
transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id;
257260

‎sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,6 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
4848

4949
// initialize parameters
5050
params_.debug_mode = declare_parameter<bool>("debug_mode");
51-
params_.has_static_tf_only = declare_parameter<bool>("has_static_tf_only");
5251
params_.rosbag_length = declare_parameter<double>("rosbag_length");
5352
params_.maximum_queue_size = static_cast<size_t>(declare_parameter<int>("maximum_queue_size"));
5453
params_.timeout_sec = declare_parameter<double>("timeout_sec");
@@ -140,8 +139,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
140139
// Combine cloud handler
141140
combine_cloud_handler_ = std::make_shared<CombineCloudHandler>(
142141
*this, params_.output_frame, params_.is_motion_compensated,
143-
params_.publish_synchronized_pointcloud, params_.keep_input_frame_in_synchronized_pointcloud,
144-
params_.has_static_tf_only);
142+
params_.publish_synchronized_pointcloud, params_.keep_input_frame_in_synchronized_pointcloud);
145143

146144
// Diagnostic Updater
147145
diagnostic_updater_.setHardwareID("concatenate_data_checker");

‎sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

Whitespace-only changes.

‎sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,8 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent(
9393

9494
// tf2 listener
9595
{
96-
managed_tf_buffer_ = std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this);
96+
managed_tf_buffer_ =
97+
std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this->get_clock());
9798
}
9899

99100
// Output Publishers
@@ -237,7 +238,9 @@ void PointCloudConcatenationComponent::combineClouds(
237238
// transform to output frame
238239
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr(
239240
new sensor_msgs::msg::PointCloud2());
240-
managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr);
241+
managed_tf_buffer_->transformPointcloud(
242+
output_frame_, *e.second, *transformed_cloud_ptr, e.second->header.stamp,
243+
rclcpp::Duration::from_seconds(1.0));
241244

242245
// concatenate
243246
if (concat_cloud_ptr == nullptr) {

‎sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+25-16
Original file line numberDiff line numberDiff line change
@@ -88,11 +88,18 @@ void DistortionCorrectorBase::get_imu_transformation(
8888
return;
8989
}
9090

91-
auto msg_imu_to_base_link =
92-
managed_tf_buffer_->getTransform<geometry_msgs::msg::TransformStamped>(base_frame, imu_frame);
91+
Eigen::Matrix4f eigen_imu_to_base_link;
92+
auto eigen_transform = managed_tf_buffer_->getTransform<Eigen::Matrix4f>(
93+
base_frame, imu_frame, node_.now(), rclcpp::Duration::from_seconds(1.0));
94+
imu_transform_exists_ = eigen_transform.has_value();
95+
if (eigen_transform.has_value()) {
96+
eigen_imu_to_base_link = eigen_transform.value();
97+
}
98+
tf2::Transform tf2_imu_to_base_link = convert_matrix_to_transform(eigen_imu_to_base_link);
9399

94100
geometry_imu_to_base_link_ptr_ = std::make_shared<geometry_msgs::msg::TransformStamped>();
95-
geometry_imu_to_base_link_ptr_->transform.rotation = msg_imu_to_base_link->transform.rotation;
101+
geometry_imu_to_base_link_ptr_->transform.rotation =
102+
tf2::toMsg(tf2_imu_to_base_link.getRotation());
96103
}
97104

98105
void DistortionCorrectorBase::enqueue_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg)
@@ -429,13 +436,15 @@ void DistortionCorrector2D::set_pointcloud_transform(
429436
return;
430437
}
431438

432-
auto tf2_lidar_to_base_link =
433-
managed_tf_buffer_->getTransform<tf2::Transform>(base_frame, lidar_frame);
434-
if (tf2_lidar_to_base_link.has_value()) {
435-
pointcloud_transform_exists_ = true;
436-
tf2_lidar_to_base_link_ = tf2_lidar_to_base_link.value();
437-
tf2_base_link_to_lidar_ = tf2_lidar_to_base_link.value().inverse();
439+
Eigen::Matrix4f eigen_lidar_to_base_link;
440+
auto eigen_transform = managed_tf_buffer_->getTransform<Eigen::Matrix4f>(
441+
base_frame, lidar_frame, node_.now(), rclcpp::Duration::from_seconds(1.0));
442+
pointcloud_transform_exists_ = eigen_transform.has_value();
443+
if (eigen_transform.has_value()) {
444+
eigen_lidar_to_base_link = eigen_transform.value();
438445
}
446+
tf2_lidar_to_base_link_ = convert_matrix_to_transform(eigen_lidar_to_base_link);
447+
tf2_base_link_to_lidar_ = tf2_lidar_to_base_link_.inverse();
439448
pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_;
440449
}
441450

@@ -446,14 +455,14 @@ void DistortionCorrector3D::set_pointcloud_transform(
446455
return;
447456
}
448457

449-
auto eigen_lidar_to_base_link =
450-
managed_tf_buffer_->getTransform<Eigen::Matrix4f>(base_frame, lidar_frame);
451-
pointcloud_transform_exists_ = eigen_lidar_to_base_link.has_value();
452-
pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_;
453-
if (pointcloud_transform_needed_) {
454-
eigen_lidar_to_base_link_ = eigen_lidar_to_base_link.value();
455-
eigen_base_link_to_lidar_ = eigen_lidar_to_base_link.value().inverse();
458+
auto eigen_transform = managed_tf_buffer_->getTransform<Eigen::Matrix4f>(
459+
base_frame, lidar_frame, node_.now(), rclcpp::Duration::from_seconds(1.0));
460+
pointcloud_transform_exists_ = eigen_transform.has_value();
461+
if (eigen_transform.has_value()) {
462+
eigen_lidar_to_base_link_ = eigen_transform.value();
456463
}
464+
eigen_base_link_to_lidar_ = eigen_lidar_to_base_link_.inverse();
465+
pointcloud_transform_needed_ = base_frame != lidar_frame && pointcloud_transform_exists_;
457466
}
458467

459468
inline void DistortionCorrector2D::undistort_point_implementation(

‎sensing/autoware_pointcloud_preprocessor/src/filter.cpp

+12-6
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,8 @@ autoware::pointcloud_preprocessor::Filter::Filter(
114114
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
115115
void autoware::pointcloud_preprocessor::Filter::setupTF()
116116
{
117-
managed_tf_buffer_ = std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this);
117+
managed_tf_buffer_ =
118+
std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this->get_clock());
118119
}
119120

120121
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -269,7 +270,9 @@ void autoware::pointcloud_preprocessor::Filter::input_indices_callback(
269270
// Convert the cloud into the different frame
270271
PointCloud2 cloud_transformed;
271272

272-
if (!managed_tf_buffer_->transformPointcloud(tf_input_frame_, *cloud, cloud_transformed)) {
273+
if (!managed_tf_buffer_->transformPointcloud(
274+
tf_input_frame_, *cloud, cloud_transformed, cloud->header.stamp,
275+
rclcpp::Duration::from_seconds(1.0))) {
273276
return;
274277
}
275278
cloud_tf = std::make_shared<PointCloud2>(cloud_transformed);
@@ -298,8 +301,8 @@ bool autoware::pointcloud_preprocessor::Filter::calculate_transform_matrix(
298301
this->get_logger(), "[get_transform_matrix] Transforming input dataset from %s to %s.",
299302
from.header.frame_id.c_str(), target_frame.c_str());
300303

301-
auto eigen_transform =
302-
managed_tf_buffer_->getTransform<Eigen::Matrix4f>(target_frame, from.header.frame_id);
304+
auto eigen_transform = managed_tf_buffer_->getTransform<Eigen::Matrix4f>(
305+
target_frame, from.header.frame_id, from.header.stamp, rclcpp::Duration::from_seconds(1.0));
303306
if (!eigen_transform.has_value()) {
304307
return false;
305308
}
@@ -322,7 +325,9 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly(
322325
// Convert the cloud into the different frame
323326
auto cloud_transformed = std::make_unique<PointCloud2>();
324327

325-
if (!managed_tf_buffer_->transformPointcloud(tf_output_frame_, *output, *cloud_transformed)) {
328+
if (!managed_tf_buffer_->transformPointcloud(
329+
tf_output_frame_, *output, *cloud_transformed, output->header.stamp,
330+
rclcpp::Duration::from_seconds(1.0))) {
326331
RCLCPP_ERROR(
327332
this->get_logger(),
328333
"[convert_output_costly] Error converting output dataset from %s to %s.",
@@ -343,7 +348,8 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly(
343348
auto cloud_transformed = std::make_unique<PointCloud2>();
344349

345350
if (!managed_tf_buffer_->transformPointcloud(
346-
tf_input_orig_frame_, *output, *cloud_transformed)) {
351+
tf_input_orig_frame_, *output, *cloud_transformed, output->header.stamp,
352+
rclcpp::Duration::from_seconds(1.0))) {
347353
return false;
348354
}
349355

‎sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp

+8-3
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,8 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
110110

111111
// tf2 listener
112112
{
113-
managed_tf_buffer_ = std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this);
113+
managed_tf_buffer_ =
114+
std::make_unique<managed_transform_buffer::ManagedTransformBuffer>(this->get_clock());
114115
}
115116

116117
// Subscribers
@@ -321,7 +322,9 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
321322
continue;
322323
}
323324
// transform pointcloud to output frame
324-
managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr);
325+
managed_tf_buffer_->transformPointcloud(
326+
output_frame_, *e.second, *transformed_cloud_ptr, e.second->header.stamp,
327+
rclcpp::Duration::from_seconds(1.0));
325328

326329
// calculate transforms to oldest stamp and transform pointcloud to oldest stamp
327330
Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity();
@@ -343,7 +346,9 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
343346
new sensor_msgs::msg::PointCloud2());
344347
managed_tf_buffer_->transformPointcloud(
345348
e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr,
346-
*transformed_delay_compensated_cloud_ptr_in_input_frame);
349+
*transformed_delay_compensated_cloud_ptr_in_input_frame,
350+
transformed_delay_compensated_cloud_ptr->header.stamp,
351+
rclcpp::Duration::from_seconds(1.0));
347352
transformed_delay_compensated_cloud_ptr =
348353
transformed_delay_compensated_cloud_ptr_in_input_frame;
349354
}

‎sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py

-1
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,6 @@ def generate_test_description():
8787
parameters=[
8888
{
8989
"debug_mode": False,
90-
"has_static_tf_only": False,
9190
"rosbag_length": 0.0,
9291
"maximum_queue_size": 5,
9392
"timeout_sec": TIMEOUT_SEC,

‎sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,6 @@ class ConcatenateCloudTest : public ::testing::Test
4646
// They just helps to setup the concatenate node
4747
node_options.parameter_overrides(
4848
{{"debug_mode", false},
49-
{"has_static_tf_only", false},
5049
{"rosbag_length", 0.0},
5150
{"maximum_queue_size", 5},
5251
{"timeout_sec", 0.2},
@@ -67,7 +66,7 @@ class ConcatenateCloudTest : public ::testing::Test
6766
node_options);
6867
combine_cloud_handler_ =
6968
std::make_shared<autoware::pointcloud_preprocessor::CombineCloudHandler>(
70-
*concatenate_node_, "base_link", true, true, true, false);
69+
*concatenate_node_, "base_link", true, true, true);
7170

7271
collector_ = std::make_shared<autoware::pointcloud_preprocessor::CloudCollector>(
7372
std::dynamic_pointer_cast<

‎sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,6 @@
4646
#include <tuple>
4747
#include <vector>
4848

49-
std::chrono::milliseconds managed_transform_buffer::ManagedTransformBuffer::default_timeout =
50-
std::chrono::milliseconds(100); // Relax timeout for CI
5149
enum AngleCoordinateSystem { HESAI, VELODYNE, CARTESIAN };
5250
class DistortionCorrectorTest : public ::testing::Test
5351
{

0 commit comments

Comments
 (0)