Skip to content

Commit

Permalink
chore: fix conflicts
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Sep 18, 2024
1 parent e115c63 commit ac66c5f
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 11 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
/**:
ros__parameters:
has_static_tf_only: false
maximum_queue_size: 5
timeout_sec: 0.2
is_motion_compensated: true
Expand All @@ -16,4 +17,3 @@
output_frame: base_link
lidar_timestamp_offsets: [0.0, 0.04, 0.08]
lidar_timestamp_noise_window: [0.01, 0.01, 0.01]
has_static_tf_only: false
Original file line number Diff line number Diff line change
Expand Up @@ -92,12 +92,11 @@ class CombineCloudHandler
{
private:
rclcpp::Node * node_;
std::unique_ptr<autoware::universe_utils::StaticTransformBuffer> managed_tf_buffer_{nullptr};

std::vector<std::string> input_topics_;
std::string output_frame_;
bool is_motion_compensated_;
bool keep_input_frame_in_synchronized_pointcloud_;
std::unique_ptr<autoware::universe_utils::ManagedTransformBuffer> managed_tf_buffer_{nullptr};

struct RclcppTimeHash_
{
Expand All @@ -112,7 +111,8 @@ class CombineCloudHandler

CombineCloudHandler(
rclcpp::Node * node, std::vector<std::string> input_topics, std::string output_frame,
bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud);
bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud,
bool has_static_tf_only);
void processTwist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input);
void processOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ CombineCloudHandler::CombineCloudHandler(
output_frame_(output_frame),
is_motion_compensated_(is_motion_compensated),
keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud),
managed_tf_buffer_ =
std::make_unique<autoware::universe_utils::ManagedTransformBuffer>(this, has_static_tf_only)
managed_tf_buffer_(
std::make_unique<autoware::universe_utils::ManagedTransformBuffer>(node_, has_static_tf_only))
{
}

Expand Down Expand Up @@ -156,8 +156,7 @@ CombineCloudHandler::combinePointClouds(
sensor_msgs::msg::PointCloud2::SharedPtr cloud = pair.second;

auto transformed_cloud_ptr = std::make_shared<sensor_msgs::msg::PointCloud2>();
managed_tf_buffer_->transformPointcloud(
output_frame_, cloud->header.frame_id, *transformed_cloud_ptr);
managed_tf_buffer_->transformPointcloud(output_frame_, *cloud, *transformed_cloud_ptr);

topic_to_original_stamp_map[topic] = rclcpp::Time(cloud->header.stamp).seconds();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@ class ConcatenateCloudTest : public ::testing::Test
// Instead of "input_topics", other parameters are not unsed.
// They just helps to setup the concatenate node
node_options.parameter_overrides(
{{"maximum_queue_size", 5},
{{"has_static_tf_only", false},
{"maximum_queue_size", 5},
{"timeout_sec", 0.2},
{"is_motion_compensated", true},
{"publish_synchronized_pointcloud", true},
Expand All @@ -60,7 +61,7 @@ class ConcatenateCloudTest : public ::testing::Test
combine_cloud_handler_ =
std::make_shared<autoware::pointcloud_preprocessor::CombineCloudHandler>(
concatenate_node_.get(), std::vector<std::string>{"lidar_top", "lidar_left", "lidar_right"},
"base_link", true, true);
"base_link", true, true, false);

collector_ = std::make_shared<autoware::pointcloud_preprocessor::CloudCollector>(
std::dynamic_pointer_cast<
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ def generate_test_description():
],
parameters=[
{
"has_static_tf_only": False,
"maximum_queue_size": 5,
"timeout_sec": TIMEOUT_SEC,
"is_motion_compensated": True,
Expand Down Expand Up @@ -470,7 +471,7 @@ def test_2_normal_inputs_with_noise(self):
cloud_arr = get_output_points(self.msg_buffer[0])
print("cloud_arr: ", cloud_arr)
self.assertTrue(
np.allclose(cloud_arr, expected_pointcloud, atol=1e-2),
np.allclose(cloud_arr, expected_pointcloud, atol=2e-2),
"The concatenation node have wierd output",
)

Expand Down

0 comments on commit ac66c5f

Please sign in to comment.