From 306d8a2e2ac6d305b13ebf5eaffedcf272d9161f Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 19 Sep 2024 11:40:38 +0900 Subject: [PATCH 01/90] chore: rebase main Signed-off-by: vividf --- .../CMakeLists.txt | 15 +- .../concatenate_and_time_sync_node.param.yaml | 18 + .../concatenate_data/cloud_collector.hpp | 117 +++ .../combine_cloud_handler.hpp | 134 +++ ...hpp => concatenate_and_time_sync_node.hpp} | 147 ++-- .../concatenate_and_time_sync_node.launch.xml | 11 + .../cocatenate_and_time_sync_node.schema.json | 98 +++ .../src/concatenate_data/cloud_collector.cpp | 157 ++++ .../combine_cloud_handler.cpp | 301 +++++++ .../concatenate_and_time_sync_node.cpp | 495 +++++++++++ .../concatenate_and_time_sync_nodelet.cpp | 717 ---------------- .../test/test_cloud_collector.cpp | 468 ++++++++++ .../test/test_concatenate_node.py | 797 ++++++++++++++++++ 13 files changed, 2670 insertions(+), 805 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp rename sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/{concatenate_and_time_sync_nodelet.hpp => concatenate_and_time_sync_node.hpp} (62%) create mode 100644 sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp delete mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 02ce2a0098220..8998c1aa38ad7 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -62,7 +62,9 @@ ament_target_dependencies(faster_voxel_grid_downsample_filter ) ament_auto_add_library(pointcloud_preprocessor_filter SHARED - src/concatenate_data/concatenate_and_time_sync_nodelet.cpp + src/concatenate_data/concatenate_and_time_sync_node.cpp + src/concatenate_data/combine_cloud_handler.cpp + src/concatenate_data/cloud_collector.cpp src/concatenate_data/concatenate_pointclouds.cpp src/time_synchronizer/time_synchronizer_node.cpp src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -109,7 +111,7 @@ rclcpp_components_register_node(pointcloud_preprocessor_filter # ========== Concatenate and Sync data ========== rclcpp_components_register_node(pointcloud_preprocessor_filter PLUGIN "autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent" - EXECUTABLE concatenate_data_node) + EXECUTABLE concatenate_and_time_sync_node) # ========== CropBox ========== rclcpp_components_register_node(pointcloud_preprocessor_filter @@ -241,8 +243,17 @@ if(BUILD_TESTING) test/test_distortion_corrector_node.cpp ) + ament_add_gtest(test_cloud_collector + test/test_cloud_collector.cpp + ) + target_link_libraries(test_utilities pointcloud_preprocessor_filter) target_link_libraries(test_distortion_corrector_node pointcloud_preprocessor_filter) + target_link_libraries(test_cloud_collector pointcloud_preprocessor_filter) + add_ros_test( + test/test_concatenate_node.py + TIMEOUT "50" + ) endif() diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml new file mode 100644 index 0000000000000..d023479acf6e3 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -0,0 +1,18 @@ +/**: + ros__parameters: + maximum_queue_size: 5 + timeout_sec: 0.2 + is_motion_compensated: true + publish_synchronized_pointcloud: true + keep_input_frame_in_synchronized_pointcloud: true + publish_previous_but_late_pointcloud: false + synchronized_pointcloud_postfix: pointcloud + input_twist_topic_type: twist + input_topics: [ + "/sensing/lidar/left/pointcloud_before_sync", + "/sensing/lidar/right/pointcloud_before_sync", + "/sensing/lidar/top/pointcloud_before_sync" + ] + output_frame: base_link + lidar_timestamp_offsets: [0.0, 0.04, 0.08] + lidar_timestamp_noise_window: [0.01, 0.01, 0.01] diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp new file mode 100644 index 0000000000000..29085472579c0 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -0,0 +1,117 @@ +// Copyright 2024 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. + +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ + * + */ + +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ + +#include "combine_cloud_handler.hpp" + +#include +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +class PointCloudConcatenateDataSynchronizerComponent; +class CombineCloudHandler; + +class CloudCollector +{ +public: + CloudCollector( + std::shared_ptr concatenate_node, + std::list> & collectors, + std::shared_ptr combine_cloud_handler, int num_of_clouds, double time); + + void setReferenceTimeStamp(double timestamp, double noise_window); + std::tuple getReferenceTimeStampBoundary(); + void processCloud(std::string topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); + void concatenateCallback(); + std::tuple< + sensor_msgs::msg::PointCloud2::SharedPtr, + std::unordered_map, + std::unordered_map> + concatenateClouds( + std::unordered_map topic_to_cloud_map); + + void publishClouds( + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, + std::unordered_map + topic_to_transformed_cloud_map, + std::unordered_map topic_to_original_stamp_map); + + void deleteCollector(); + + std::unordered_map + get_topic_to_cloud_map(); + +private: + std::shared_ptr concatenate_node_; + std::list> & collectors_; + std::shared_ptr combine_cloud_handler_; + rclcpp::TimerBase::SharedPtr timer_; + std::unordered_map topic_to_cloud_map_; + uint64_t num_of_clouds_; + double timeout_sec_; + double reference_timestamp_min_; + double reference_timestamp_max_; + std::mutex mutex_; +}; + +} // namespace autoware::pointcloud_preprocessor + +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ // NOLINT +// clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp new file mode 100644 index 0000000000000..1e51e072928e3 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -0,0 +1,134 @@ +// Copyright 2024 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. + +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ + * + */ + +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include + +// ROS includes +#include "autoware_point_types/types.hpp" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +class CombineCloudHandler +{ +private: + rclcpp::Node * node_; + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + std::vector input_topics_; + std::string output_frame_; + bool is_motion_compensated_; + bool keep_input_frame_in_synchronized_pointcloud_; + + struct RclcppTimeHash_ + { + std::size_t operator()(const rclcpp::Time & t) const + { + return std::hash()(t.nanoseconds()); + } + }; + +public: + std::deque twist_ptr_queue_; + + CombineCloudHandler( + rclcpp::Node * node, std::vector input_topics, std::string output_frame, + bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud); + void processTwist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input); + void processOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input); + + std::tuple< + sensor_msgs::msg::PointCloud2::SharedPtr, + std::unordered_map, + std::unordered_map> + combinePointClouds(std::unordered_map & + topic_to_cloud_map_); + + Eigen::Matrix4f computeTransformToAdjustForOldTimestamp( + const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); +}; + +} // namespace autoware::pointcloud_preprocessor + +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ // NOLINT +// clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp similarity index 62% rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 977adc59cd7e5..1f653b19fdb6a 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -49,19 +49,22 @@ * */ -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ #include -#include +#include #include #include #include #include +#include #include // ROS includes #include "autoware_point_types/types.hpp" +#include "cloud_collector.hpp" +#include "combine_cloud_handler.hpp" #include #include @@ -83,115 +86,87 @@ #include #include #include -#include -#include namespace autoware::pointcloud_preprocessor { + using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; -/** \brief @b PointCloudConcatenateDataSynchronizerComponent is a special form of data - * synchronizer: it listens for a set of input PointCloud messages on the same topic, - * checks their timestamps, and concatenates their fields together into a single - * PointCloud output message. - * \author Radu Bogdan Rusu - */ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node { public: - typedef sensor_msgs::msg::PointCloud2 PointCloud2; - - /** \brief constructor. */ explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); - - /** \brief constructor. - * \param queue_size the maximum queue size - */ - PointCloudConcatenateDataSynchronizerComponent( - const rclcpp::NodeOptions & node_options, int queue_size); - - /** \brief Empty destructor. */ virtual ~PointCloudConcatenateDataSynchronizerComponent() {} + void publishClouds( + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, + std::unordered_map & + topic_to_transformed_cloud_map, + std::unordered_map & topic_to_original_stamp_map, + double reference_timestamp_min, double reference_timestamp_max); private: - /** \brief The output PointCloud publisher. */ - rclcpp::Publisher::SharedPtr pub_output_; - /** \brief Delay Compensated PointCloud publisher*/ - std::map::SharedPtr> - transformed_raw_pc_publisher_map_; - - /** \brief The maximum number of messages that we can store in the queue. */ - int maximum_queue_size_ = 3; - - double timeout_sec_ = 0.1; - - bool publish_synchronized_pointcloud_; - bool keep_input_frame_in_synchronized_pointcloud_; - std::string synchronized_pointcloud_postfix_; - - std::set not_subscribed_topic_names_; - - /** \brief A vector of subscriber. */ - std::vector::SharedPtr> filters_; - - rclcpp::Subscription::SharedPtr sub_twist_; - rclcpp::Subscription::SharedPtr sub_odom_; - - rclcpp::TimerBase::SharedPtr timer_; - diagnostic_updater::Updater updater_{this}; - - const std::string input_twist_topic_type_; - - /** \brief Output TF frame the concatenated points should be transformed to. */ - std::string output_frame_; - - /** \brief The flag to indicate if only static TF are used. */ - bool has_static_tf_only_; - - /** \brief Input point cloud topics. */ - // XmlRpc::XmlRpcValue input_topics_; - std::vector input_topics_; - - std::unique_ptr managed_tf_buffer_{nullptr}; - - std::deque twist_ptr_queue_; - - std::map cloud_stdmap_; - std::map cloud_stdmap_tmp_; + struct Parameters + { + int maximum_queue_size; + double timeout_sec; + bool is_motion_compensated; + bool publish_synchronized_pointcloud; + bool keep_input_frame_in_synchronized_pointcloud; + bool publish_previous_but_late_pointcloud; + std::string synchronized_pointcloud_postfix; + std::string input_twist_topic_type; + std::vector input_topics; + std::string output_frame; + std::vector lidar_timestamp_offsets; + std::vector lidar_timestamp_noise_window; + } params_; + + double current_concat_cloud_timestamp_{0.0}; + double lastest_concat_cloud_timestamp_{0.0}; + bool drop_previous_but_late_pointcloud_{false}; + bool publish_pointcloud_{false}; + double diagnostic_reference_timestamp_min_{0.0}; + double diagnostic_reference_timestamp_max_{0.0}; + std::unordered_map diagnostic_topic_to_original_stamp_map_; + + std::shared_ptr combine_cloud_handler_; + std::shared_ptr cloud_collector_; + std::list> cloud_collectors_; std::mutex mutex_; + std::unordered_map topic_to_offset_map_; + std::unordered_map topic_to_noise_window_map_; + + // subscribers + std::vector::SharedPtr> pointcloud_subs; + rclcpp::Subscription::SharedPtr twist_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + + // publishers + rclcpp::Publisher::SharedPtr concatenate_cloud_publisher_; + std::unordered_map::SharedPtr> + topic_to_transformed_cloud_publisher_map_; + std::unique_ptr debug_publisher_; - std::vector input_offset_; - std::map offset_map_; - - Eigen::Matrix4f computeTransformToAdjustForOldTimestamp( - const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); - std::map combineClouds( - sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr); - void publish(); + std::unique_ptr> stop_watch_ptr_; + diagnostic_updater::Updater updater_{this}; - void convertToXYZIRCCloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, - sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); - void setPeriod(const int64_t new_period); void cloud_callback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, - const std::string & topic_name); + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name); void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input); void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input); - void timer_callback(); + std::string formatTimestamp(double timestamp); void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); std::string replaceSyncTopicNamePostfix( const std::string & original_topic_name, const std::string & postfix); - - /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + void convertToXYZIRCCloud( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, + sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); }; } // namespace autoware::pointcloud_preprocessor // clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ // NOLINT +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ // NOLINT // clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml new file mode 100644 index 0000000000000..aa9579305dfb8 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json new file mode 100644 index 0000000000000..059411e02ab92 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json @@ -0,0 +1,98 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Concatenate and Time Synchronize Node", + "type": "object", + "definitions": { + "concatenate_and_time_sync_node": { + "type": "object", + "properties": { + "maximum_queue_size": { + "type": "integer", + "default": 5, + "description": "Maximum size of the queue." + }, + "timeout_sec": { + "type": "number", + "default": 0.0, + "description": "Timeout in seconds." + }, + "offset_tolerance": { + "type": "number", + "default": 0.0, + "description": "Tolerance for offset." + }, + "is_motion_compensated": { + "type": "boolean", + "default": true, + "description": "Flag to indicate if motion compensation is enabled." + }, + "publish_synchronized_pointcloud": { + "type": "boolean", + "default": true, + "description": "Flag to indicate if synchronized point cloud should be published." + }, + "keep_input_frame_in_synchronized_pointcloud": { + "type": "boolean", + "default": true, + "description": "Flag to indicate if input frame should be kept in synchronized point cloud." + }, + "synchronized_pointcloud_postfix": { + "type": "string", + "default": "pointcloud", + "description": "Postfix for the synchronized point cloud." + }, + "input_twist_topic_type": { + "type": "string", + "default": "twist", + "description": "Type of the input twist topic." + }, + "input_topics": { + "type": "array", + "items": { + "type": "string" + }, + "default": [], + "description": "List of input topics." + }, + "output_frame": { + "type": "string", + "default": "", + "description": "Output frame." + }, + "lidar_timestamp_offsets": { + "type": "array", + "items": { + "type": "number" + }, + "default": [], + "description": "List of LiDAR timestamp offsets." + } + }, + "required": [ + "maximum_queue_size", + "timeout_sec", + "offset_tolerance", + "is_motion_compensated", + "publish_synchronized_pointcloud", + "keep_input_frame_in_synchronized_pointcloud", + "synchronized_pointcloud_postfix", + "input_twist_topic_type", + "input_topics", + "output_frame", + "lidar_timestamp_offsets" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/concatenate_and_time_sync_node" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp new file mode 100644 index 0000000000000..28ae3fc85dc12 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -0,0 +1,157 @@ +// Copyright 2024 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. + +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ + * + */ + +#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" + +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" + +#include + +#include + +namespace autoware::pointcloud_preprocessor +{ + +CloudCollector::CloudCollector( + std::shared_ptr concatenate_node, + std::list> & collectors, + std::shared_ptr combine_cloud_handler, int num_of_clouds, double timeout_sec) +: concatenate_node_(concatenate_node), + collectors_(collectors), + combine_cloud_handler_(combine_cloud_handler), + num_of_clouds_(num_of_clouds), + timeout_sec_(timeout_sec) +{ + const auto period_ns = std::chrono::duration_cast( + std::chrono::duration(timeout_sec_)); + + timer_ = rclcpp::create_timer( + concatenate_node_, concatenate_node_->get_clock(), period_ns, + std::bind(&CloudCollector::concatenateCallback, this)); +} + +void CloudCollector::setReferenceTimeStamp(double timestamp, double noise_window) +{ + reference_timestamp_max_ = timestamp + noise_window; + reference_timestamp_min_ = timestamp - noise_window; +} + +std::tuple CloudCollector::getReferenceTimeStampBoundary() +{ + return std::make_tuple(reference_timestamp_min_, reference_timestamp_max_); +} + +void CloudCollector::processCloud( + std::string topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) +{ + // Check if the map already contains an entry for the same topic, shouldn't happened if the + // parameter set correctly. + if (topic_to_cloud_map_.find(topic_name) != topic_to_cloud_map_.end()) { + RCLCPP_WARN( + concatenate_node_->get_logger(), + "Topic '%s' already exists in the collector. Check the timestamp of the pointcloud.", + topic_name.c_str()); + } + topic_to_cloud_map_[topic_name] = cloud; + if (topic_to_cloud_map_.size() == num_of_clouds_) { + concatenateCallback(); + } +} + +void CloudCollector::concatenateCallback() +{ + // lock for protecting collector list and concatenated pointcloud + std::lock_guard lock(mutex_); + auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = + concatenateClouds(topic_to_cloud_map_); + publishClouds(concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map); + deleteCollector(); +} + +std::tuple< + sensor_msgs::msg::PointCloud2::SharedPtr, + std::unordered_map, + std::unordered_map> +CloudCollector::concatenateClouds( + std::unordered_map topic_to_cloud_map) +{ + return combine_cloud_handler_->combinePointClouds(topic_to_cloud_map); +} + +void CloudCollector::publishClouds( + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, + std::unordered_map + topic_to_transformed_cloud_map, + std::unordered_map topic_to_original_stamp_map) +{ + concatenate_node_->publishClouds( + concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map, + reference_timestamp_min_, reference_timestamp_max_); +} + +void CloudCollector::deleteCollector() +{ + auto it = std::find_if( + collectors_.begin(), collectors_.end(), + [this](const std::shared_ptr & collector) { return collector.get() == this; }); + if (it != collectors_.end()) { + collectors_.erase(it); + } +} + +std::unordered_map +CloudCollector::get_topic_to_cloud_map() +{ + return topic_to_cloud_map_; +} + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp new file mode 100644 index 0000000000000..11985a4c8720d --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -0,0 +1,301 @@ +// Copyright 2024 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. + +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ + * + */ + +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" + +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +CombineCloudHandler::CombineCloudHandler( + rclcpp::Node * node, std::vector input_topics, std::string output_frame, + bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud) +: node_(node), + tf_buffer_(node_->get_clock()), + tf_listener_(tf_buffer_), + input_topics_(input_topics), + output_frame_(output_frame), + is_motion_compensated_(is_motion_compensated), + keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud) +{ +} + +void CombineCloudHandler::processTwist( + 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(); + twist_ptr->header = input->header; + twist_ptr->twist = input->twist.twist; + twist_ptr_queue_.push_back(twist_ptr); +} + +void CombineCloudHandler::processOdometry(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(); + twist_ptr->header = input->header; + twist_ptr->twist = input->twist.twist; + twist_ptr_queue_.push_back(twist_ptr); +} + +std::tuple< + sensor_msgs::msg::PointCloud2::SharedPtr, + std::unordered_map, + std::unordered_map> +CombineCloudHandler::combinePointClouds( + std::unordered_map & topic_to_cloud_map) +{ + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr = nullptr; + std::unordered_map + topic_to_transformed_cloud_map; + std::unordered_map topic_to_original_stamp_map; + + std::vector pc_stamps; + for (const auto & pair : topic_to_cloud_map) { + pc_stamps.push_back(rclcpp::Time(pair.second->header.stamp)); + } + std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); + const auto oldest_stamp = pc_stamps.back(); + + std::unordered_map transform_memo; + + for (const auto & pair : topic_to_cloud_map) { + std::string topic = pair.first; + sensor_msgs::msg::PointCloud2::SharedPtr cloud = pair.second; + + auto transformed_cloud_ptr = std::make_shared(); + if (output_frame_ != cloud->header.frame_id) { + if (!pcl_ros::transformPointCloud( + output_frame_, *cloud, *transformed_cloud_ptr, tf_buffer_)) { + RCLCPP_ERROR( + node_->get_logger(), + "Transform pointcloud from %s to %s failed, Please check the defined output frame.", + cloud->header.frame_id.c_str(), output_frame_.c_str()); + transformed_cloud_ptr = cloud; + } + } else { + transformed_cloud_ptr = cloud; + } + + topic_to_original_stamp_map[topic] = rclcpp::Time(cloud->header.stamp).seconds(); + + auto transformed_delay_compensated_cloud_ptr = + std::make_shared(); + + if (is_motion_compensated_) { + Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); + rclcpp::Time current_cloud_stamp = rclcpp::Time(cloud->header.stamp); + for (const auto & stamp : pc_stamps) { + if (stamp >= current_cloud_stamp) continue; + + Eigen::Matrix4f new_to_old_transform; + if (transform_memo.find(stamp) != transform_memo.end()) { + new_to_old_transform = transform_memo[stamp]; + } else { + new_to_old_transform = + computeTransformToAdjustForOldTimestamp(stamp, current_cloud_stamp); + transform_memo[stamp] = new_to_old_transform; + } + adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform; + current_cloud_stamp = stamp; + } + pcl_ros::transformPointCloud( + adjust_to_old_data_transform, *transformed_cloud_ptr, + *transformed_delay_compensated_cloud_ptr); + + } else { + transformed_delay_compensated_cloud_ptr = transformed_cloud_ptr; + } + + // concatenate + if (concatenate_cloud_ptr == nullptr) { + concatenate_cloud_ptr = + std::make_shared(*transformed_delay_compensated_cloud_ptr); + } else { + pcl::concatenatePointCloud( + *concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concatenate_cloud_ptr); + } + + // convert to original sensor frame if necessary + bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); + if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { + sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame( + new sensor_msgs::msg::PointCloud2()); + pcl_ros::transformPointCloud( + (std::string)cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, + *transformed_cloud_ptr_in_sensor_frame, tf_buffer_); + transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; + transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id; + topic_to_transformed_cloud_map[topic] = transformed_cloud_ptr_in_sensor_frame; + } else { + transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp; + transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_; + topic_to_transformed_cloud_map[topic] = transformed_delay_compensated_cloud_ptr; + } + } + concatenate_cloud_ptr->header.stamp = oldest_stamp; + + return std::make_tuple( + concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map); +} + +Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( + const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) +{ + // return identity if no twist is available + if (twist_ptr_queue_.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + node_->get_logger(), *node_->get_clock(), std::chrono::milliseconds(10000).count(), + "No twist is available. Please confirm twist topic and timestamp"); + 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; + tf2::Quaternion baselink_quat{}; + 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( + node_->get_logger(), *node_->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::Matrix4f transformation_matrix = Eigen::Matrix4f::Identity(); + + float cos_yaw = std::cos(yaw); + float sin_yaw = std::sin(yaw); + + transformation_matrix(0, 3) = x; + transformation_matrix(1, 3) = y; + transformation_matrix(0, 0) = cos_yaw; + transformation_matrix(0, 1) = -sin_yaw; + transformation_matrix(1, 0) = sin_yaw; + transformation_matrix(1, 1) = cos_yaw; + + return transformation_matrix; +} + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp new file mode 100644 index 0000000000000..475a203319727 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -0,0 +1,495 @@ +// Copyright 2024 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. + +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ + * + */ + +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" + +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +#define DEFAULT_SYNC_TOPIC_POSTFIX \ + "_synchronized" // default postfix name for synchronized pointcloud + +namespace autoware::pointcloud_preprocessor +{ + +PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent( + const rclcpp::NodeOptions & node_options) +: Node("point_cloud_concatenator_component", node_options) +{ + // initialize debug tool + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ = std::make_unique(this, "concatenate_data_synchronizer"); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + + // initialize parameters + params_.maximum_queue_size = declare_parameter("maximum_queue_size"); + params_.timeout_sec = declare_parameter("timeout_sec"); + params_.is_motion_compensated = declare_parameter("is_motion_compensated"); + params_.publish_synchronized_pointcloud = + declare_parameter("publish_synchronized_pointcloud"); + params_.keep_input_frame_in_synchronized_pointcloud = + declare_parameter("keep_input_frame_in_synchronized_pointcloud"); + params_.publish_previous_but_late_pointcloud = + declare_parameter("publish_previous_but_late_pointcloud"); + params_.synchronized_pointcloud_postfix = + declare_parameter("synchronized_pointcloud_postfix"); + params_.input_twist_topic_type = declare_parameter("input_twist_topic_type"); + params_.input_topics = declare_parameter>("input_topics"); + params_.output_frame = declare_parameter("output_frame"); + params_.lidar_timestamp_offsets = + declare_parameter>("lidar_timestamp_offsets"); + params_.lidar_timestamp_noise_window = + declare_parameter>("lidar_timestamp_noise_window"); + + if (params_.input_topics.empty()) { + RCLCPP_ERROR(get_logger(), "Need a 'input_topics' parameter to be set before continuing!"); + return; + } else if (params_.input_topics.size() == 1) { + RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue."); + return; + } + + if (params_.output_frame.empty()) { + RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); + return; + } + if (params_.lidar_timestamp_offsets.size() != params_.input_topics.size()) { + RCLCPP_ERROR( + get_logger(), "The number of topics does not match the number of timestamp offsets"); + return; + } + if (params_.lidar_timestamp_noise_window.size() != params_.input_topics.size()) { + RCLCPP_ERROR( + get_logger(), "The number of topics does not match the number of timestamp noise windwo"); + return; + } + + for (size_t i = 0; i < params_.input_topics.size(); i++) { + topic_to_offset_map_[params_.input_topics[i]] = params_.lidar_timestamp_offsets[i]; + topic_to_noise_window_map_[params_.input_topics[i]] = params_.lidar_timestamp_noise_window[i]; + } + + // Publishers + concatenate_cloud_publisher_ = this->create_publisher( + "output", rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + + // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud + if (params_.publish_synchronized_pointcloud) { + for (auto & topic : params_.input_topics) { + std::string new_topic = + replaceSyncTopicNamePostfix(topic, params_.synchronized_pointcloud_postfix); + auto publisher = this->create_publisher( + new_topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + topic_to_transformed_cloud_publisher_map_.insert({topic, publisher}); + } + } + + // Subscribers + if (params_.input_twist_topic_type == "twist") { + twist_sub_ = this->create_subscription( + "~/input/twist", rclcpp::QoS{100}, + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, + std::placeholders::_1)); + } else if (params_.input_twist_topic_type == "odom") { + odom_sub_ = this->create_subscription( + "~/input/odom", rclcpp::QoS{100}, + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, + std::placeholders::_1)); + } else { + RCLCPP_ERROR_STREAM( + get_logger(), "input_twist_topic_type is invalid: " << params_.input_twist_topic_type); + throw std::runtime_error( + "input_twist_topic_type is invalid: " + params_.input_twist_topic_type); + } + + pointcloud_subs.resize(params_.input_topics.size()); + for (size_t topic_id = 0; topic_id < params_.input_topics.size(); ++topic_id) { + std::function callback = std::bind( + &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1, + params_.input_topics[topic_id]); + + pointcloud_subs[topic_id].reset(); + pointcloud_subs[topic_id] = this->create_subscription( + params_.input_topics[topic_id], rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size), + callback); + } + RCLCPP_DEBUG_STREAM( + get_logger(), + "Subscribing to " << params_.input_topics.size() << " user given topics as inputs:"); + for (auto & input_topic : params_.input_topics) { + RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); + } + + // Cloud handler + combine_cloud_handler_ = std::make_shared( + this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, + params_.keep_input_frame_in_synchronized_pointcloud); + + // Diagnostic Updater + updater_.setHardwareID("concatenate_data_checker"); + updater_.add( + "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus); +} + +std::string PointCloudConcatenateDataSynchronizerComponent::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; +} + +void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name) +{ + stop_watch_ptr_->toc("processing_time", true); + if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), "The pointcloud layout is not compatible with PointXYZIRC. Aborting"); + + if (utils::is_data_layout_compatible_with_point_xyzi(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), + "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); + } + + return; + } + + sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); + auto input = std::make_shared(*input_ptr); + if (input->data.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); + return; + } else { + // convert to XYZIRC pointcloud if pointcloud is not empty + convertToXYZIRCCloud(input, xyzirc_input_ptr); + } + + // protect cloud collectors list + std::unique_lock lock(mutex_); + + // For each callback, check whether there is a exist collector that matches this cloud + bool collector_found = false; + + if (!cloud_collectors_.empty()) { + for (const auto & cloud_collector : cloud_collectors_) { + auto [reference_timestamp_min, reference_timestamp_max] = + cloud_collector->getReferenceTimeStampBoundary(); + + if ( + rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] < + reference_timestamp_max + topic_to_noise_window_map_[topic_name] && + rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] > + reference_timestamp_min - topic_to_noise_window_map_[topic_name]) { + lock.unlock(); + cloud_collector->processCloud(topic_name, input_ptr); + collector_found = true; + break; + } + } + } + + // if point cloud didn't find matched collector, create a new collector. + if (!collector_found) { + auto new_cloud_collector = std::make_shared( + std::dynamic_pointer_cast(shared_from_this()), + cloud_collectors_, combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec); + + cloud_collectors_.push_back(new_cloud_collector); + lock.unlock(); + new_cloud_collector->setReferenceTimeStamp( + rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name], + topic_to_noise_window_map_[topic_name]); + new_cloud_collector->processCloud(topic_name, input_ptr); + } +} + +void PointCloudConcatenateDataSynchronizerComponent::twist_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input) +{ + combine_cloud_handler_->processTwist(input); +} + +void PointCloudConcatenateDataSynchronizerComponent::odom_callback( + const nav_msgs::msg::Odometry::ConstSharedPtr input) +{ + combine_cloud_handler_->processOdometry(input); +} + +void PointCloudConcatenateDataSynchronizerComponent::publishClouds( + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, + std::unordered_map & + topic_to_transformed_cloud_map, + std::unordered_map & topic_to_original_stamp_map, + double reference_timestamp_min, double reference_timestamp_max) +{ + // should never come to this state. + if (concatenate_cloud_ptr == nullptr) return; + + current_concat_cloud_timestamp_ = rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds(); + + if ( + current_concat_cloud_timestamp_ < lastest_concat_cloud_timestamp_ && + !params_.publish_previous_but_late_pointcloud) { + drop_previous_but_late_pointcloud_ = true; + } else { + publish_pointcloud_ = true; + lastest_concat_cloud_timestamp_ = current_concat_cloud_timestamp_; + auto concat_output = std::make_unique(*concatenate_cloud_ptr); + concatenate_cloud_publisher_->publish(std::move(concat_output)); + // publish transformed raw pointclouds + for (const auto & pair : topic_to_transformed_cloud_map) { + if (pair.second) { + if (params_.publish_synchronized_pointcloud) { + auto transformed_cloud_output = + std::make_unique(*pair.second); + topic_to_transformed_cloud_publisher_map_[pair.first]->publish( + std::move(transformed_cloud_output)); + } + } else { + RCLCPP_WARN( + this->get_logger(), "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.", + pair.first.c_str()); + } + } + } + + diagnostic_reference_timestamp_min_ = reference_timestamp_min; + diagnostic_reference_timestamp_max_ = reference_timestamp_max; + diagnostic_topic_to_original_stamp_map_ = topic_to_original_stamp_map; + updater_.force_update(); + + // 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( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + + for (const auto & pair : topic_to_transformed_cloud_map) { + if (pair.second != nullptr) { + const auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds( + (this->get_clock()->now() - pair.second->header.stamp).nanoseconds())) + .count(); + debug_publisher_->publish( + "debug" + pair.first + "/pipeline_latency_ms", pipeline_latency_ms); + } + } + } +} + +void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, + sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) +{ + output_ptr->header = input_ptr->header; + + PointCloud2Modifier output_modifier{ + *output_ptr, input_ptr->header.frame_id}; + output_modifier.reserve(input_ptr->width); + + bool has_valid_intensity = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_return_type = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_channel = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; + }); + + sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); + sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); + sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); + + if (has_valid_intensity && has_valid_return_type && has_valid_channel) { + sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); + sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); + sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { + PointXYZIRC point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + point.intensity = *it_i; + point.return_type = *it_r; + point.channel = *it_c; + output_modifier.push_back(std::move(point)); + } + } else { + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { + PointXYZIRC point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + output_modifier.push_back(std::move(point)); + } + } +} + +std::string PointCloudConcatenateDataSynchronizerComponent::formatTimestamp(double timestamp) +{ + std::ostringstream oss; + oss << std::fixed << std::setprecision(9) << timestamp; + return oss.str(); +} + +void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( + diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + if (publish_pointcloud_ || drop_previous_but_late_pointcloud_) { + std::set missed_cloud; + + stat.add("concatenated cloud timestamp", formatTimestamp(current_concat_cloud_timestamp_)); + stat.add("reference timestamp min", formatTimestamp(diagnostic_reference_timestamp_min_)); + stat.add("reference timestamp max", formatTimestamp(diagnostic_reference_timestamp_max_)); + + bool topic_miss = false; + + int concatenate_status = 1; + for (auto topic : params_.input_topics) { + int cloud_status; // 1 for success, 0 for failure + if ( + diagnostic_topic_to_original_stamp_map_.find(topic) != + diagnostic_topic_to_original_stamp_map_.end()) { + cloud_status = 1; + stat.add( + topic + " timestamp", formatTimestamp(diagnostic_topic_to_original_stamp_map_[topic])); + } else { + topic_miss = true; + cloud_status = 0; + concatenate_status = 0; + } + stat.add(topic, cloud_status); + } + + stat.add("concatenate status", concatenate_status); + + int8_t level; + std::string message; + if (topic_miss) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = "Concatenated pointcloud is published but miss some topics"; + } else if (drop_previous_but_late_pointcloud_) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = "Concatenated pointcloud is not published as it is too late"; + } else { + level = diagnostic_msgs::msg::DiagnosticStatus::OK; + message = "Concatenated pointcloud is published and include all topics"; + } + + stat.summary(level, message); + + publish_pointcloud_ = false; + drop_previous_but_late_pointcloud_ = false; + } else { + const int8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + const std::string message = + "Concatenate node launch successfully, but waiting for input pointcloud"; + stat.summary(level, message); + } +} + +} // namespace autoware::pointcloud_preprocessor + +#include +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp deleted file mode 100644 index d0911f769d3bd..0000000000000 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ /dev/null @@ -1,717 +0,0 @@ -// Copyright 2020 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. - -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - -#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp" - -#include "autoware/pointcloud_preprocessor/utility/memory.hpp" - -#include - -#include - -#include -#include -#include -#include -#include - -#define DEFAULT_SYNC_TOPIC_POSTFIX \ - "_synchronized" // default postfix name for synchronized pointcloud - -////////////////////////////////////////////////////////////////////////////////////////////// - -namespace autoware::pointcloud_preprocessor -{ -PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent( - const rclcpp::NodeOptions & node_options) -: Node("point_cloud_concatenator_component", node_options), - input_twist_topic_type_(declare_parameter("input_twist_topic_type", "twist")) -{ - // initialize debug tool - { - using autoware::universe_utils::DebugPublisher; - using autoware::universe_utils::StopWatch; - stop_watch_ptr_ = std::make_unique>(); - debug_publisher_ = std::make_unique(this, "concatenate_data_synchronizer"); - stop_watch_ptr_->tic("cyclic_time"); - stop_watch_ptr_->tic("processing_time"); - } - - // Set parameters - { - output_frame_ = static_cast(declare_parameter("output_frame", "")); - if (output_frame_.empty()) { - RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); - return; - } - has_static_tf_only_ = declare_parameter("has_static_tf_only", false); - declare_parameter("input_topics", std::vector()); - 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; - } - - // Optional parameters - maximum_queue_size_ = static_cast(declare_parameter("max_queue_size", 5)); - timeout_sec_ = static_cast(declare_parameter("timeout_sec", 0.1)); - - input_offset_ = declare_parameter("input_offset", std::vector{}); - 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; - } - - // Check if publish synchronized pointcloud - publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", true); - keep_input_frame_in_synchronized_pointcloud_ = - declare_parameter("keep_input_frame_in_synchronized_pointcloud", true); - synchronized_pointcloud_postfix_ = - declare_parameter("synchronized_pointcloud_postfix", "pointcloud"); - } - - // 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 - { - managed_tf_buffer_ = - std::make_unique(this, has_static_tf_only_); - } - - // Output Publishers - { - rclcpp::PublisherOptions pub_options; - pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - pub_output_ = this->create_publisher( - "output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); - } - - // Subscribers - { - RCLCPP_DEBUG_STREAM( - get_logger(), "Subscribing to " << input_topics_.size() << " user given topics as inputs:"); - for (const auto & input_topic : input_topics_) { - RCLCPP_DEBUG_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 cb = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, - std::placeholders::_1, input_topics_[d]); - - filters_[d].reset(); - filters_[d] = this->create_subscription( - input_topics_[d], rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), cb); - } - - if (input_twist_topic_type_ == "twist") { - auto twist_cb = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, - std::placeholders::_1); - sub_twist_ = this->create_subscription( - "~/input/twist", rclcpp::QoS{100}, twist_cb); - } else if (input_twist_topic_type_ == "odom") { - auto odom_cb = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, - std::placeholders::_1); - sub_odom_ = this->create_subscription( - "~/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 to publish the transformed pointcloud - if (publish_synchronized_pointcloud_) { - rclcpp::PublisherOptions pub_options; - pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - for (auto & topic : input_topics_) { - std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_); - auto publisher = this->create_publisher( - new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); - transformed_raw_pc_publisher_map_.insert({topic, publisher}); - } - } - - // Set timer - { - const auto period_ns = std::chrono::duration_cast( - std::chrono::duration(timeout_sec_)); - timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, - std::bind(&PointCloudConcatenateDataSynchronizerComponent::timer_callback, this)); - } - - // Diagnostic Updater - { - updater_.setHardwareID("concatenate_data_checker"); - updater_.add( - "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus); - } -} - -std::string PointCloudConcatenateDataSynchronizerComponent::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; -} - -/** - * @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 -PointCloudConcatenateDataSynchronizerComponent::computeTransformToAdjustForOldTimestamp( - const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) -{ - // return identity if no twist is available - if (twist_ptr_queue_.empty()) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), - "No twist is available. Please confirm twist topic and timestamp"); - return Eigen::Matrix4f::Identity(); - } - - // return identity if old_stamp is newer than new_stamp - if (old_stamp > new_stamp) { - RCLCPP_DEBUG_STREAM_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), - "old_stamp is newer than 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 -PointCloudConcatenateDataSynchronizerComponent::combineClouds( - sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr) -{ - // map for storing the transformed point clouds - std::map transformed_clouds; - - // Step1. gather stamps and sort it - std::vector 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) { - if (e.second->data.size() == 0) { - continue; - } - sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr( - new sensor_msgs::msg::PointCloud2()); - managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); - - // calculate transforms 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); - } - sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr( - new sensor_msgs::msg::PointCloud2()); - pcl_ros::transformPointCloud( - adjust_to_old_data_transform, *transformed_cloud_ptr, - *transformed_delay_compensated_cloud_ptr); - - // concatenate - if (concat_cloud_ptr == nullptr) { - concat_cloud_ptr = - std::make_shared(*transformed_delay_compensated_cloud_ptr); - } else { - pcl::concatenatePointCloud( - *concat_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concat_cloud_ptr); - } - // convert to original sensor frame if necessary - bool need_transform_to_sensor_frame = (e.second->header.frame_id != output_frame_); - if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { - sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame( - new sensor_msgs::msg::PointCloud2()); - managed_tf_buffer_->transformPointcloud( - e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, - *transformed_cloud_ptr_in_sensor_frame); - transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; - transformed_cloud_ptr_in_sensor_frame->header.frame_id = e.second->header.frame_id; - transformed_clouds[e.first] = transformed_cloud_ptr_in_sensor_frame; - } else { - 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); - } - } - concat_cloud_ptr->header.stamp = oldest_stamp; - return transformed_clouds; -} - -void PointCloudConcatenateDataSynchronizerComponent::publish() -{ - stop_watch_ptr_->toc("processing_time", true); - sensor_msgs::msg::PointCloud2::SharedPtr concat_cloud_ptr = nullptr; - not_subscribed_topic_names_.clear(); - - const auto & transformed_raw_points = - PointCloudConcatenateDataSynchronizerComponent::combineClouds(concat_cloud_ptr); - - // publish concatenated pointcloud - if (concat_cloud_ptr) { - auto output = std::make_unique(*concat_cloud_ptr); - pub_output_->publish(std::move(output)); - } else { - RCLCPP_WARN(this->get_logger(), "concat_cloud_ptr is nullptr, skipping pointcloud publish."); - } - - // publish transformed raw pointclouds - if (publish_synchronized_pointcloud_) { - for (const auto & e : transformed_raw_points) { - if (e.second) { - auto output = std::make_unique(*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( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); - } - for (const auto & e : cloud_stdmap_) { - if (e.second != nullptr) { - if (debug_publisher_) { - const auto pipeline_latency_ms = - std::chrono::duration( - std::chrono::nanoseconds( - (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) - .count(); - debug_publisher_->publish( - "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); - } - } - } -} - -/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, - sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) -{ - output_ptr->header = input_ptr->header; - - PointCloud2Modifier output_modifier{ - *output_ptr, input_ptr->header.frame_id}; - output_modifier.reserve(input_ptr->width); - - bool has_valid_intensity = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; - }); - - bool has_valid_return_type = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; - }); - - bool has_valid_channel = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; - }); - - sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); - sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); - sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); - - if (has_valid_intensity && has_valid_return_type && has_valid_channel) { - sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); - sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); - sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); - - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { - PointXYZIRC point; - point.x = *it_x; - point.y = *it_y; - point.z = *it_z; - point.intensity = *it_i; - point.return_type = *it_r; - point.channel = *it_c; - output_modifier.push_back(std::move(point)); - } - } else { - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { - PointXYZIRC point; - point.x = *it_x; - point.y = *it_y; - point.z = *it_z; - output_modifier.push_back(std::move(point)); - } - } -} - -void PointCloudConcatenateDataSynchronizerComponent::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 PointCloudConcatenateDataSynchronizerComponent::cloud_callback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name) -{ - if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { - RCLCPP_ERROR( - get_logger(), "The pointcloud layout is not compatible with PointXYZIRC. Aborting"); - - if (utils::is_data_layout_compatible_with_point_xyzi(*input_ptr)) { - RCLCPP_ERROR( - get_logger(), - "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); - } - - return; - } - - std::lock_guard lock(mutex_); - sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); - auto input = std::make_shared(*input_ptr); - if (input->data.empty()) { - RCLCPP_WARN_STREAM_THROTTLE( - this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); - } else { - // convert to XYZIRC pointcloud if pointcloud is not empty - convertToXYZIRCCloud(input, xyzirc_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] = xyzirc_input_ptr; - - if (!is_already_subscribed_tmp) { - auto period = std::chrono::duration_cast( - std::chrono::duration(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] = xyzirc_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::duration(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 PointCloudConcatenateDataSynchronizerComponent::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 PointCloudConcatenateDataSynchronizerComponent::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(); - twist_ptr->header = input->header; - twist_ptr->twist = input->twist.twist; - twist_ptr_queue_.push_back(twist_ptr); -} - -void PointCloudConcatenateDataSynchronizerComponent::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(); - twist_ptr->header = input->header; - twist_ptr->twist = input->twist.twist; - twist_ptr_queue_.push_back(twist_ptr); -} - -void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( - 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 autoware::pointcloud_preprocessor - -#include -RCLCPP_COMPONENTS_REGISTER_NODE( - autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp new file mode 100644 index 0000000000000..f3f0626364f88 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp @@ -0,0 +1,468 @@ +// Copyright 2024 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. +// cloud_collector_test.cpp +// cloud_collector_test.cpp + +// cloud_collector_test.cpp + +#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" + +#include + +#include +#include + +#include +#include + +#include +#include +#include + +class ConcatenateCloudTest : public ::testing::Test +{ +protected: + void SetUp() override + { + rclcpp::NodeOptions node_options; + // 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}, + {"timeout_sec", 0.2}, + {"is_motion_compensated", true}, + {"publish_synchronized_pointcloud", true}, + {"keep_input_frame_in_synchronized_pointcloud", true}, + {"publish_previous_but_late_pointcloud", false}, + {"synchronized_pointcloud_postfix", "pointcloud"}, + {"input_twist_topic_type", "twist"}, + {"input_topics", std::vector{"lidar_top", "lidar_left", "lidar_right"}}, + {"output_frame", "base_link"}, + {"lidar_timestamp_offsets", std::vector{0.0, 0.04, 0.08}}, + {"lidar_timestamp_noise_window", std::vector{0.01, 0.01, 0.01}}}); + + concatenate_node_ = std::make_shared< + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( + node_options); + combine_cloud_handler_ = + std::make_shared( + concatenate_node_.get(), std::vector{"lidar_top", "lidar_left", "lidar_right"}, + "base_link", true, true); + + collector_ = std::make_shared( + std::dynamic_pointer_cast< + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( + concatenate_node_->shared_from_this()), + collectors_, combine_cloud_handler_, number_of_pointcloud_, timeout_sec_); + + collectors_.push_back(collector_); + + // Setup TF + tf_broadcaster_ = std::make_shared(concatenate_node_); + tf_broadcaster_->sendTransform(generateStaticTransformMsg()); + + // Spin the node for a while to ensure transforms are published + auto start = std::chrono::steady_clock::now(); + auto timeout = std::chrono::milliseconds(100); + while (std::chrono::steady_clock::now() - start < timeout) { + rclcpp::spin_some(concatenate_node_); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + + geometry_msgs::msg::TransformStamped generateTransformMsg( + const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, + double qx, double qy, double qz, double qw) + { + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + geometry_msgs::msg::TransformStamped tf_msg; + tf_msg.header.stamp = timestamp; + tf_msg.header.frame_id = parent_frame; + tf_msg.child_frame_id = child_frame; + tf_msg.transform.translation.x = x; + tf_msg.transform.translation.y = y; + tf_msg.transform.translation.z = z; + tf_msg.transform.rotation.x = qx; + tf_msg.transform.rotation.y = qy; + tf_msg.transform.rotation.z = qz; + tf_msg.transform.rotation.w = qw; + return tf_msg; + } + + sensor_msgs::msg::PointCloud2 generatePointCloudMsg( + bool generate_points, bool is_lidar_frame, std::string topic_name, rclcpp::Time stamp) + { + sensor_msgs::msg::PointCloud2 pointcloud_msg; + pointcloud_msg.header.stamp = stamp; + pointcloud_msg.header.frame_id = is_lidar_frame ? topic_name : "base_link"; + pointcloud_msg.height = 1; + pointcloud_msg.is_dense = true; + pointcloud_msg.is_bigendian = false; + + if (generate_points) { + std::array points = {{ + Eigen::Vector3f(10.0f, 0.0f, 0.0f), // point 1 + Eigen::Vector3f(0.0f, 10.0f, 0.0f), // point 2 + Eigen::Vector3f(0.0f, 0.0f, 10.0f), // point 3 + }}; + + sensor_msgs::PointCloud2Modifier modifier(pointcloud_msg); + modifier.setPointCloud2Fields( + 10, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, + sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, + "intensity", 1, sensor_msgs::msg::PointField::UINT8, "return_type", 1, + sensor_msgs::msg::PointField::UINT8, "channel", 1, sensor_msgs::msg::PointField::UINT16, + "azimuth", 1, sensor_msgs::msg::PointField::FLOAT32, "elevation", 1, + sensor_msgs::msg::PointField::FLOAT32, "distance", 1, sensor_msgs::msg::PointField::FLOAT32, + "time_stamp", 1, sensor_msgs::msg::PointField::UINT32); + + modifier.resize(number_of_points_); + + sensor_msgs::PointCloud2Iterator iter_x(pointcloud_msg, "x"); + sensor_msgs::PointCloud2Iterator iter_y(pointcloud_msg, "y"); + sensor_msgs::PointCloud2Iterator iter_z(pointcloud_msg, "z"); + sensor_msgs::PointCloud2Iterator iter_t(pointcloud_msg, "time_stamp"); + + for (size_t i = 0; i < number_of_points_; ++i) { + *iter_x = points[i].x(); + *iter_y = points[i].y(); + *iter_z = points[i].z(); + *iter_t = 0; + ++iter_x; + ++iter_y; + ++iter_z; + ++iter_t; + } + } else { + pointcloud_msg.width = 0; + pointcloud_msg.row_step = 0; + } + + return pointcloud_msg; + } + + std::vector generateStaticTransformMsg() + { + // generate defined transformations + return { + generateTransformMsg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), + generateTransformMsg("base_link", "lidar_left", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; + generateTransformMsg("base_link", "lidar_right", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453); + } + + std::shared_ptr + concatenate_node_; + std::list> collectors_; + std::shared_ptr combine_cloud_handler_; + std::shared_ptr collector_; + std::shared_ptr tf_broadcaster_; + + static constexpr int32_t timestamp_seconds_{10}; + static constexpr uint32_t timestamp_nanoseconds_{100000000}; + static constexpr size_t number_of_points_{3}; + static constexpr float standard_tolerance_{1e-4}; + static constexpr int number_of_pointcloud_{3}; + static constexpr float timeout_sec_{1}; + bool debug_{true}; +}; + +//////////////////////////////// Test combine_cloud_handler //////////////////////////////// +TEST_F(ConcatenateCloudTest, ProcessTwist) +{ + auto twist_msg = std::make_shared(); + twist_msg->header.stamp = rclcpp::Time(10, 0); + twist_msg->twist.twist.linear.x = 1.0; + twist_msg->twist.twist.angular.z = 0.1; + + combine_cloud_handler_->processTwist(twist_msg); + + ASSERT_FALSE(combine_cloud_handler_->twist_ptr_queue_.empty()); + EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.angular.z, 0.1); +} + +TEST_F(ConcatenateCloudTest, ProcessOdometry) +{ + auto odom_msg = std::make_shared(); + odom_msg->header.stamp = rclcpp::Time(10, 0); + odom_msg->twist.twist.linear.x = 1.0; + odom_msg->twist.twist.angular.z = 0.1; + + combine_cloud_handler_->processOdometry(odom_msg); + + ASSERT_FALSE(combine_cloud_handler_->twist_ptr_queue_.empty()); + EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.angular.z, 0.1); +} + +TEST_F(ConcatenateCloudTest, ComputeTransformToAdjustForOldTimestamp) +{ + rclcpp::Time old_stamp(10, 100000000, RCL_ROS_TIME); + rclcpp::Time new_stamp(10, 150000000, RCL_ROS_TIME); + + // Time difference between twist msg is more than 100 miliseconds, won't calculate the difference + auto twist_msg1 = std::make_shared(); + twist_msg1->header.stamp = rclcpp::Time(10, 130000000, RCL_ROS_TIME); + twist_msg1->twist.linear.x = 1.0; + twist_msg1->twist.angular.z = 0.1; + combine_cloud_handler_->twist_ptr_queue_.push_back(twist_msg1); + + auto twist_msg2 = std::make_shared(); + twist_msg2->header.stamp = rclcpp::Time(10, 160000000, RCL_ROS_TIME); + twist_msg2->twist.linear.x = 1.0; + twist_msg2->twist.angular.z = 0.1; + combine_cloud_handler_->twist_ptr_queue_.push_back(twist_msg2); + + Eigen::Matrix4f transform = + combine_cloud_handler_->computeTransformToAdjustForOldTimestamp(old_stamp, new_stamp); + + // translation + EXPECT_NEAR(transform(0, 3), 0.0499996, standard_tolerance_); + EXPECT_NEAR(transform(1, 3), 0.000189999, standard_tolerance_); + + // rotation, yaw = 0.005 + EXPECT_NEAR(transform(0, 0), 0.999987, standard_tolerance_); + EXPECT_NEAR(transform(0, 1), -0.00499998, standard_tolerance_); + EXPECT_NEAR(transform(1, 0), 0.00499998, standard_tolerance_); + EXPECT_NEAR(transform(1, 1), 0.999987, standard_tolerance_); + + std::ostringstream oss; + oss << "Transformation matrix:\n" << transform; + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } +} + +//////////////////////////////// Test cloud_collector //////////////////////////////// + +TEST_F(ConcatenateCloudTest, SetAndGetReferenceTimeStampBoundary) +{ + double reference_timestamp = 10.0; + double noise_window = 0.1; + collector_->setReferenceTimeStamp(reference_timestamp, noise_window); + auto [min, max] = collector_->getReferenceTimeStampBoundary(); + EXPECT_DOUBLE_EQ(min, 9.9); + EXPECT_DOUBLE_EQ(max, 10.1); +} + +TEST_F(ConcatenateCloudTest, concatenateAndPublishClouds) +{ + rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40000000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80000000, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 top_pointcloud = + generatePointCloudMsg(true, false, "lidar_top", top_timestamp); + sensor_msgs::msg::PointCloud2 left_pointcloud = + generatePointCloudMsg(true, false, "lidar_left", left_timestamp); + sensor_msgs::msg::PointCloud2 right_pointcloud = + generatePointCloudMsg(true, false, "lidar_right", right_timestamp); + + sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = + std::make_shared(top_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr left_pointcloud_ptr = + std::make_shared(left_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr right_pointcloud_ptr = + std::make_shared(right_pointcloud); + + std::unordered_map topic_to_cloud_map; + topic_to_cloud_map["lidar_top"] = top_pointcloud_ptr; + topic_to_cloud_map["lidar_left"] = left_pointcloud_ptr; + topic_to_cloud_map["lidar_right"] = right_pointcloud_ptr; + + auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = + collector_->concatenateClouds(topic_to_cloud_map); + + // test output concatenate cloud + // No input twist, so it will not do the motion compensation + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f), Eigen::Vector3f(10.0f, 0.0f, 0.0f), + Eigen::Vector3f(0.0f, 10.0f, 0.0f), Eigen::Vector3f(0.0f, 0.0f, 10.0f), + Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + + size_t i = 0; + std::ostringstream oss; + oss << "Concatenated pointcloud:\n"; + + sensor_msgs::PointCloud2Iterator iter_x(*concatenate_cloud_ptr, "x"); + sensor_msgs::PointCloud2Iterator iter_y(*concatenate_cloud_ptr, "y"); + sensor_msgs::PointCloud2Iterator iter_z(*concatenate_cloud_ptr, "z"); + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Concatenated point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z + << ")\n"; + EXPECT_FLOAT_EQ(*iter_x, expected_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*iter_y, expected_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*iter_z, expected_pointcloud[i].z()); + } + + // concatenate cloud should have the oldest pointcloud's timestamp + EXPECT_FLOAT_EQ( + top_timestamp.seconds(), rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds()); + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + // test seperated transformed cloud + std::array expected_top_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + std::array expected_left_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + std::array expected_right_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + + oss.clear(); + oss.str(""); + i = 0; + sensor_msgs::PointCloud2Iterator top_pc_iter_x( + *topic_to_transformed_cloud_map["lidar_top"], "x"); + sensor_msgs::PointCloud2Iterator top_pc_iter_y( + *topic_to_transformed_cloud_map["lidar_top"], "y"); + sensor_msgs::PointCloud2Iterator top_pc_iter_z( + *topic_to_transformed_cloud_map["lidar_top"], "z"); + + for (; top_pc_iter_x != top_pc_iter_x.end(); + ++top_pc_iter_x, ++top_pc_iter_y, ++top_pc_iter_z, ++i) { + oss << "Top point " << i << ": (" << *top_pc_iter_x << ", " << *top_pc_iter_y << ", " + << *top_pc_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*top_pc_iter_x, expected_top_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*top_pc_iter_y, expected_top_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*top_pc_iter_z, expected_top_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + oss.clear(); + oss.str(""); + i = 0; + sensor_msgs::PointCloud2Iterator left_pc_iter_x( + *topic_to_transformed_cloud_map["lidar_left"], "x"); + sensor_msgs::PointCloud2Iterator left_pc_iter_y( + *topic_to_transformed_cloud_map["lidar_left"], "y"); + sensor_msgs::PointCloud2Iterator left_pc_iter_z( + *topic_to_transformed_cloud_map["lidar_left"], "z"); + + for (; left_pc_iter_x != left_pc_iter_x.end(); + ++left_pc_iter_x, ++left_pc_iter_y, ++left_pc_iter_z, ++i) { + oss << "Left point " << i << ": (" << *left_pc_iter_x << ", " << *left_pc_iter_y << ", " + << *left_pc_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*left_pc_iter_x, expected_left_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*left_pc_iter_y, expected_left_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*left_pc_iter_z, expected_left_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + oss.clear(); + oss.str(""); + i = 0; + sensor_msgs::PointCloud2Iterator right_pc_iter_x( + *topic_to_transformed_cloud_map["lidar_right"], "x"); + sensor_msgs::PointCloud2Iterator right_pc_iter_y( + *topic_to_transformed_cloud_map["lidar_right"], "y"); + sensor_msgs::PointCloud2Iterator right_pc_iter_z( + *topic_to_transformed_cloud_map["lidar_right"], "z"); + + for (; right_pc_iter_x != right_pc_iter_x.end(); + ++right_pc_iter_x, ++right_pc_iter_y, ++right_pc_iter_z, ++i) { + oss << "Right point " << i << ": (" << *right_pc_iter_x << ", " << *right_pc_iter_y << ", " + << *right_pc_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*right_pc_iter_x, expected_right_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*right_pc_iter_y, expected_right_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*right_pc_iter_z, expected_right_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + // test original cloud's timestamps + EXPECT_FLOAT_EQ(top_timestamp.seconds(), topic_to_original_stamp_map["lidar_top"]); + EXPECT_FLOAT_EQ(left_timestamp.seconds(), topic_to_original_stamp_map["lidar_left"]); + EXPECT_FLOAT_EQ(right_timestamp.seconds(), topic_to_original_stamp_map["lidar_right"]); +} + +TEST_F(ConcatenateCloudTest, DeleteCollector) +{ + collector_->deleteCollector(); + EXPECT_TRUE(collectors_.empty()); +} + +TEST_F(ConcatenateCloudTest, ProcessSingleCloud) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 top_pointcloud = + generatePointCloudMsg(true, false, "lidar_top", timestamp); + sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = + std::make_shared(top_pointcloud); + collector_->processCloud("lidar_top", top_pointcloud_ptr); + + auto topic_to_cloud_map = collector_->get_topic_to_cloud_map(); + EXPECT_EQ(topic_to_cloud_map["lidar_top"], top_pointcloud_ptr); + EXPECT_FALSE(collectors_.empty()); + + // Sleep for 1.5 seconds + std::this_thread::sleep_for(std::chrono::milliseconds(1500)); + rclcpp::spin_some(concatenate_node_); + + // Collector should concatenate and publish the pointcloud, also delete itself. + EXPECT_TRUE(collectors_.empty()); +} + +TEST_F(ConcatenateCloudTest, ProcessMultipleCloud) +{ + rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40000000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80000000, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 top_pointcloud = + generatePointCloudMsg(true, false, "lidar_top", top_timestamp); + sensor_msgs::msg::PointCloud2 left_pointcloud = + generatePointCloudMsg(true, false, "lidar_left", left_timestamp); + sensor_msgs::msg::PointCloud2 right_pointcloud = + generatePointCloudMsg(true, false, "lidar_right", right_timestamp); + + sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = + std::make_shared(top_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr left_pointcloud_ptr = + std::make_shared(left_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr right_pointcloud_ptr = + std::make_shared(right_pointcloud); + + collector_->processCloud("lidar_top", top_pointcloud_ptr); + collector_->processCloud("lidar_left", left_pointcloud_ptr); + collector_->processCloud("lidar_right", right_pointcloud_ptr); + + EXPECT_TRUE(collectors_.empty()); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int ret = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return ret; +} diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py new file mode 100644 index 0000000000000..ac1a63b9ef07a --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py @@ -0,0 +1,797 @@ +#!/usr/bin/env python3 + +# Copyright 2024 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. + +import random +import struct +import time +import unittest + +# TODO: remove unused later +from geometry_msgs.msg import TransformStamped +from geometry_msgs.msg import TwistWithCovarianceStamped +import launch +import launch.actions +from launch.logging import get_logger +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing +import launch_testing.actions +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +import numpy as np +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from rclpy.time import Time +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField +from sensor_msgs_py import point_cloud2 +from std_msgs.msg import Header +from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster + +logger = get_logger(__name__) + +INPUT_LIDAR_TOPICS = [ + "/test/sensing/lidar/left/pointcloud", + "/test/sensing/lidar/right/pointcloud", + "/test/sensing/lidar/top/pointcloud", +] +FRAME_ID_LISTS = [ + "left_lidar", + "right_lidar", + "top_lidar", +] + +TIMEOUT_SEC = 0.2 +NUM_OF_POINTS = 3 + +global_seconds = 10 +global_nanosceonds = 100000000 +milliseconds = 1000000 +global_timestamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() + + +@pytest.mark.launch_test +def generate_test_description(): + nodes = [] + + nodes.append( + ComposableNode( + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="test_concatenate_node", + remappings=[ + ("~/input/twist", "/test/sensing/vehicle_velocity_converter/twist_with_covariance"), + ("output", "/test/sensing/lidar/concatenated/pointcloud"), + ], + parameters=[ + { + "maximum_queue_size": 5, + "timeout_sec": TIMEOUT_SEC, + "is_motion_compensated": True, + "publish_synchronized_pointcloud": True, + "keep_input_frame_in_synchronized_pointcloud": True, + "publish_previous_but_late_pointcloud": True, + "synchronized_pointcloud_postfix": "pointcloud", + "input_twist_topic_type": "twist", + "input_topics": INPUT_LIDAR_TOPICS, + "output_frame": "base_link", + "lidar_timestamp_offsets": [0.0, 0.04, 0.08], + "lidar_timestamp_noise_window": [0.01, 0.01, 0.01], + } + ], + extra_arguments=[{"use_intra_process_comms": True}], + ) + ) + + container = ComposableNodeContainer( + name="test_concateante_data_container", + namespace="pointcloud_preprocessor", + package="rclcpp_components", + executable="component_container", + composable_node_descriptions=nodes, + output="screen", + ) + + return launch.LaunchDescription( + [ + container, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +def create_header(timestamp: Time, frame_id_index: int, is_base_link: bool): + header = Header() + header.stamp = timestamp + + if is_base_link: + header.frame_id = "base_link" + else: + header.frame_id = FRAME_ID_LISTS[frame_id_index] + return header + + +def create_points(): + return [(1.0, 0.0, 0.0), (0.0, 1.0, 0.0), (0.0, 0.0, 1.0)] + + +def create_fields(): + # The values of the fields do not influence the results. + intensities = [255] * NUM_OF_POINTS + return_types = [1] * NUM_OF_POINTS + channels = [1] * NUM_OF_POINTS + azimuths = [0.0] * NUM_OF_POINTS + elevations = [0.0] * NUM_OF_POINTS + distances = [1.0] * NUM_OF_POINTS + timestamps = [0] * NUM_OF_POINTS + return intensities, return_types, channels, azimuths, elevations, distances, timestamps + + +def get_pointcloud_msg( + timestamp: Time, is_generate_points: bool, frame_id_index: int, is_base_link: bool +): + header = create_header(timestamp, frame_id_index, is_base_link) + points = create_points() + intensities, return_types, channels, azimuths, elevations, distances, timestamps = ( + create_fields() + ) + + pointcloud_data = bytearray() + + if is_generate_points: + for i in range(NUM_OF_POINTS): + pointcloud_data += struct.pack("fff", points[i][0], points[i][1], points[i][2]) + pointcloud_data += struct.pack("B", intensities[i]) + pointcloud_data += struct.pack("B", return_types[i]) + pointcloud_data += struct.pack("H", channels[i]) + pointcloud_data += struct.pack("f", azimuths[i]) + pointcloud_data += struct.pack("f", elevations[i]) + pointcloud_data += struct.pack("f", distances[i]) + pointcloud_data += struct.pack("I", timestamps[i]) + + fields = [ + PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), + PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), + PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), + PointField(name="intensity", offset=12, datatype=PointField.UINT8, count=1), + PointField(name="return_type", offset=13, datatype=PointField.UINT8, count=1), + PointField(name="channel", offset=14, datatype=PointField.UINT16, count=1), + PointField(name="azimuth", offset=16, datatype=PointField.FLOAT32, count=1), + PointField(name="elevation", offset=20, datatype=PointField.FLOAT32, count=1), + PointField(name="distance", offset=24, datatype=PointField.FLOAT32, count=1), + PointField(name="time_stamp", offset=28, datatype=PointField.UINT32, count=1), + ] + + pointcloud_msg = PointCloud2( + header=header, + height=1, + width=NUM_OF_POINTS, + is_dense=True, + is_bigendian=False, + point_step=32, # 3*4 + 1 + 1 + 2 + 4 + 4 + 4 + 4 = 32 bytes per point + row_step=32 * NUM_OF_POINTS, + fields=fields, + data=pointcloud_data, + ) + + return pointcloud_msg + + +def generate_transform_msg(parent_frame, child_frame, x, y, z, qx, qy, qz, qw): + tf_msg = TransformStamped() + tf_msg.header.stamp = global_timestamp + tf_msg.header.frame_id = parent_frame + tf_msg.child_frame_id = child_frame + tf_msg.transform.translation.x = x + tf_msg.transform.translation.y = y + tf_msg.transform.translation.z = z + tf_msg.transform.rotation.x = qx + tf_msg.transform.rotation.y = qy + tf_msg.transform.rotation.z = qz + tf_msg.transform.rotation.w = qw + return tf_msg + + +def generate_static_transform_msgs(): + tf_top_lidar_msg = generate_transform_msg( + parent_frame="base_link", + child_frame=FRAME_ID_LISTS[0], + x=0.0, + y=0.0, + z=5.0, + qx=0.0, + qy=0.0, + qz=0.0, + qw=1.0, + ) + + tf_right_lidar_msg = generate_transform_msg( + parent_frame="base_link", + child_frame=FRAME_ID_LISTS[1], + x=0.0, + y=5.0, + z=5.0, + qx=0.0, + qy=0.0, + qz=0.0, + qw=1.0, + ) + + tf_left_lidar_msg = generate_transform_msg( + parent_frame="base_link", + child_frame=FRAME_ID_LISTS[2], + x=0.0, + y=-5.0, + z=5.0, + qx=0.0, + qy=0.0, + qz=0.0, + qw=1.0, + ) + + return [tf_top_lidar_msg, tf_right_lidar_msg, tf_left_lidar_msg] + + +def generate_twist_msg(): + twist_header = Header() + twist_header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() + twist_header.frame_id = "base_link" + twist_msg = TwistWithCovarianceStamped() + twist_msg.header = twist_header + twist_msg.twist.twist.linear.x = 1.0 + + return twist_msg + + +def get_output_points(cloud_msg): + points_list = [] + for point in point_cloud2.read_points(cloud_msg, field_names=("x", "y", "z"), skip_nans=True): + points_list.append([point[0], point[1], point[2]]) + points = np.array(points_list, dtype=np.float32) + return points + + +class TestConcatenateNode(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Init ROS at once + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown ROS at once + rclpy.shutdown() + + def setUp(self): + self.node = rclpy.create_node("test_concat_node") + tf_msg = generate_static_transform_msgs() + self.tf_broadcaster = StaticTransformBroadcaster(self.node) + self.tf_broadcaster.sendTransform(tf_msg) + self.msg_buffer = [] + self.twist_publisher, self.pointcloud_publishers = self.create_pub_sub() + + def tearDown(self): + self.node.destroy_node() + + def callback(self, msg: PointCloud2): + self.msg_buffer.append(msg) + + def create_pub_sub(self): + # QoS profile for sensor data + sensor_qos = QoSProfile( + history=QoSHistoryPolicy.KEEP_LAST, + depth=10, + reliability=QoSReliabilityPolicy.BEST_EFFORT, + durability=QoSDurabilityPolicy.VOLATILE, + ) + # Publishers + twist_publisher = self.node.create_publisher( + TwistWithCovarianceStamped, + "/test/sensing/vehicle_velocity_converter/twist_with_covariance", + 10, + ) + + pointcloud_publishers = {} + for idx, input_lidar_topic in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_publishers[idx] = self.node.create_publisher( + PointCloud2, + input_lidar_topic, + qos_profile=sensor_qos, + ) + + # create subscriber + self.msg_buffer = [] + self.node.create_subscription( + PointCloud2, + "/test/sensing/lidar/concatenated/pointcloud", + self.callback, + qos_profile=sensor_qos, + ) + + return twist_publisher, pointcloud_publishers + + def test_1_normal_inputs(self): + """Test the normal situation when no pointcloud is delayed or dropped. + + This can test that + 1. Concatenate works fine when all pointclouds are arrived in time. + 2. The motion compensation of concatenation works well. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + NUM_OF_POINTS * len(FRAME_ID_LISTS), + "The concatenate pointcloud has a different number of point as expected", + ) + + # test tf + self.assertEqual( + self.msg_buffer[0].header.frame_id, + "base_link", + "The concatenate pointcloud frame id is not base_link", + ) + + expected_pointcloud = np.array( + [ + [1.08, -5, 5], + [0.08, -4, 5], + [0.08, -5, 6], + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + cloud_arr = get_output_points(self.msg_buffer[0]) + print("cloud_arr: ", cloud_arr) + self.assertTrue( + np.allclose(cloud_arr, expected_pointcloud, atol=1e-3), + "The concatenation node have wierd output", + ) + + global_seconds += 1 + + def test_2_normal_inputs_with_noise(self): + """Test the normal situation when no pointcloud is delayed or dropped. Additionally, the pointcloud's timestamp is not ideal which has some noise. + + This can test that + 1. Concatenate works fine when pointclouds' timestamp has noise. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + noise = random.uniform(-10, 10) * milliseconds + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = ( + global_nanosceonds + frame_idx * milliseconds * 40 + noise + ) # add 40 ms and noise (-10 to 10 ms) + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + NUM_OF_POINTS * len(FRAME_ID_LISTS), + "The concatenate pointcloud has a different number of point as expected", + ) + + # test tf + self.assertEqual( + self.msg_buffer[0].header.frame_id, + "base_link", + "The concatenate pointcloud frame id is not base_link", + ) + + # test transformed points + expected_pointcloud = np.array( + [ + [1.08, -5, 5], + [0.08, -4, 5], + [0.08, -5, 6], + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + 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), + "The concatenation node have wierd output", + ) + + def test_3_abnormal_null_pointcloud(self): + """Test the abnormal situation when a pointcloud is empty. + + This can test that + 1. The concatenate node ignore empty pointcloud and concatenate the remain pointcloud. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + + if frame_idx == len(INPUT_LIDAR_TOPICS) - 1: + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=False, + frame_id_index=len(INPUT_LIDAR_TOPICS) - 1, + is_base_link=False, + ) + else: + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), + "The concatenate pointcloud has a different number of point as expected", + ) + + global_seconds += 1 + + def test_4_abnormal_null_pointcloud_and_drop(self): + """Test the abnormal situation when a pointcloud is empty and other pointclouds are dropped. + + This can test that + 1. The concatenate node ignore empty pointcloud and do not publish any pointcloud. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=False, + frame_id_index=0, + is_base_link=False, + ) + + self.pointcloud_publishers[0].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 0, + "The number of concatenate pointcloud has different number as expected.", + ) + + global_seconds += 1 + + def test_5_abnormal_multiple_pointcloud_drop(self): + """Test the abnormal situation when a pointcloud was dropped. + + This can test that + 1. The concatenate node concatenates the remaining pointcloud after the timeout. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=0, + is_base_link=False, + ) + + self.pointcloud_publishers[0].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + 3, + "The concatenate pointcloud has a different number of point as expected", + ) + + def test_6_abnormal_single_pointcloud_drop(self): + """Test the abnormal situation when a pointcloud was dropped. + + This can test that + 1. The concatenate node concatenate the remain pointcloud after the timeout. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.02) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + # Should receive only one concatenate pointcloud + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), + "The concatenate pointcloud has a different number of point as expected", + ) + + global_seconds += 1 + + def test_7_abnormal_pointcloud_delay(self): + """Test the abnormal situation when a pointcloud was delayed after the timeout. + + This can test that + 1. The concatenate node concatenate the remain pointcloud after the timeout. + 2. The concatenate node will publish the delayed pointcloud after the timeout. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.02) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = ( + global_nanosceonds + (len(INPUT_LIDAR_TOPICS) - 1) * milliseconds * 40 + ) # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=len(INPUT_LIDAR_TOPICS) - 1, + is_base_link=False, + ) + + self.pointcloud_publishers[len(INPUT_LIDAR_TOPICS) - 1].publish(pointcloud_msg) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + # Should receive only one concatenate pointcloud + self.assertEqual( + len(self.msg_buffer), + 2, + "The number of concatenate pointcloud has different number as expected.", + ) + + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), + "The concatenate pointcloud has a different number of point as expected", + ) + + self.assertEqual( + len(get_output_points(self.msg_buffer[1])), + NUM_OF_POINTS, + "The concatenate pointcloud has a different number of point as expected", + ) + + global_seconds += 1 + + def test_8_abnormal_pointcloud_drop_continue_normal(self): + """Test the abnormal situation when a pointcloud was dropped. Afterward, next iteration of pointclouds comes normally. + + This can test that + 1. The concatenate node concatenate the remain pointcloud after the timeout. + 2. The concatenate node concatenate next iteration pointclouds when all of the pointcloud arrived. + """ + time.sleep(1) + global global_seconds + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) + rclpy.spin_once(self.node) + + next_global_nanosecond = global_nanosceonds + 100 * milliseconds + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_seconds = global_seconds + pointcloud_nanoseconds = ( + next_global_nanosecond + frame_idx * milliseconds * 40 + ) # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + rclpy.spin_once(self.node) + print("len of msg buffer: ", len(self.msg_buffer)) + # Should receive only one concatenate pointcloud + self.assertEqual( + len(self.msg_buffer), + 2, + "The number of concatenate pointcloud has different number as expected.", + ) + + self.assertEqual( + len(get_output_points(self.msg_buffer[0])), + NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), + "The concatenate pointcloud has a different number of point as expected", + ) + + self.assertEqual( + len(get_output_points(self.msg_buffer[1])), + NUM_OF_POINTS * len(FRAME_ID_LISTS), + "The concatenate pointcloud has a different number of point as expected", + ) + + global_seconds += 1 From 946365af7dc928d651ee7260ea3fff398c6a8644 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 19 Sep 2024 11:41:28 +0900 Subject: [PATCH 02/90] chore: solve conflicts Signed-off-by: vividf --- .../CMakeLists.txt | 8 +- .../docs/concatenate-data.md | 113 +- .../docs/distortion-corrector.md | 8 + .../image/concatenate_algorithm.drawio.svg | 810 ++++++ .../docs/image/concatenate_data.drawio.svg | 298 --- .../image/concatenate_edge_case.drawio.svg | 2334 +++++++++++++++++ .../image/ideal_timestamp_offset.drawio.svg | 784 ++++++ .../image/noise_timestamp_offset.drawio.svg | 2023 ++++++++++++++ .../concatenate_data/cloud_collector.hpp | 3 +- .../distortion_corrector.hpp | 16 +- .../cocatenate_and_time_sync_node.schema.json | 25 +- .../src/concatenate_data/cloud_collector.cpp | 2 +- .../concatenate_and_time_sync_node.cpp | 38 +- .../distortion_corrector.cpp | 8 +- ....py => test_concatenate_node_component.py} | 294 ++- ...tor.cpp => test_concatenate_node_unit.cpp} | 40 +- .../test/test_distortion_corrector_node.cpp | 22 +- 17 files changed, 6315 insertions(+), 511 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg delete mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg rename sensing/autoware_pointcloud_preprocessor/test/{test_concatenate_node.py => test_concatenate_node_component.py} (79%) rename sensing/autoware_pointcloud_preprocessor/test/{test_cloud_collector.cpp => test_concatenate_node_unit.cpp} (95%) diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 8998c1aa38ad7..76933b35c4914 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -243,16 +243,16 @@ if(BUILD_TESTING) test/test_distortion_corrector_node.cpp ) - ament_add_gtest(test_cloud_collector - test/test_cloud_collector.cpp + ament_add_gtest(test_concatenate_node_unit + test/test_concatenate_node_unit.cpp ) target_link_libraries(test_utilities pointcloud_preprocessor_filter) target_link_libraries(test_distortion_corrector_node pointcloud_preprocessor_filter) - target_link_libraries(test_cloud_collector pointcloud_preprocessor_filter) + target_link_libraries(test_concatenate_node_unit pointcloud_preprocessor_filter) add_ros_test( - test/test_concatenate_node.py + test/test_concatenate_node_component.py TIMEOUT "50" ) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 08f7b92f88975..64477a1e34cdd 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -1,75 +1,102 @@ -# concatenate_data +# concatenate_and_time_synchronize_node ## Purpose -Many self-driving cars combine multiple LiDARs to expand the sensing range. Therefore, a function to combine a plurality of point clouds is required. +The `concatenate_and_time_synchronize_node` is a ROS2 node that combines and synchronizes multiple point clouds into a single concatenated point cloud. This enhances the sensing range for autonomous driving vehicles by integrating data from multiple LiDARs. -To combine multiple sensor data with a similar timestamp, the [message_filters](https://github.com/ros2/message_filters) is often used in the ROS-based system, but this requires the assumption that all inputs can be received. Since safety must be strongly considered in autonomous driving, the point clouds concatenate node must be designed so that even if one sensor fails, the remaining sensor information can be output. +## Inner Workings / Algorithms -## Inner-workings / Algorithms +![concatenate_algorithm](./image/concatenate_algorithm.drawio.svg) -The figure below represents the reception time of each sensor data and how it is combined in the case. +### Step 1: Match and Create Collector -![concatenate_data_timing_chart](./image/concatenate_data.drawio.svg) +When a point cloud arrives, its timestamp is checked, and an offset is subtracted to get the reference timestamp. The node then checks if there is an existing collector with the same reference timestamp. If such a collector exists, the point cloud is added to it. If no such collector exists, a new collector is created with the reference timestamp. + +### Step 2: Trigger the Timer + +Once a collector is created, a timer for that collector starts counting down (this value is defined by `timeout_sec`). The collector begins to concatenate the point clouds either when the required number of point clouds has been collected or when the timer counts down to zero. + +### Step 3: Concatenate the Point Clouds + +The concatenation process involves merging multiple point clouds into a single, concatenated point cloud. The timestamp of the concatenated point cloud will be the earliest timestamp from the input point clouds. By setting the parameter `is_motion_compensated` to `true`, the node will consider the timestamps of the input point clouds and utilize the `twist` information from `geometry_msgs::msg::TwistWithCovarianceStamped` to compensate for motion, aligning the point cloud to the selected (earliest) timestamp. + +### Step 4: Publish the Point Cloud + +After concatenation, the concatenated point cloud is published, and the collector is deleted to free up resources. ## Inputs / Outputs ### Input -| Name | Type | Description | -| --------------- | ------------------------------------------------ | ----------------------------------------------------------------------------- | -| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The vehicle odometry is used to interpolate the timestamp of each sensor data | +| Name | Type | Description | +| --------------- | ------------------------------------------------ | --------------------------------------------------------------------------------- | +| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The twist information used to interpolate the timestamp of each LiDAR point cloud | +| `~/input/odom` | `nav_msgs::msg::Odometry` | The vehicle odometry used to interpolate the timestamp of each LiDAR point cloud | + +By setting the `input_twist_topic_type` parameter to `twist` or `odom`, the subscriber will subscribe to either `~/input/twist` or `~/input/odom`. If the user doesn't want to use the twist information or vehicle odometry to compensate for motion, set `is_motion_compensated` to `false`. ### Output | Name | Type | Description | | ----------------- | ------------------------------- | ------------------------- | -| `~/output/points` | `sensor_msgs::msg::Pointcloud2` | concatenated point clouds | +| `~/output/points` | `sensor_msgs::msg::Pointcloud2` | Concatenated point clouds | -## Parameters +### Core Parameters -| Name | Type | Default Value | Description | -| -------------------- | ---------------- | ------------- | ------------------------------------------------------------------- | -| `input/points` | vector of string | [] | input topic names that type must be `sensor_msgs::msg::Pointcloud2` | -| `input_frame` | string | "" | input frame id | -| `output_frame` | string | "" | output frame id | -| `has_static_tf_only` | bool | false | flag to listen TF only once | -| `max_queue_size` | int | 5 | max queue size of input/output topics | +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json") }} -### Core Parameters +### Parameter Settings + +Three parameters, `timeout_sec`, `lidar_timestamp_offsets`, and `lidar_timestamp_noise_window`, are critical for collecting point clouds in the same collector and handling edge cases effectively. + +#### timeout_sec + +When network issues occur or when point clouds experience delays in the previous processing pipeline, some point clouds may be delayed or dropped. To address this, the `timeout_sec` parameter is used. If the timer reaches zero, the collector will not wait for delayed or dropped point clouds but will concatenate the remaining point clouds in the collector directly. The figure below demonstrates how `timeout_sec` works with `concatenate_and_time_sync_node`. + +![concatenate_edge_case](./image/concatenate_edge_case.drawio.svg) + +#### lidar_timestamp_offsets + +Since different vehicles have varied designs for LiDAR scanning, the timestamps of each LiDAR may differ. Users need to know the offsets between each LiDAR and set the values in `lidar_timestamp_offsets`. For instance, if there are three LiDARs (left, right, top), and the timestamps for the left, right, and top point clouds are 0.01, 0.05, and 0.09 seconds respectively, the parameters should be set as [0.0, 0.04, 0.08]. This reflects the timestamp differences between the current point cloud and the point cloud with the earliest timestamp. Note that the order of the `lidar_timestamp_offsets` corresponds to the order of the `input_topics`. + +The figure below demonstrates how `lidar_timestamp_offsets` works with `concatenate_and_time_sync_node`. + +![ideal_timestamp_offset](./image/ideal_timestamp_offset.drawio.svg) + +#### lidar_timestamp_noise_window + +Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. + +Take the left LiDAR from the above example: if the timestamps of the left point clouds are 0.01, 0.11, and 0.21 seconds, the timestamp is ideal without any noise. Then the example will be the same as above. However, if the timestamps of the left point clouds are 0.010, 0.115, and 0.210 seconds respectively, resulting in differences of 105 ms and 95 ms, the noise is 5 ms (compared to 100 ms). In this case, the user should set 0.005 in the `lidar_timestamp_noise_window` parameter. -| Name | Type | Default Value | Description | -| --------------------------------- | ---------------- | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `timeout_sec` | double | 0.1 | tolerance of time to publish next pointcloud [s]
When this time limit is exceeded, the filter concatenates and publishes pointcloud, even if not all the point clouds are subscribed. | -| `input_offset` | vector of double | [] | This parameter can control waiting time for each input sensor pointcloud [s]. You must to set the same length of offsets with input pointclouds numbers.
For its tuning, please see [actual usage page](#how-to-tuning-timeout_sec-and-input_offset). | -| `publish_synchronized_pointcloud` | bool | false | If true, publish the time synchronized pointclouds. All input pointclouds are transformed and then re-published as message named `_synchronized`. | -| `input_twist_topic_type` | std::string | twist | Topic type for twist. Currently support `twist` or `odom`. | +The figure below demonstrates how `lidar_timestamp_noise_window` works with `concatenate_and_time_sync_node`. If the green `X` is in the range of the red triangles, it means that the point cloud matches the reference timestamp of the collector. -## Actual Usage +![noise_timestamp_offset](./image/noise_timestamp_offset.drawio.svg) -For the example of actual usage of this node, please refer to the [preprocessor.launch.py](../launch/preprocessor.launch.py) file. +## Launch -### How to tuning timeout_sec and input_offset +```bash +# The launch file will read the parameters from the concatenate_and_time_sync_node.param.yaml +ros2 launch autoware_pointcloud_preprocessor concatenate_and_time_sync_node.launch.xml +``` -The values in `timeout_sec` and `input_offset` are used in the timer_callback to control concatenation timings. +## Test -- Assumptions - - when the timer runs out, we concatenate the pointclouds in the buffer - - when the first pointcloud comes to buffer, we reset the timer to `timeout_sec` - - when the second and later pointclouds comes to buffer, we reset the timer to `timeout_sec` - `input_offset` - - we assume all lidar has same frequency +```bash +# build autoware_pointcloud_preprocessor +colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-up-to autoware_pointcloud_preprocessor -| Name | Description | How to tune | -| -------------- | ---------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `timeout_sec` | timeout sec for default timer | To avoid mis-concatenation, at least this value must be shorter than sampling time. | -| `input_offset` | timeout extension when a pointcloud comes to buffer. | The amount of waiting time will be `timeout_sec` - `input_offset`. So, you will need to set larger value for the last-coming pointcloud and smaller for fore-coming. | +# test autoware_pointcloud_preprocessor +colcon test --packages-select autoware_pointcloud_preprocessor --event-handlers console_cohesion+ +``` -### Node separation options for future +### Node separation options -Since the pointcloud concatenation has two process, "time synchronization" and "pointcloud concatenation", it is possible to separate these processes. +There is also an option to separate the concatenate_and_time_sync_node into two nodes: one for `time synchronization` and another for `concatenate pointclouds` ([See this PR](https://github.com/autowarefoundation/autoware.universe/pull/3312)). -In the future, Nodes will be completely separated in order to achieve node loosely coupled nature, but currently both nodes can be selected for backward compatibility ([See this PR](https://github.com/autowarefoundation/autoware.universe/pull/3312)). +Note that the `concatenate_pointclouds` and `time_synchronizer_nodelet` are using the old design of the concatenate node. -## Assumptions / Known limits +## Assumptions / Known Limits -It is necessary to assume that the vehicle odometry value exists, the sensor data and odometry timestamp are correct, and the TF from `base_link` to `sensor_frame` is also correct. +- If `is_motion_compensated` is set to `false`, the `concatenate_and_time_sync_node` will directly concatenate the point clouds without applying for motion compensation. This can save several milliseconds depending on the number of LiDARs being concatenated. Therefore, if the timestamp differences between point clouds are negligible, the user can set `is_motion_compensated` to `false` and omit the need for twist or odometry input for the node. +- As mentioned above, the user should clearly understand how their LiDAR's point cloud timestamps are managed to set the parameters correctly. diff --git a/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md index ab5a07b5279bc..44a064e89ad1a 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md @@ -44,6 +44,14 @@ Please note that the processing time difference between the two distortion metho ros2 launch autoware_pointcloud_preprocessor distortion_corrector.launch.xml ``` +## Test + +```bash +colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-up-to autoware_pointcloud_preprocessor + +colcon test --packages-select autoware_pointcloud_preprocessor --event-handlers console_cohesion+ +``` + ## Assumptions / Known limits - The node requires time synchronization between the topics from lidars, twist, and IMU. diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg new file mode 100644 index 0000000000000..0ca825f5acaa6 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg @@ -0,0 +1,810 @@ + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Collector +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ left pc +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ top pc +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ right pc +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+ L +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
stamp: t1_left
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ stamp: t1_right +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
stamp: t1_top
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ reference timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ T +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ R +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
arrival time
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ compare with the +
reference timestamp.
+
If match, add to the group
+
if it doesn't match, create new group
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ Left pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Right pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
Top pointcloud
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ timer +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ add to the collector +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ create a collector +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ set stamp as +
reference timestamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ trigger the timer +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ When timer count to zero +
+ concatenate + publish +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ When group has +
left, right, top pointclouds
+
+ + concatenate + publish + +
+
+
+
+
+ +
+
+
+
+ + + + + + +
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg deleted file mode 100644 index 786fee4c22ed7..0000000000000 --- a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg +++ /dev/null @@ -1,298 +0,0 @@ - - - - - - - - - - -
-
-
- input topic 1 -
-
-
-
- input topic... -
-
- - - - -
-
-
- input topic 2 -
-
-
-
- input topic... -
-
- - - - -
-
-
- input topic 3 -
-
-
-
- input topic... -
-
- - - - - - - -
-
-
- concatenated topic -
-
-
-
- concatenate... -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- timer -
- start -
-
-
-
- timer... -
-
- - - - -
-
-
- this data is abandoned -
-
-
-
- this data i... -
-
- - - - - - - - - -
-
-
- t0 -
-
-
-
- t0 -
-
- - - - -
-
-
- t1 -
-
-
-
- t1 -
-
- - - - -
-
-
- t2 -
-
-
-
- t2 -
-
- - - - -
-
-
- t3 -
-
-
-
- t3 -
-
- - - - - - - - - - - - - - -
-
-
- timer -
- start -
-
-
-
- timer... -
-
- - - - - -
-
-
- timeout -
-
-
-
- timeout -
-
- - - - - - -
-
-
- t4 -
-
-
-
- t4 -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg new file mode 100644 index 0000000000000..bf81613c7e536 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg @@ -0,0 +1,2334 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
+ receive all pc +
+ concatenate +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
+ group 1: + timeout +
+ concatenate +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + Normal + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + One pointcloud + +
+ + drop + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Several pointclouds + +
+ + delay + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Several pointclouds + +
+ + delay, and one drop + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Several pointclouds + +
+ + delay, and drop + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + One pointcloud + +
+ + delay + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
group 1 created.
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+
group 2 created.
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
group 2
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
group 1 created.
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+
group 1
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
group 1 created.
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+
group 1
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
group 1 created.
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+
group 1
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
Can decide to
+
publish or not
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
120 ms
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
120 ms
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
120 ms
+
+
+
+ +
+
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg new file mode 100644 index 0000000000000..0b8eca9dd75aa --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg @@ -0,0 +1,784 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 80 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ lidar_timestamp_offset: [0.0, 0.04, 0.08] +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ ideal timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ first arrive pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference timestamp +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 80 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+ compare with +
reference stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ compare with +
reference stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ compare with +
reference stamp
+
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg new file mode 100644 index 0000000000000..bf5d604d2fb94 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg @@ -0,0 +1,2023 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 20 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 40 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 20 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
-5ms
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+10ms
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
-15
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
15
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
-15ms
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ minus offset 80 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+5ms
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+10ms
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
15
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-15
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
-15ms
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ ideal timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ first arrive pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
real timestamp
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ possible reference timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ possible timestamp +
for non-first pointcloud
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ timestamp of non-first pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ lidar_timestamp_offset: [0.0, 0.04, 0.08] +
+ + lidar_timestamp_noise_window: [0.005, 0.01, 0.015] +
+
+
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Case 2 + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Case 1 + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 29085472579c0..f71bb1df968b5 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -94,8 +94,7 @@ class CloudCollector void deleteCollector(); - std::unordered_map - get_topic_to_cloud_map(); + std::unordered_map getTopicToCloudMap(); private: std::shared_ptr concatenate_node_; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index e786bff04b3cd..7e26d4c1cf2c8 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -50,10 +50,10 @@ namespace autoware::pointcloud_preprocessor class DistortionCorrectorBase { public: - virtual bool pointcloud_transform_exists() = 0; - virtual bool pointcloud_transform_needed() = 0; - virtual std::deque get_twist_queue() = 0; - virtual std::deque get_angular_velocity_queue() = 0; + virtual bool pointcloudTransformExists() = 0; + virtual bool pointcloudTransformNeeded() = 0; + virtual std::deque getTwistQueue() = 0; + virtual std::deque getAngularVelocityQueue() = 0; virtual void processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) = 0; @@ -104,10 +104,10 @@ class DistortionCorrector : public DistortionCorrectorBase managed_tf_buffer_ = std::make_unique(node, has_static_tf_only); } - bool pointcloud_transform_exists(); - bool pointcloud_transform_needed(); - std::deque get_twist_queue(); - std::deque get_angular_velocity_queue(); + bool pointcloudTransformExists(); + bool pointcloudTransformNeeded(); + std::deque getTwistQueue(); + std::deque getAngularVelocityQueue(); void processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) override; diff --git a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json index 059411e02ab92..183b807ec83b2 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json @@ -16,11 +16,6 @@ "default": 0.0, "description": "Timeout in seconds." }, - "offset_tolerance": { - "type": "number", - "default": 0.0, - "description": "Tolerance for offset." - }, "is_motion_compensated": { "type": "boolean", "default": true, @@ -36,6 +31,11 @@ "default": true, "description": "Flag to indicate if input frame should be kept in synchronized point cloud." }, + "publish_previous_but_late_pointcloud": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if a concatenated point cloud should be published if its timestamp is earlier than the previous published concatenated point cloud." + }, "synchronized_pointcloud_postfix": { "type": "string", "default": "pointcloud", @@ -56,7 +56,7 @@ }, "output_frame": { "type": "string", - "default": "", + "default": "base_link", "description": "Output frame." }, "lidar_timestamp_offsets": { @@ -66,20 +66,29 @@ }, "default": [], "description": "List of LiDAR timestamp offsets." + }, + "lidar_timestamp_noise_window": { + "type": "array", + "items": { + "type": "number" + }, + "default": [], + "description": "List of LiDAR timestamp noise window." } }, "required": [ "maximum_queue_size", "timeout_sec", - "offset_tolerance", "is_motion_compensated", "publish_synchronized_pointcloud", "keep_input_frame_in_synchronized_pointcloud", + "publish_previous_but_late_pointcloud", "synchronized_pointcloud_postfix", "input_twist_topic_type", "input_topics", "output_frame", - "lidar_timestamp_offsets" + "lidar_timestamp_offsets", + "lidar_timestamp_noise_window" ] } }, diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 28ae3fc85dc12..315d53e304c4c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -149,7 +149,7 @@ void CloudCollector::deleteCollector() } std::unordered_map -CloudCollector::get_topic_to_cloud_map() +CloudCollector::getTopicToCloudMap() { return topic_to_cloud_map_; } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 475a203319727..920f2aa6e2466 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -147,23 +147,25 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } // Subscribers - if (params_.input_twist_topic_type == "twist") { - twist_sub_ = this->create_subscription( - "~/input/twist", rclcpp::QoS{100}, - std::bind( - &PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, - std::placeholders::_1)); - } else if (params_.input_twist_topic_type == "odom") { - odom_sub_ = this->create_subscription( - "~/input/odom", rclcpp::QoS{100}, - std::bind( - &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, - std::placeholders::_1)); - } else { - RCLCPP_ERROR_STREAM( - get_logger(), "input_twist_topic_type is invalid: " << params_.input_twist_topic_type); - throw std::runtime_error( - "input_twist_topic_type is invalid: " + params_.input_twist_topic_type); + if (params_.is_motion_compensated) { + if (params_.input_twist_topic_type == "twist") { + twist_sub_ = this->create_subscription( + "~/input/twist", rclcpp::QoS{100}, + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, + std::placeholders::_1)); + } else if (params_.input_twist_topic_type == "odom") { + odom_sub_ = this->create_subscription( + "~/input/odom", rclcpp::QoS{100}, + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, + std::placeholders::_1)); + } else { + RCLCPP_ERROR_STREAM( + get_logger(), "input_twist_topic_type is invalid: " << params_.input_twist_topic_type); + throw std::runtime_error( + "input_twist_topic_type is invalid: " + params_.input_twist_topic_type); + } } pointcloud_subs.resize(params_.input_topics.size()); @@ -184,7 +186,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); } - // Cloud handler + // Combine cloud handler combine_cloud_handler_ = std::make_shared( this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, params_.keep_input_frame_in_synchronized_pointcloud); diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index d0119fbc44f24..eff4e726352b6 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -25,25 +25,25 @@ namespace autoware::pointcloud_preprocessor { template -bool DistortionCorrector::pointcloud_transform_exists() +bool DistortionCorrector::pointcloudTransformExists() { return pointcloud_transform_exists_; } template -bool DistortionCorrector::pointcloud_transform_needed() +bool DistortionCorrector::pointcloudTransformNeeded() { return pointcloud_transform_needed_; } template -std::deque DistortionCorrector::get_twist_queue() +std::deque DistortionCorrector::getTwistQueue() { return twist_queue_; } template -std::deque DistortionCorrector::get_angular_velocity_queue() +std::deque DistortionCorrector::getAngularVelocityQueue() { return angular_velocity_queue_; } diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py similarity index 79% rename from sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py rename to sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index ac1a63b9ef07a..ce0c2653022d1 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -17,21 +17,17 @@ import random import struct import time +from typing import List +from typing import Tuple import unittest -# TODO: remove unused later from geometry_msgs.msg import TransformStamped from geometry_msgs.msg import TwistWithCovarianceStamped import launch import launch.actions -from launch.logging import get_logger from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode import launch_testing -import launch_testing.actions -import launch_testing.asserts -import launch_testing.markers -import launch_testing.tools import numpy as np import pytest import rclpy @@ -46,8 +42,6 @@ from std_msgs.msg import Header from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster -logger = get_logger(__name__) - INPUT_LIDAR_TOPICS = [ "/test/sensing/lidar/left/pointcloud", "/test/sensing/lidar/right/pointcloud", @@ -60,12 +54,19 @@ ] TIMEOUT_SEC = 0.2 +TIMESTAMP_OFFSET = [0.0, 0.04, 0.08] +TIMESTAMP_NOISE = 0.01 # 10 ms + NUM_OF_POINTS = 3 +DEBUG = False +MILLISECONDS = 1000000 + + +STANDARD_TOLERANCE = 1e-4 +COARSE_TOLERANCE = TIMESTAMP_NOISE * 2 global_seconds = 10 global_nanosceonds = 100000000 -milliseconds = 1000000 -global_timestamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() @pytest.mark.launch_test @@ -93,8 +94,12 @@ def generate_test_description(): "input_twist_topic_type": "twist", "input_topics": INPUT_LIDAR_TOPICS, "output_frame": "base_link", - "lidar_timestamp_offsets": [0.0, 0.04, 0.08], - "lidar_timestamp_noise_window": [0.01, 0.01, 0.01], + "lidar_timestamp_offsets": TIMESTAMP_OFFSET, + "lidar_timestamp_noise_window": [ + TIMESTAMP_NOISE, + TIMESTAMP_NOISE, + TIMESTAMP_NOISE, + ], } ], extra_arguments=[{"use_intra_process_comms": True}], @@ -119,7 +124,7 @@ def generate_test_description(): ) -def create_header(timestamp: Time, frame_id_index: int, is_base_link: bool): +def create_header(timestamp: Time, frame_id_index: int, is_base_link: bool) -> Header: header = Header() header.stamp = timestamp @@ -130,11 +135,13 @@ def create_header(timestamp: Time, frame_id_index: int, is_base_link: bool): return header -def create_points(): +def create_points() -> List[Tuple[float, float, float]]: return [(1.0, 0.0, 0.0), (0.0, 1.0, 0.0), (0.0, 0.0, 1.0)] -def create_fields(): +def create_fields() -> ( + Tuple[List[int], List[int], List[int], List[float], List[float], List[float], List[int]] +): # The values of the fields do not influence the results. intensities = [255] * NUM_OF_POINTS return_types = [1] * NUM_OF_POINTS @@ -148,7 +155,7 @@ def create_fields(): def get_pointcloud_msg( timestamp: Time, is_generate_points: bool, frame_id_index: int, is_base_link: bool -): +) -> PointCloud2: header = create_header(timestamp, frame_id_index, is_base_link) points = create_points() intensities, return_types, channels, azimuths, elevations, distances, timestamps = ( @@ -196,9 +203,19 @@ def get_pointcloud_msg( return pointcloud_msg -def generate_transform_msg(parent_frame, child_frame, x, y, z, qx, qy, qz, qw): +def generate_transform_msg( + parent_frame: str, + child_frame: str, + x: float, + y: float, + z: float, + qx: float, + qy: float, + qz: float, + qw: float, +) -> TransformStamped: tf_msg = TransformStamped() - tf_msg.header.stamp = global_timestamp + tf_msg.header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() tf_msg.header.frame_id = parent_frame tf_msg.child_frame_id = child_frame tf_msg.transform.translation.x = x @@ -211,7 +228,7 @@ def generate_transform_msg(parent_frame, child_frame, x, y, z, qx, qy, qz, qw): return tf_msg -def generate_static_transform_msgs(): +def generate_static_transform_msgs() -> List[TransformStamped]: tf_top_lidar_msg = generate_transform_msg( parent_frame="base_link", child_frame=FRAME_ID_LISTS[0], @@ -251,7 +268,7 @@ def generate_static_transform_msgs(): return [tf_top_lidar_msg, tf_right_lidar_msg, tf_left_lidar_msg] -def generate_twist_msg(): +def generate_twist_msg() -> TwistWithCovarianceStamped: twist_header = Header() twist_header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() twist_header.frame_id = "base_link" @@ -262,7 +279,7 @@ def generate_twist_msg(): return twist_msg -def get_output_points(cloud_msg): +def get_output_points(cloud_msg) -> np.ndarray: points_list = [] for point in point_cloud2.read_points(cloud_msg, field_names=("x", "y", "z"), skip_nans=True): points_list.append([point[0], point[1], point[2]]) @@ -344,7 +361,7 @@ def test_1_normal_inputs(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -364,18 +381,6 @@ def test_1_normal_inputs(self): 1, "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - NUM_OF_POINTS * len(FRAME_ID_LISTS), - "The concatenate pointcloud has a different number of point as expected", - ) - - # test tf - self.assertEqual( - self.msg_buffer[0].header.frame_id, - "base_link", - "The concatenate pointcloud frame id is not base_link", - ) expected_pointcloud = np.array( [ @@ -392,13 +397,22 @@ def test_1_normal_inputs(self): dtype=np.float32, ) - cloud_arr = get_output_points(self.msg_buffer[0]) - print("cloud_arr: ", cloud_arr) + concatenate_cloud = get_output_points(self.msg_buffer[0]) + + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + self.assertTrue( - np.allclose(cloud_arr, expected_pointcloud, atol=1e-3), + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), "The concatenation node have wierd output", ) + self.assertEqual( + self.msg_buffer[0].header.frame_id, + "base_link", + "The concatenate pointcloud frame id is not base_link", + ) + global_seconds += 1 def test_2_normal_inputs_with_noise(self): @@ -414,10 +428,10 @@ def test_2_normal_inputs_with_noise(self): self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): - noise = random.uniform(-10, 10) * milliseconds + noise = random.uniform(-10, 10) * MILLISECONDS pointcloud_seconds = global_seconds pointcloud_nanoseconds = ( - global_nanosceonds + frame_idx * milliseconds * 40 + noise + global_nanosceonds + frame_idx * MILLISECONDS * 40 + noise ) # add 40 ms and noise (-10 to 10 ms) pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -438,20 +452,7 @@ def test_2_normal_inputs_with_noise(self): 1, "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - NUM_OF_POINTS * len(FRAME_ID_LISTS), - "The concatenate pointcloud has a different number of point as expected", - ) - # test tf - self.assertEqual( - self.msg_buffer[0].header.frame_id, - "base_link", - "The concatenate pointcloud frame id is not base_link", - ) - - # test transformed points expected_pointcloud = np.array( [ [1.08, -5, 5], @@ -467,10 +468,12 @@ def test_2_normal_inputs_with_noise(self): dtype=np.float32, ) - cloud_arr = get_output_points(self.msg_buffer[0]) - print("cloud_arr: ", cloud_arr) + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + self.assertTrue( - np.allclose(cloud_arr, expected_pointcloud, atol=1e-2), + np.allclose(concatenate_cloud, expected_pointcloud, atol=2e-2), "The concatenation node have wierd output", ) @@ -488,7 +491,7 @@ def test_3_abnormal_null_pointcloud(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -519,10 +522,26 @@ def test_3_abnormal_null_pointcloud(self): 1, "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), - "The concatenate pointcloud has a different number of point as expected", + + expected_pointcloud = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have wierd output", ) global_seconds += 1 @@ -567,10 +586,10 @@ def test_4_abnormal_null_pointcloud_and_drop(self): global_seconds += 1 def test_5_abnormal_multiple_pointcloud_drop(self): - """Test the abnormal situation when a pointcloud was dropped. + """Test the abnormal situation when multiple pointclouds were dropped (only one poincloud arrive). This can test that - 1. The concatenate node concatenates the remaining pointcloud after the timeout. + 1. The concatenate node concatenates the single pointcloud after the timeout. """ time.sleep(1) global global_seconds @@ -602,10 +621,23 @@ def test_5_abnormal_multiple_pointcloud_drop(self): 1, "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - 3, - "The concatenate pointcloud has a different number of point as expected", + + expected_pointcloud = np.array( + [ + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have wierd output", ) def test_6_abnormal_single_pointcloud_drop(self): @@ -622,7 +654,7 @@ def test_6_abnormal_single_pointcloud_drop(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -645,10 +677,25 @@ def test_6_abnormal_single_pointcloud_drop(self): "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), - "The concatenate pointcloud has a different number of point as expected", + expected_pointcloud = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have wierd output", ) global_seconds += 1 @@ -668,7 +715,7 @@ def test_7_abnormal_pointcloud_delay(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -686,7 +733,7 @@ def test_7_abnormal_pointcloud_delay(self): pointcloud_seconds = global_seconds pointcloud_nanoseconds = ( - global_nanosceonds + (len(INPUT_LIDAR_TOPICS) - 1) * milliseconds * 40 + global_nanosceonds + (len(INPUT_LIDAR_TOPICS) - 1) * MILLISECONDS * 40 ) # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -710,16 +757,43 @@ def test_7_abnormal_pointcloud_delay(self): "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), - "The concatenate pointcloud has a different number of point as expected", + expected_pointcloud1 = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, ) - self.assertEqual( - len(get_output_points(self.msg_buffer[1])), - NUM_OF_POINTS, - "The concatenate pointcloud has a different number of point as expected", + concatenate_cloud1 = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud 1: ", concatenate_cloud1) + + self.assertTrue( + np.allclose(concatenate_cloud1, expected_pointcloud1, atol=1e-3), + "The concatenation node have wierd output", + ) + + expected_pointcloud2 = np.array( + [ + [1, -5, 5], + [0, -4, 5], + [0, -5, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud2 = get_output_points(self.msg_buffer[1]) + if DEBUG: + print("concatenate_cloud 2: ", concatenate_cloud2) + + self.assertTrue( + np.allclose(concatenate_cloud2, expected_pointcloud2, atol=1e-3), + "The concatenation node have wierd output", ) global_seconds += 1 @@ -739,7 +813,7 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * milliseconds * 40 # add 40 ms + pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -755,11 +829,11 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): time.sleep(TIMEOUT_SEC) rclpy.spin_once(self.node) - next_global_nanosecond = global_nanosceonds + 100 * milliseconds + next_global_nanosecond = global_nanosceonds + 100 * MILLISECONDS for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): pointcloud_seconds = global_seconds pointcloud_nanoseconds = ( - next_global_nanosecond + frame_idx * milliseconds * 40 + next_global_nanosecond + frame_idx * MILLISECONDS * 40 ) # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -774,24 +848,56 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): time.sleep(0.01) rclpy.spin_once(self.node) - print("len of msg buffer: ", len(self.msg_buffer)) - # Should receive only one concatenate pointcloud + self.assertEqual( len(self.msg_buffer), 2, "The number of concatenate pointcloud has different number as expected.", ) - self.assertEqual( - len(get_output_points(self.msg_buffer[0])), - NUM_OF_POINTS * (len(FRAME_ID_LISTS) - 1), - "The concatenate pointcloud has a different number of point as expected", + expected_pointcloud1 = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, ) - self.assertEqual( - len(get_output_points(self.msg_buffer[1])), - NUM_OF_POINTS * len(FRAME_ID_LISTS), - "The concatenate pointcloud has a different number of point as expected", + concatenate_cloud1 = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud 1: ", concatenate_cloud1) + + self.assertTrue( + np.allclose(concatenate_cloud1, expected_pointcloud1, atol=1e-3), + "The concatenation node have wierd output", + ) + + expected_pointcloud2 = np.array( + [ + [1.08, -5, 5], + [0.08, -4, 5], + [0.08, -5, 6], + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud2 = get_output_points(self.msg_buffer[1]) + if DEBUG: + print("concatenate_cloud 2: ", concatenate_cloud2) + + self.assertTrue( + np.allclose(concatenate_cloud2, expected_pointcloud2, atol=1e-3), + "The concatenation node have wierd output", ) global_seconds += 1 diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp similarity index 95% rename from sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp rename to sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index f3f0626364f88..397310f5b4335 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -11,10 +11,10 @@ // 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. -// cloud_collector_test.cpp -// cloud_collector_test.cpp -// cloud_collector_test.cpp +// Note: To regenerate the ground truth (GT) for the expected undistorted point cloud values, +// set the "debug_" value to true to display the point cloud values. Then, +// replace the expected values with the newly displayed undistorted point cloud values. #include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" #include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" @@ -175,12 +175,12 @@ class ConcatenateCloudTest : public ::testing::Test static constexpr size_t number_of_points_{3}; static constexpr float standard_tolerance_{1e-4}; static constexpr int number_of_pointcloud_{3}; - static constexpr float timeout_sec_{1}; - bool debug_{true}; + static constexpr float timeout_sec_{0.2}; + bool debug_{false}; }; //////////////////////////////// Test combine_cloud_handler //////////////////////////////// -TEST_F(ConcatenateCloudTest, ProcessTwist) +TEST_F(ConcatenateCloudTest, TestProcessTwist) { auto twist_msg = std::make_shared(); twist_msg->header.stamp = rclcpp::Time(10, 0); @@ -194,7 +194,7 @@ TEST_F(ConcatenateCloudTest, ProcessTwist) EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.angular.z, 0.1); } -TEST_F(ConcatenateCloudTest, ProcessOdometry) +TEST_F(ConcatenateCloudTest, TestProcessOdometry) { auto odom_msg = std::make_shared(); odom_msg->header.stamp = rclcpp::Time(10, 0); @@ -208,7 +208,7 @@ TEST_F(ConcatenateCloudTest, ProcessOdometry) EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.angular.z, 0.1); } -TEST_F(ConcatenateCloudTest, ComputeTransformToAdjustForOldTimestamp) +TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) { rclcpp::Time old_stamp(10, 100000000, RCL_ROS_TIME); rclcpp::Time new_stamp(10, 150000000, RCL_ROS_TIME); @@ -249,7 +249,7 @@ TEST_F(ConcatenateCloudTest, ComputeTransformToAdjustForOldTimestamp) //////////////////////////////// Test cloud_collector //////////////////////////////// -TEST_F(ConcatenateCloudTest, SetAndGetReferenceTimeStampBoundary) +TEST_F(ConcatenateCloudTest, TestSetAndGetReferenceTimeStampBoundary) { double reference_timestamp = 10.0; double noise_window = 0.1; @@ -259,7 +259,7 @@ TEST_F(ConcatenateCloudTest, SetAndGetReferenceTimeStampBoundary) EXPECT_DOUBLE_EQ(max, 10.1); } -TEST_F(ConcatenateCloudTest, concatenateAndPublishClouds) +TEST_F(ConcatenateCloudTest, TestConcatenateClouds) { rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40000000, RCL_ROS_TIME); @@ -311,14 +311,14 @@ TEST_F(ConcatenateCloudTest, concatenateAndPublishClouds) EXPECT_FLOAT_EQ(*iter_z, expected_pointcloud[i].z()); } - // concatenate cloud should have the oldest pointcloud's timestamp - EXPECT_FLOAT_EQ( - top_timestamp.seconds(), rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds()); - if (debug_) { RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); } + // test concatenate cloud has the oldest pointcloud's timestamp + EXPECT_FLOAT_EQ( + top_timestamp.seconds(), rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds()); + // test seperated transformed cloud std::array expected_top_pointcloud = { {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), @@ -405,13 +405,13 @@ TEST_F(ConcatenateCloudTest, concatenateAndPublishClouds) EXPECT_FLOAT_EQ(right_timestamp.seconds(), topic_to_original_stamp_map["lidar_right"]); } -TEST_F(ConcatenateCloudTest, DeleteCollector) +TEST_F(ConcatenateCloudTest, TestDeleteCollector) { collector_->deleteCollector(); EXPECT_TRUE(collectors_.empty()); } -TEST_F(ConcatenateCloudTest, ProcessSingleCloud) +TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) { rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = @@ -420,19 +420,19 @@ TEST_F(ConcatenateCloudTest, ProcessSingleCloud) std::make_shared(top_pointcloud); collector_->processCloud("lidar_top", top_pointcloud_ptr); - auto topic_to_cloud_map = collector_->get_topic_to_cloud_map(); + auto topic_to_cloud_map = collector_->getTopicToCloudMap(); EXPECT_EQ(topic_to_cloud_map["lidar_top"], top_pointcloud_ptr); EXPECT_FALSE(collectors_.empty()); - // Sleep for 1.5 seconds - std::this_thread::sleep_for(std::chrono::milliseconds(1500)); + // Sleep for timeout seconds (200 ms) + std::this_thread::sleep_for(std::chrono::milliseconds(200)); rclcpp::spin_some(concatenate_node_); // Collector should concatenate and publish the pointcloud, also delete itself. EXPECT_TRUE(collectors_.empty()); } -TEST_F(ConcatenateCloudTest, ProcessMultipleCloud) +TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) { rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40000000, RCL_ROS_TIME); diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index 047d021a4c6da..2e0306c6217c2 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -286,9 +286,9 @@ TEST_F(DistortionCorrectorTest, TestProcessTwistMessage) auto twist_msg = generateTwistMsg(twist_linear_x_, twist_angular_z_, timestamp); distortion_corrector_2d_->processTwistMessage(twist_msg); - ASSERT_FALSE(distortion_corrector_2d_->get_twist_queue().empty()); - EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.linear.x, twist_linear_x_); - EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.angular.z, twist_angular_z_); + ASSERT_FALSE(distortion_corrector_2d_->getTwistQueue().empty()); + EXPECT_EQ(distortion_corrector_2d_->getTwistQueue().front().twist.linear.x, twist_linear_x_); + EXPECT_EQ(distortion_corrector_2d_->getTwistQueue().front().twist.angular.z, twist_angular_z_); } TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) @@ -297,9 +297,9 @@ TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) auto imu_msg = generateImuMsg(imu_angular_x_, imu_angular_y_, imu_angular_z_, timestamp); distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); - ASSERT_FALSE(distortion_corrector_2d_->get_angular_velocity_queue().empty()); + ASSERT_FALSE(distortion_corrector_2d_->getAngularVelocityQueue().empty()); EXPECT_NEAR( - distortion_corrector_2d_->get_angular_velocity_queue().front().vector.z, -0.03159, + distortion_corrector_2d_->getAngularVelocityQueue().front().vector.z, -0.03159, standard_tolerance_); } @@ -329,22 +329,22 @@ TEST_F(DistortionCorrectorTest, TestIsInputValid) TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithBaseLink) { distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); - EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists()); - EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloudTransformExists()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloudTransformNeeded()); } TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithLidarFrame) { distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); - EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists()); - EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_needed()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloudTransformExists()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloudTransformNeeded()); } TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithMissingFrame) { distortion_corrector_2d_->setPointCloudTransform("base_link", "missing_lidar_frame"); - EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_exists()); - EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloudTransformExists()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloudTransformNeeded()); } TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyTwist) From d4978f7ef9e3d2116c78c7b603e855f25f9d24c0 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 1 Aug 2024 13:46:07 +0900 Subject: [PATCH 03/90] chore: fix cpp check Signed-off-by: vividf --- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 920f2aa6e2466..e0f71fee8eb0c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -182,7 +182,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro RCLCPP_DEBUG_STREAM( get_logger(), "Subscribing to " << params_.input_topics.size() << " user given topics as inputs:"); - for (auto & input_topic : params_.input_topics) { + for (const auto & input_topic : params_.input_topics) { RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); } @@ -438,8 +438,6 @@ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( diagnostic_updater::DiagnosticStatusWrapper & stat) { if (publish_pointcloud_ || drop_previous_but_late_pointcloud_) { - std::set missed_cloud; - stat.add("concatenated cloud timestamp", formatTimestamp(current_concat_cloud_timestamp_)); stat.add("reference timestamp min", formatTimestamp(diagnostic_reference_timestamp_min_)); stat.add("reference timestamp max", formatTimestamp(diagnostic_reference_timestamp_max_)); From 63a870b1e4709c04472f51d2e9988e016efc7e2f Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 1 Aug 2024 15:22:23 +0900 Subject: [PATCH 04/90] chore: add diagnostics readme Signed-off-by: vividf --- .../docs/concatenate-data.md | 88 ++++++++++++++++++- 1 file changed, 87 insertions(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 64477a1e34cdd..4e0dd2887dc8f 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -90,7 +90,93 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --package colcon test --packages-select autoware_pointcloud_preprocessor --event-handlers console_cohesion+ ``` -### Node separation options +## Debug and Diagnostics + +To verify whether the node has successfully concatenated the point clouds, the user can examine the `/diagnostics` topic using the following command: + +```bash +ros2 topic echo /diagnostics +``` + +Below is an example output when the point clouds are concatenated successfully: + +- Each point cloud has a value of `1`. +- The `concatenate status` is `1`. +- The `level` value is `\0`. (diagnostic_msgs::msg::DiagnosticStatus::OK) + +```bash +header: + stamp: + sec: 1722492015 + nanosec: 848508777 + frame_id: '' +status: +- level: "\0" + name: 'concatenate_and_time_sync_node: concat_status' + message: Concatenated pointcloud is published and include all topics + hardware_id: concatenate_data_checker + values: + - key: concatenated cloud timestamp + value: '1718260240.159229994' + - key: reference timestamp min + value: '1718260240.149230003' + - key: reference timestamp max + value: '1718260240.169229984' + - key: /sensing/lidar/left/pointcloud_before_sync timestamp + value: '1718260240.159229994' + - key: /sensing/lidar/left/pointcloud_before_sync + value: '1' + - key: /sensing/lidar/right/pointcloud_before_sync timestamp + value: '1718260240.194104910' + - key: /sensing/lidar/right/pointcloud_before_sync + value: '1' + - key: /sensing/lidar/top/pointcloud_before_sync timestamp + value: '1718260240.234578133' + - key: /sensing/lidar/top/pointcloud_before_sync + value: '1' + - key: concatenate status + value: '1' +``` + +Below is an example when point clouds fail to concatenate successfully. + +- Some point clouds might have values of `0`. +- The `concatenate status` is `0`. +- The `level` value is `\x02`. (diagnostic_msgs::msg::DiagnosticStatus::ERROR) + +```bash +header: + stamp: + sec: 1722492663 + nanosec: 344942959 + frame_id: '' +status: +- level: "\x02" + name: 'concatenate_and_time_sync_node: concat_status' + message: Concatenated pointcloud is published but miss some topics + hardware_id: concatenate_data_checker + values: + - key: concatenated cloud timestamp + value: '1718260240.859827995' + - key: reference timestamp min + value: '1718260240.849828005' + - key: reference timestamp max + value: '1718260240.869827986' + - key: /sensing/lidar/left/pointcloud_before_sync timestamp + value: '1718260240.859827995' + - key: /sensing/lidar/left/pointcloud_before_sync + value: '1' + - key: /sensing/lidar/right/pointcloud_before_sync timestamp + value: '1718260240.895193815' + - key: /sensing/lidar/right/pointcloud_before_sync + value: '1' + - key: /sensing/lidar/top/pointcloud_before_sync + value: '0' + - key: concatenate status + value: '0' +``` + +## Node separation options There is also an option to separate the concatenate_and_time_sync_node into two nodes: one for `time synchronization` and another for `concatenate pointclouds` ([See this PR](https://github.com/autowarefoundation/autoware.universe/pull/3312)). From c8cca1f95fad5cfef642cd56a1d80fac4e65717d Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 1 Aug 2024 15:34:33 +0900 Subject: [PATCH 05/90] chore: update figure Signed-off-by: vividf --- .../image/concatenate_edge_case.drawio.svg | 115 +++++++++++------- 1 file changed, 71 insertions(+), 44 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg index bf81613c7e536..33835b6396e51 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg @@ -8,7 +8,7 @@ width="2232px" height="963px" viewBox="-0.5 -0.5 2232 963" - content="<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/126.0.0.0 Safari/537.36" scale="1" border="0" version="24.7.6"> <diagram name="Page-1" id="NLJ4wg49r_tGfpfCC3yf"> <mxGraphModel dx="3417" dy="2014" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-385" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="757.5000000000002" as="sourcePoint" /> <mxPoint x="2225" y="757.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-386" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2095" y="797.5000000000002" as="sourcePoint" /> <mxPoint x="2225" y="797.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-387" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2175" y="837.5" as="sourcePoint" /> <mxPoint x="2225" y="837.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-388" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-389" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="797.5" as="sourcePoint" /> <mxPoint x="2095" y="797.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-389" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1825" y="787.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-390" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-431" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="877.5" as="sourcePoint" /> <mxPoint x="2225" y="877.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-391" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-392" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="837.5" as="sourcePoint" /> <mxPoint x="2095" y="837.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-392" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1925" y="827.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-393" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1715" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-394" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1835" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-395" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1955" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-396" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="757.5" as="sourcePoint" /> <mxPoint x="1975" y="757.5000000000002" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-397" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-389" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1795" y="797.5" as="sourcePoint" /> <mxPoint x="2075" y="797.5000000000002" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-398" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1735" y="747.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-399" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2075" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-400" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="877.5" as="sourcePoint" /> <mxPoint x="2000" y="877.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-401" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-392" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1940" y="837.5" as="sourcePoint" /> <mxPoint x="2155" y="837.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-406" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="1097.5" as="sourcePoint" /> <mxPoint x="2225" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-407" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2085" y="1137.5" as="sourcePoint" /> <mxPoint x="2225" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-408" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2145" y="1177.5" as="sourcePoint" /> <mxPoint x="2225" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-409" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-410" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1137.5" as="sourcePoint" /> <mxPoint x="2095" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-410" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1825" y="1127.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-411" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2215" y="1217.5" as="sourcePoint" /> <mxPoint x="2225" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-412" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-413" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1177.5" as="sourcePoint" /> <mxPoint x="2095" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-413" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1935" y="1167.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-414" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1715" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-415" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1835" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-416" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1955" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-417" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1097.5" as="sourcePoint" /> <mxPoint x="1975" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-418" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-410" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1795" y="1137.5" as="sourcePoint" /> <mxPoint x="2065" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-419" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1735" y="1087.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-420" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2075" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-421" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1217.5" as="sourcePoint" /> <mxPoint x="2025" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-422" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-413" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1915" y="1177.5" as="sourcePoint" /> <mxPoint x="2125" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-423" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2015" y="1217.5" as="sourcePoint" /> <mxPoint x="2215" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-427" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1975" y="745" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-428" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2075" y="785" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-429" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2155" y="822.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-430" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-431" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="877.5" as="sourcePoint" /> <mxPoint x="2225" y="877.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-431" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2205" y="862.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-433" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1975" y="1082.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-434" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2065" y="1122.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-435" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2125" y="1162.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-444" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1130" y="440.25" as="sourcePoint" /> <mxPoint x="1360" y="440.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-445" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1170" y="480.25" as="sourcePoint" /> <mxPoint x="1360" y="480.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-446" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-484" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="520.25" as="sourcePoint" /> <mxPoint x="1360" y="520.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-447" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-448" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="480.25" as="sourcePoint" /> <mxPoint x="1230" y="480.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-448" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="910" y="470.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-449" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-486" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="560.25" as="sourcePoint" /> <mxPoint x="1360" y="560.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-450" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-451" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="520.25" as="sourcePoint" /> <mxPoint x="1230" y="520.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-451" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="950" y="510.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-453" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="850" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-454" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="970" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-455" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1090" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-456" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="440.25" as="sourcePoint" /> <mxPoint x="1110" y="440.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-457" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-448" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="930" y="480.25" as="sourcePoint" /> <mxPoint x="1150" y="480.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-458" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="870" y="430.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-459" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1210" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-460" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1120" y="760" as="sourcePoint" /> <mxPoint x="1350" y="760" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-461" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1160" y="800" as="sourcePoint" /> <mxPoint x="1350" y="800" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-462" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-489" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="840" as="sourcePoint" /> <mxPoint x="1350" y="840" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-463" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-464" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="800" as="sourcePoint" /> <mxPoint x="1220" y="800" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-464" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="900" y="790" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-465" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=0.681;exitY=0.753;exitDx=0;exitDy=0;exitPerimeter=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-491" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="880" as="sourcePoint" /> <mxPoint x="1350" y="880" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-466" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-467" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="840" as="sourcePoint" /> <mxPoint x="1220" y="840" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-467" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="940" y="830" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-468" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="840" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-469" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="960" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-470" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1080" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-471" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="760" as="sourcePoint" /> <mxPoint x="1100" y="760" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-472" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-464" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="920" y="800" as="sourcePoint" /> <mxPoint x="1140" y="800" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-473" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="860" y="750" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-474" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1200" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-475" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1000" y="360.25" as="sourcePoint" /> <mxPoint x="999.6600000000001" y="595.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-476" value="&lt;div&gt;&lt;font color=&quot;#ff0000&quot;&gt;receive all pc&lt;/font&gt;&lt;/div&gt;&lt;font color=&quot;#ff0000&quot;&gt;concatenate&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1000" y="575.25" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-477" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1144.8899999999999" y="707.5" as="sourcePoint" /> <mxPoint x="1144.55" y="942.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-480" value="&lt;div&gt;group 1:&amp;nbsp;&lt;span style=&quot;background-color: initial;&quot;&gt;timeout&lt;/span&gt;&lt;/div&gt;concatenate" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1100" y="950" width="110" height="40" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-481" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1115" y="425.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-482" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1150" y="465.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-483" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-451" target="80uhdLyXJ-cf-2mWR6Fi-484" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="970" y="520.25" as="sourcePoint" /> <mxPoint x="1360" y="520.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-484" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1190" y="505.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-485" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-486" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="560.25" as="sourcePoint" /> <mxPoint x="1360" y="560.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-486" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1230" y="545.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-487" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1095" y="745" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-488" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1135" y="785" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-490" value="" style="endArrow=none;dashed=1;html=1;rounded=0;entryX=0.625;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-491" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="880" as="sourcePoint" /> <mxPoint x="1350" y="880" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-491" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1215" y="870" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-503" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-467" target="80uhdLyXJ-cf-2mWR6Fi-489" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="960" y="840" as="sourcePoint" /> <mxPoint x="1350" y="840" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-489" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1175" y="827.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-505" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Normal&lt;/b&gt;&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="660" y="486.25" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-506" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;One pointcloud&lt;/b&gt;&lt;/font&gt;&lt;div&gt;&lt;font size=&quot;3&quot;&gt;&lt;b&gt;drop&lt;/b&gt;&lt;/font&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="630" y="797.5" width="160" height="50" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-507" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Several pointclouds&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1510" y="470.25" width="190" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-508" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Several pointclouds&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay, and one drop&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1480" y="785" width="200" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-509" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Several pointclouds&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay, and drop&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1510" y="1127.5" width="190" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-570" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;One pointcloud&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="640" y="1127.5" width="160" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-452" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="990" y="550.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-639" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1125" y="1097.5" as="sourcePoint" /> <mxPoint x="1355" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-640" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1165" y="1137.5" as="sourcePoint" /> <mxPoint x="1355" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-641" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-666" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1177.5" as="sourcePoint" /> <mxPoint x="1355" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-642" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-643" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1137.5" as="sourcePoint" /> <mxPoint x="1225" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-643" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="905" y="1127.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-644" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=0.681;exitY=0.753;exitDx=0;exitDy=0;exitPerimeter=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-660" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1217.5" as="sourcePoint" /> <mxPoint x="1355" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-645" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-646" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1177.5" as="sourcePoint" /> <mxPoint x="1225" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-646" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="945" y="1167.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-647" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="845" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-648" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="965" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-649" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1085" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-650" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1097.5" as="sourcePoint" /> <mxPoint x="1105" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-651" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-643" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="925" y="1137.5" as="sourcePoint" /> <mxPoint x="1145" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-652" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="865" y="1087.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-653" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1205" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-654" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1064.6299999999999" y="1040" as="sourcePoint" /> <mxPoint x="1064.29" y="1275" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-657" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1100" y="1082.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-658" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1140" y="1122.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-659" value="" style="endArrow=none;dashed=1;html=1;rounded=0;entryX=0.625;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-699" target="80uhdLyXJ-cf-2mWR6Fi-660" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1217.5" as="sourcePoint" /> <mxPoint x="1355" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-660" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1220" y="1207.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-665" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-646" target="80uhdLyXJ-cf-2mWR6Fi-666" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="965" y="1177.5" as="sourcePoint" /> <mxPoint x="1355" y="1177.5" as="targetPoint" /> <Array as="points" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-666" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1180" y="1165" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-700" value="" style="endArrow=none;dashed=1;html=1;rounded=0;entryX=0.625;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-699" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1217.5" as="sourcePoint" /> <mxPoint x="1230" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-699" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1055" y="1207.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-2" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="870.3399999999998" y="710" as="sourcePoint" /> <mxPoint x="869.9999999999999" y="945" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-4" value="" style="endArrow=none;html=1;rounded=0;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1105.3399999999997" y="710" as="sourcePoint" /> <mxPoint x="1105" y="945" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-5" value="&lt;div&gt;group 1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="815" y="950" width="110" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-6" value="&lt;div&gt;group 2 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#6c8ebf;fillColor=#dae8fc;" parent="1" vertex="1"> <mxGeometry x="1040" y="660" width="110" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-7" value="" style="endArrow=none;html=1;rounded=0;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1224.9799999999998" y="710" as="sourcePoint" /> <mxPoint x="1224.64" y="945" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-8" value="&lt;div&gt;group 2&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#6c8ebf;fillColor=#dae8fc;" parent="1" vertex="1"> <mxGeometry x="1185" y="660" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-9" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="874.6299999999998" y="1040" as="sourcePoint" /> <mxPoint x="874.2899999999998" y="1275" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-10" value="&lt;div&gt;group 1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="820" y="1280" width="110" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-11" value="&lt;div&gt;group 1&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1025" y="1280" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-42" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-65" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="437.5" as="sourcePoint" /> <mxPoint x="2265" y="437.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-43" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2095" y="477.5" as="sourcePoint" /> <mxPoint x="2265" y="477.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-44" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2145" y="517.5" as="sourcePoint" /> <mxPoint x="2265" y="517.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-45" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-46" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="477.5" as="sourcePoint" /> <mxPoint x="2095" y="477.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-46" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1835" y="467.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-47" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2195" y="557.5" as="sourcePoint" /> <mxPoint x="2265" y="557.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-48" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-49" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="517.5" as="sourcePoint" /> <mxPoint x="2095" y="517.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-49" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1935" y="507.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-50" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1715" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-51" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1835" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-52" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1955" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-53" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="437.5" as="sourcePoint" /> <mxPoint x="1975" y="437.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-54" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-46" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1795" y="477.5" as="sourcePoint" /> <mxPoint x="2075" y="477.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-55" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1735" y="427.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-56" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2075" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-57" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="557.5" as="sourcePoint" /> <mxPoint x="2225" y="557.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-58" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-49" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1940" y="517.5" as="sourcePoint" /> <mxPoint x="2125" y="517.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-64" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-65" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="437.5" as="sourcePoint" /> <mxPoint x="2265" y="437.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-65" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;" parent="1" vertex="1"> <mxGeometry x="2215" y="427.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-66" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2020" y="557.5" as="sourcePoint" /> <mxPoint x="2175" y="557.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-68" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1975" y="425" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-69" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2075" y="462.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-70" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2125" y="502.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-71" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2175" y="542.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-74" value="&lt;div&gt;group 1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1700" y="605" width="110" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-75" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1745.3399999999997" y="360" as="sourcePoint" /> <mxPoint x="1745" y="595" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-76" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" source="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2024.1599999999999" y="363.75" as="sourcePoint" /> <mxPoint x="2023.82" y="598.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-77" value="&lt;div&gt;group 1&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1975" y="612.5" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-79" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2685" y="476.25" as="sourcePoint" /> <mxPoint x="2855" y="476.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-80" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2735" y="516.25" as="sourcePoint" /> <mxPoint x="2855" y="516.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-81" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-82" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="476.25" as="sourcePoint" /> <mxPoint x="2685" y="476.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-82" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2425" y="466.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-83" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2785" y="556.25" as="sourcePoint" /> <mxPoint x="2855" y="556.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-84" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-85" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="516.25" as="sourcePoint" /> <mxPoint x="2685" y="516.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-85" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2525" y="506.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-86" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2305" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-87" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2425" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-88" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2545" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-89" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="436.25" as="sourcePoint" /> <mxPoint x="2565" y="436.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-90" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-82" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2385" y="476.25" as="sourcePoint" /> <mxPoint x="2665" y="476.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-91" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2325" y="426.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-92" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2665" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-93" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-95" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="556.25" as="sourcePoint" /> <mxPoint x="2815" y="556.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-94" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-85" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2530" y="516.25" as="sourcePoint" /> <mxPoint x="2715" y="516.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-95" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#d5e8d4;strokeColor=#82b366;" parent="1" vertex="1"> <mxGeometry x="2680" y="547.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-96" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2585" y="436.25" as="sourcePoint" /> <mxPoint x="2860" y="436.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-98" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-95" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2610" y="556.25" as="sourcePoint" /> <mxPoint x="2765" y="556.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-99" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2565" y="423.75" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-100" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2665" y="461.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-101" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2715" y="501.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-102" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2765" y="541.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-103" value="&lt;div&gt;group 1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="2290" y="603.75" width="110" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-104" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2335.3399999999997" y="358.75" as="sourcePoint" /> <mxPoint x="2335" y="593.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-105" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2615.3399999999997" y="358.75" as="sourcePoint" /> <mxPoint x="2615" y="593.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-106" value="&lt;div&gt;group 1&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="2565" y="603.75" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-108" value="" style="endArrow=none;html=1;rounded=0;fillColor=#d5e8d4;strokeColor=#82b366;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2689.75" y="362.5" as="sourcePoint" /> <mxPoint x="2689.41" y="597.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-109" value="&lt;div&gt;Can decide to&lt;/div&gt;&lt;div&gt;&amp;nbsp;publish or not&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#82b366;fillColor=#d5e8d4;" parent="1" vertex="1"> <mxGeometry x="2690" y="605" width="100" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-112" value="" style="group" parent="1" vertex="1" connectable="0"> <mxGeometry x="2340" y="557.5" width="275" height="30" as="geometry" /> </mxCell> <mxCell id="cD1KZ4Ka8YFXE9963_W6-1" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;" parent="viYa4thklxoO5ObslHZt-112" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint y="29.289999999999964" as="sourcePoint" /> <mxPoint x="275" y="29.289999999999964" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="cD1KZ4Ka8YFXE9963_W6-2" value="120 ms" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="viYa4thklxoO5ObslHZt-112" vertex="1"> <mxGeometry x="110" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-113" value="" style="group" parent="1" vertex="1" connectable="0"> <mxGeometry x="870" y="900" width="275" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-114" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;" parent="viYa4thklxoO5ObslHZt-113" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint y="29.289999999999964" as="sourcePoint" /> <mxPoint x="275" y="29.289999999999964" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-115" value="120 ms" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="viYa4thklxoO5ObslHZt-113" vertex="1"> <mxGeometry x="110" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-122" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" target="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2024.1599999999999" y="363.75" as="sourcePoint" /> <mxPoint x="2023.82" y="598.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-63" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2015" y="547.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-123" value="" style="group" parent="1" vertex="1" connectable="0"> <mxGeometry x="1745" y="565" width="275" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-124" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;" parent="viYa4thklxoO5ObslHZt-123" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint y="29.289999999999964" as="sourcePoint" /> <mxPoint x="275" y="29.289999999999964" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-125" value="120 ms" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="viYa4thklxoO5ObslHZt-123" vertex="1"> <mxGeometry x="110" width="60" height="30" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + content="<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/126.0.0.0 Safari/537.36" scale="1" border="0" version="24.7.6"> <diagram name="Page-1" id="NLJ4wg49r_tGfpfCC3yf"> <mxGraphModel dx="1709" dy="1007" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-385" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="757.5000000000002" as="sourcePoint" /> <mxPoint x="2225" y="757.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-386" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2095" y="797.5000000000002" as="sourcePoint" /> <mxPoint x="2225" y="797.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-387" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2175" y="837.5" as="sourcePoint" /> <mxPoint x="2225" y="837.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-388" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-389" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="797.5" as="sourcePoint" /> <mxPoint x="2095" y="797.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-389" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1825" y="787.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-390" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-431" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="877.5" as="sourcePoint" /> <mxPoint x="2225" y="877.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-391" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-392" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="837.5" as="sourcePoint" /> <mxPoint x="2095" y="837.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-392" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1925" y="827.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-393" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1715" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-394" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1835" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-395" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1955" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-396" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="757.5" as="sourcePoint" /> <mxPoint x="1975" y="757.5000000000002" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-397" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-389" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1795" y="797.5" as="sourcePoint" /> <mxPoint x="2075" y="797.5000000000002" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-398" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1735" y="747.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-399" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2075" y="707.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-400" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="877.5" as="sourcePoint" /> <mxPoint x="2000" y="877.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-401" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-392" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1940" y="837.5" as="sourcePoint" /> <mxPoint x="2155" y="837.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-406" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="1097.5" as="sourcePoint" /> <mxPoint x="2225" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-407" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2085" y="1137.5" as="sourcePoint" /> <mxPoint x="2225" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-408" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2145" y="1177.5" as="sourcePoint" /> <mxPoint x="2225" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-409" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-410" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1137.5" as="sourcePoint" /> <mxPoint x="2095" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-410" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1825" y="1127.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-411" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2215" y="1217.5" as="sourcePoint" /> <mxPoint x="2225" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-412" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-413" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1177.5" as="sourcePoint" /> <mxPoint x="2095" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-413" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1935" y="1167.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-414" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1715" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-415" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1835" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-416" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1955" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-417" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1097.5" as="sourcePoint" /> <mxPoint x="1975" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-418" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-410" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1795" y="1137.5" as="sourcePoint" /> <mxPoint x="2065" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-419" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1735" y="1087.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-420" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2075" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-421" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="1217.5" as="sourcePoint" /> <mxPoint x="2025" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-422" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-413" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1915" y="1177.5" as="sourcePoint" /> <mxPoint x="2125" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-423" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2015" y="1217.5" as="sourcePoint" /> <mxPoint x="2215" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-427" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1975" y="745" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-428" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2075" y="785" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-429" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2155" y="822.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-430" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-431" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="877.5" as="sourcePoint" /> <mxPoint x="2225" y="877.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-431" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2205" y="862.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-433" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1975" y="1082.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-434" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2065" y="1122.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-435" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2125" y="1162.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-444" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1130" y="440.25" as="sourcePoint" /> <mxPoint x="1360" y="440.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-445" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1170" y="480.25" as="sourcePoint" /> <mxPoint x="1360" y="480.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-446" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-484" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="520.25" as="sourcePoint" /> <mxPoint x="1360" y="520.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-447" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-448" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="480.25" as="sourcePoint" /> <mxPoint x="1230" y="480.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-448" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="910" y="470.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-449" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-486" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="560.25" as="sourcePoint" /> <mxPoint x="1360" y="560.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-450" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-451" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="520.25" as="sourcePoint" /> <mxPoint x="1230" y="520.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-451" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="950" y="510.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-453" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="850" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-454" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="970" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-455" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1090" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-456" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="440.25" as="sourcePoint" /> <mxPoint x="1110" y="440.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-457" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-448" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="930" y="480.25" as="sourcePoint" /> <mxPoint x="1150" y="480.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-458" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="870" y="430.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-459" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1210" y="390.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-460" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1120" y="760" as="sourcePoint" /> <mxPoint x="1350" y="760" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-461" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1160" y="800" as="sourcePoint" /> <mxPoint x="1350" y="800" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-462" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-489" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="840" as="sourcePoint" /> <mxPoint x="1350" y="840" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-463" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-464" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="800" as="sourcePoint" /> <mxPoint x="1220" y="800" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-464" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="900" y="790" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-465" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=0.681;exitY=0.753;exitDx=0;exitDy=0;exitPerimeter=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-491" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="880" as="sourcePoint" /> <mxPoint x="1350" y="880" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-466" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-467" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="840" as="sourcePoint" /> <mxPoint x="1220" y="840" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-467" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="940" y="830" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-468" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="840" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-469" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="960" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-470" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1080" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-471" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="760" as="sourcePoint" /> <mxPoint x="1100" y="760" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-472" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-464" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="920" y="800" as="sourcePoint" /> <mxPoint x="1140" y="800" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-473" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="860" y="750" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-474" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1200" y="710" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-475" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1000" y="360.25" as="sourcePoint" /> <mxPoint x="999.6600000000001" y="595.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-476" value="&lt;div&gt;&lt;font color=&quot;#ff0000&quot;&gt;receive all pc&lt;/font&gt;&lt;/div&gt;&lt;font color=&quot;#ff0000&quot;&gt;concatenate&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1000" y="575.25" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-477" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1144.8899999999999" y="707.5" as="sourcePoint" /> <mxPoint x="1144.55" y="942.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-480" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1:&amp;nbsp;&lt;span style=&quot;background-color: initial;&quot;&gt;timeout&lt;/span&gt;&lt;/div&gt;concatenate" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1095" y="950" width="120" height="40" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-481" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1115" y="425.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-482" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1150" y="465.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-483" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-451" target="80uhdLyXJ-cf-2mWR6Fi-484" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="970" y="520.25" as="sourcePoint" /> <mxPoint x="1360" y="520.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-484" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1190" y="505.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-485" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-486" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="860" y="560.25" as="sourcePoint" /> <mxPoint x="1360" y="560.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-486" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1230" y="545.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-487" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1095" y="745" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-488" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1135" y="785" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-490" value="" style="endArrow=none;dashed=1;html=1;rounded=0;entryX=0.625;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-491" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="850" y="880" as="sourcePoint" /> <mxPoint x="1350" y="880" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-491" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1215" y="870" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-503" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-467" target="80uhdLyXJ-cf-2mWR6Fi-489" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="960" y="840" as="sourcePoint" /> <mxPoint x="1350" y="840" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-489" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1175" y="827.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-505" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Normal&lt;/b&gt;&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="660" y="486.25" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-506" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;One pointcloud&lt;/b&gt;&lt;/font&gt;&lt;div&gt;&lt;font size=&quot;3&quot;&gt;&lt;b&gt;drop&lt;/b&gt;&lt;/font&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="630" y="797.5" width="160" height="50" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-507" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Several pointclouds&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1510" y="470.25" width="190" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-508" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Several pointclouds&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay, and one drop&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1480" y="785" width="200" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-509" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;Several pointclouds&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay, and drop&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="1510" y="1127.5" width="190" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-570" value="&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;One pointcloud&lt;/b&gt;&lt;/span&gt;&lt;div&gt;&lt;span style=&quot;font-size: 18px;&quot;&gt;&lt;b&gt;&amp;nbsp;delay&lt;/b&gt;&lt;/span&gt;&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="1" vertex="1"> <mxGeometry x="640" y="1127.5" width="160" height="60" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-452" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="990" y="550.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-639" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1125" y="1097.5" as="sourcePoint" /> <mxPoint x="1355" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-640" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1165" y="1137.5" as="sourcePoint" /> <mxPoint x="1355" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-641" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-666" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1177.5" as="sourcePoint" /> <mxPoint x="1355" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-642" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-643" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1137.5" as="sourcePoint" /> <mxPoint x="1225" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-643" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="905" y="1127.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-644" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=0.681;exitY=0.753;exitDx=0;exitDy=0;exitPerimeter=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-660" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1217.5" as="sourcePoint" /> <mxPoint x="1355" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-645" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-646" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1177.5" as="sourcePoint" /> <mxPoint x="1225" y="1177.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-646" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="945" y="1167.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-647" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="845" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-648" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="965" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-649" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1085" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-650" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1097.5" as="sourcePoint" /> <mxPoint x="1105" y="1097.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-651" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-643" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="925" y="1137.5" as="sourcePoint" /> <mxPoint x="1145" y="1137.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-652" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="865" y="1087.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-653" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1205" y="1047.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-654" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1064.6299999999999" y="1040" as="sourcePoint" /> <mxPoint x="1064.29" y="1275" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-657" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1100" y="1082.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-658" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1140" y="1122.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-659" value="" style="endArrow=none;dashed=1;html=1;rounded=0;entryX=0.625;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-699" target="80uhdLyXJ-cf-2mWR6Fi-660" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1217.5" as="sourcePoint" /> <mxPoint x="1355" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-660" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1220" y="1207.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-665" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="80uhdLyXJ-cf-2mWR6Fi-646" target="80uhdLyXJ-cf-2mWR6Fi-666" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="965" y="1177.5" as="sourcePoint" /> <mxPoint x="1355" y="1177.5" as="targetPoint" /> <Array as="points" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-666" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1180" y="1165" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-700" value="" style="endArrow=none;dashed=1;html=1;rounded=0;entryX=0.625;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" target="80uhdLyXJ-cf-2mWR6Fi-699" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="855" y="1217.5" as="sourcePoint" /> <mxPoint x="1230" y="1217.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="80uhdLyXJ-cf-2mWR6Fi-699" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1055" y="1207.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-2" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="870.3399999999998" y="710" as="sourcePoint" /> <mxPoint x="869.9999999999999" y="945" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-4" value="" style="endArrow=none;html=1;rounded=0;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1105.3399999999997" y="710" as="sourcePoint" /> <mxPoint x="1105" y="945" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-5" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="810" y="950" width="120" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-6" value="&lt;div&gt;collector 2 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#6c8ebf;fillColor=#dae8fc;" parent="1" vertex="1"> <mxGeometry x="1035" y="660" width="120" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-7" value="" style="endArrow=none;html=1;rounded=0;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1224.9799999999998" y="710" as="sourcePoint" /> <mxPoint x="1224.64" y="945" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-8" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;2&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#6c8ebf;fillColor=#dae8fc;" parent="1" vertex="1"> <mxGeometry x="1185" y="660" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-9" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="874.6299999999998" y="1040" as="sourcePoint" /> <mxPoint x="874.2899999999998" y="1275" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-10" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="815" y="1280" width="120" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-11" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1025" y="1280" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-42" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-65" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="437.5" as="sourcePoint" /> <mxPoint x="2265" y="437.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-43" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2095" y="477.5" as="sourcePoint" /> <mxPoint x="2265" y="477.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-44" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2145" y="517.5" as="sourcePoint" /> <mxPoint x="2265" y="517.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-45" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-46" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="477.5" as="sourcePoint" /> <mxPoint x="2095" y="477.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-46" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1835" y="467.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-47" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2195" y="557.5" as="sourcePoint" /> <mxPoint x="2265" y="557.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-48" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-49" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="517.5" as="sourcePoint" /> <mxPoint x="2095" y="517.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-49" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1935" y="507.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-50" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1715" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-51" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1835" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-52" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="1955" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-53" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="437.5" as="sourcePoint" /> <mxPoint x="1975" y="437.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-54" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-46" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1795" y="477.5" as="sourcePoint" /> <mxPoint x="2075" y="477.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-55" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="1735" y="427.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-56" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2075" y="387.5" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-57" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1725" y="557.5" as="sourcePoint" /> <mxPoint x="2225" y="557.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-58" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-49" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1940" y="517.5" as="sourcePoint" /> <mxPoint x="2125" y="517.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-64" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-65" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1995" y="437.5" as="sourcePoint" /> <mxPoint x="2265" y="437.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-65" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;" parent="1" vertex="1"> <mxGeometry x="2215" y="427.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-66" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2020" y="557.5" as="sourcePoint" /> <mxPoint x="2175" y="557.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-68" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="1975" y="425" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-69" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2075" y="462.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-70" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2125" y="502.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-71" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2175" y="542.5" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-74" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1695" y="605" width="120" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-75" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1745.3399999999997" y="360" as="sourcePoint" /> <mxPoint x="1745" y="595" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-76" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" source="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2024.1599999999999" y="363.75" as="sourcePoint" /> <mxPoint x="2023.82" y="598.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-77" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="1975" y="612.5" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-79" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2685" y="476.25" as="sourcePoint" /> <mxPoint x="2855" y="476.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-80" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2735" y="516.25" as="sourcePoint" /> <mxPoint x="2855" y="516.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-81" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-82" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="476.25" as="sourcePoint" /> <mxPoint x="2685" y="476.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-82" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2425" y="466.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-83" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2785" y="556.25" as="sourcePoint" /> <mxPoint x="2855" y="556.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-84" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-85" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="516.25" as="sourcePoint" /> <mxPoint x="2685" y="516.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-85" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2525" y="506.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-86" value="0" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2305" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-87" value="50" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2425" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-88" value="100" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2545" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-89" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="436.25" as="sourcePoint" /> <mxPoint x="2565" y="436.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-90" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-82" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2385" y="476.25" as="sourcePoint" /> <mxPoint x="2665" y="476.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-91" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2325" y="426.25" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-92" value="150" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="2665" y="386.25" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-93" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" target="viYa4thklxoO5ObslHZt-95" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2315" y="556.25" as="sourcePoint" /> <mxPoint x="2815" y="556.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-94" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-85" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2530" y="516.25" as="sourcePoint" /> <mxPoint x="2715" y="516.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-95" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#d5e8d4;strokeColor=#82b366;" parent="1" vertex="1"> <mxGeometry x="2680" y="547.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-96" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2585" y="436.25" as="sourcePoint" /> <mxPoint x="2860" y="436.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-98" value="" style="endArrow=none;dashed=1;html=1;rounded=0;" parent="1" source="viYa4thklxoO5ObslHZt-95" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2610" y="556.25" as="sourcePoint" /> <mxPoint x="2765" y="556.25" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-99" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2565" y="423.75" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-100" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2665" y="461.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-101" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2715" y="501.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-102" value="" style="triangle;whiteSpace=wrap;html=1;rotation=-90;fillColor=#dae8fc;strokeColor=#6c8ebf;" parent="1" vertex="1"> <mxGeometry x="2765" y="541.25" width="20" height="25" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-103" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1 created.&lt;/div&gt;&lt;div&gt;timer start&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="2285" y="603.75" width="120" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-104" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2335.3399999999997" y="358.75" as="sourcePoint" /> <mxPoint x="2335" y="593.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-105" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2615.3399999999997" y="358.75" as="sourcePoint" /> <mxPoint x="2615" y="593.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-106" value="&lt;div&gt;&lt;span style=&quot;background-color: initial;&quot;&gt;collector&lt;/span&gt;&amp;nbsp;1&lt;/div&gt;&lt;div&gt;&amp;nbsp;concatenate&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#b85450;fillColor=#f8cecc;" parent="1" vertex="1"> <mxGeometry x="2565" y="603.75" width="90" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-108" value="" style="endArrow=none;html=1;rounded=0;fillColor=#d5e8d4;strokeColor=#82b366;" parent="1" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2689.75" y="362.5" as="sourcePoint" /> <mxPoint x="2689.41" y="597.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-109" value="&lt;div&gt;Can decide to&lt;/div&gt;&lt;div&gt;&amp;nbsp;publish or not&lt;/div&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=#82b366;fillColor=#d5e8d4;" parent="1" vertex="1"> <mxGeometry x="2690" y="605" width="100" height="40" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-112" value="" style="group" parent="1" vertex="1" connectable="0"> <mxGeometry x="2340" y="557.5" width="275" height="30" as="geometry" /> </mxCell> <mxCell id="cD1KZ4Ka8YFXE9963_W6-1" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;" parent="viYa4thklxoO5ObslHZt-112" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint y="29.289999999999964" as="sourcePoint" /> <mxPoint x="275" y="29.289999999999964" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="cD1KZ4Ka8YFXE9963_W6-2" value="120 ms" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="viYa4thklxoO5ObslHZt-112" vertex="1"> <mxGeometry x="110" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-113" value="" style="group" parent="1" vertex="1" connectable="0"> <mxGeometry x="870" y="900" width="275" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-114" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;" parent="viYa4thklxoO5ObslHZt-113" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint y="29.289999999999964" as="sourcePoint" /> <mxPoint x="275" y="29.289999999999964" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-115" value="120 ms" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="viYa4thklxoO5ObslHZt-113" vertex="1"> <mxGeometry x="110" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-122" value="" style="endArrow=none;html=1;rounded=0;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" target="viYa4thklxoO5ObslHZt-63" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="2024.1599999999999" y="363.75" as="sourcePoint" /> <mxPoint x="2023.82" y="598.75" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-63" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#f8cecc;strokeColor=#b85450;" parent="1" vertex="1"> <mxGeometry x="2015" y="547.5" width="20" height="20" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-123" value="" style="group" parent="1" vertex="1" connectable="0"> <mxGeometry x="1745" y="565" width="275" height="30" as="geometry" /> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-124" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;" parent="viYa4thklxoO5ObslHZt-123" edge="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint y="29.289999999999964" as="sourcePoint" /> <mxPoint x="275" y="29.289999999999964" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="viYa4thklxoO5ObslHZt-125" value="120 ms" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" parent="viYa4thklxoO5ObslHZt-123" vertex="1"> <mxGeometry x="110" width="60" height="30" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " style="background-color: rgb(255, 255, 255);" > @@ -42,7 +42,9 @@ - + + + @@ -157,7 +159,7 @@ - + @@ -655,7 +657,7 @@ - + @@ -856,7 +858,7 @@ - + @@ -869,7 +871,8 @@
- group 1: + collector + 1: timeout
concatenate @@ -878,11 +881,11 @@
@@ -900,7 +903,7 @@ - + @@ -1197,7 +1200,7 @@ - + @@ -1410,7 +1413,7 @@ - + @@ -1422,18 +1425,21 @@ >
-
group 1 created.
+
+ collector + 1 created. +
timer start
@@ -1441,7 +1447,7 @@
- + @@ -1453,18 +1459,18 @@ >
-
group 2 created.
+
collector 2 created.
timer start
@@ -1489,7 +1495,10 @@ >
-
group 2
+
+ collector + 2 +
concatenate
@@ -1500,7 +1509,7 @@ y="307" width="69" height="32" - xlink:href="data:image/png;base64,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" + xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAARQAAACACAYAAADK8JaYAAAAAXNSR0IArs4c6QAAIABJREFUeF7tnQXU5LqRhW+YmXHDzMzMTBtmpg0zMzNnkw0zMzNzNsy4YWYmfxNpTk2NbMvdsru3X9U5c977u21ZvpKuCtUHUkggEAgEAo0QOFCjdqKZQCAQCAQUhBKTIBAIBJohEITSDMpoKBAIBIJQYg4EAoFAMwSCUJpBGQ0FAoFAEErMgUAgEGiGQBBKMyijoUAgEAhCiTkQCAQCzRAIQmkD5UEl/dU1dVZJnyg0/6Du2nuaz9/YXXeZNt2IVgKBzSIQhNIG/yCUNjhGK/9G4CCSTiPpdJKOLOmwkn4r6ReSviDpc5L+to1gBaG0GZUglDY4HtBbOUVHGreRdC1Jhx8A4w+SXt6RzRMkfWqbQAtCaTMaQSh1OP6HpBukS/9X0mvqbtv5q5g/95Z0d0kHm/C2/5D06GRCe5N7QjPtLg1CaYNlEEodjreU9OR06XMlXb/utp2+CgJ5iaQrrfGWL05azT/XaKPJrUEoTWBUEEodjs+XdO0glH3AgmAhWiu/l/R0Sa9M/pLfSTqipDMm4rhe8rPYe24n6fF1wzDfVUEobbANQqnD8RuSThSEshes80h6n7RPke4XJV1W0jcHID2/JKKDhzHX/FzSCSRBPhuTIJQ20AehjON4dEk/NpeFySO9tnOqXs5g8qvO2XpqST8Yh3OPufhsdx1m06sr7p3tkiCUNtAGoYzjeHnnhD2gE8oRJKFVECLOglP2YeNQ7rniwJK+L+mY5vonpihRZRPtL9tGQjl7UvkuKOk4ktjZcDYRg/+8pPdKYjL+cEU4ziDpkl07tI+KeNQU52d3YIC/Jundkt4k6SuVz1iSUE6Y8LmopJN2Ts6jdZ7+wyV8ftY59z4r6a2S3pDep/IV9rsMZ+ElElbnlHQMSUeR9CdJP+368Mn0HByKhDFL4pP4xvpyxYrIzxzjl/M8cv9+nXwW/M2Cv7mk60g6VcLafj/2Tn3fX0jSO92XmIPfmtDgKzofy5XN9a9yf09oqs2l20QoJPI8RhILZUxI6nlSl9xzL0k4sGrk9JIemhZIzfWQGLF+slq/PnLDEoRy7G5XekCKjNhdra9rJEI9siPLR0n6Y80Lm2tQw7n3ZBX3/bIjmbt15P+MRPz2lpaEMuf4gadNFCMEe/BEJoS2fSZzC0LByXraRNSZrBnfKfKUzoy8hbnhXZIuPKWB1tduC6FcqssMhG0PNfEFPyPpYp2X/Ccj911F0gs6QjnExPa5nAVzheQ867t9bkI5U9KYmHhT5SOSwJf3qJH7dcRw35oL3TVEcMgx+bv5vBWhzD1+dBkSYRyz8P9ETiBkLy0IZQWI97vlpZKuaj5FW7xGi4ZXbWMbCAXTAxXdJvT8JX32nuTI47uTJ3UONd8Kqve5JHFPSbDdUQWxObOQEMTOg1MM7QNzhxTnU6ZnXNw19OfOq05tDinPJZmTUNjFPpTMMvvsN3cq+MskfSmlZdP/s6SwIv+18mlJ5xjAKF+LNgYJWMHUBCcyMjEJMa8IX16tC1MeyV3rbXhMCf4hD+8iF9c119P327r7IT2wtrLE+PE8oiM2aoJvgjR3zLwsmJTMI9YNeG9aGBPGIgsaziqbQbP32DShMNlYpPgysvA3rPvlwlsymPdPpo79ml2Vz73gX8Dvgh8my4+SxvHRARQJ28H+VmNiUZ6tp4ZiLkJB7f54qunI3f1NwgcS7hNsfha33XHBB5z6hIkJJpbYWfS0VdJuUNlfmLQf2yYbBBuBl6d1fq+bmQ9rnLJLjR/dQuuw6e6YcThI8Q/do5ujz0nXcC3EU2tqD0C+1ldEg5jbVvAvobVvTDZNKLCpneQ4+yiIYtEPCYNLck8WJvzxCoOMT+b25jrUWjSNGtBRHV/kOsFnqJVe5iIU+s47ZMGcuICkD1TMmDuktOx8KRocqe992OKIpu0skAL+rKEitENKgmipQcny9mSG+i6uQihLjR99RROzGtdX00YHJh+uwHvpS5ib1ryhsp25vVHZJKGgbXw7EUEG4U5uEfSBc/zkDbdmjI/B4y8hrGZVVrISbz0BcQbpzBWLZQ5CYWyY1Ccxz6cYzJsJfa/D/ZhDmIpZ7pKcrf4ezEieZaXv+AV/L5mv+E+yYE6iEWIeWZlKKEuOH/3EnLFzhc8e4o6amDB1Zr2UyA4+RyvnrdxoZu3YJgkF1RivtBUiGbXhYBJ42FGYuEwG/n6LaYxIBba/FdR6itJqBafcY91iwXZGPbYyB6EwQciitELIGBKuFd9/zEk0QC+YQ/cxHxIut1rH0PPA4x1pHBgL/j0uhd/tfVMJZcnxo5+eUNAGj5VC5LV4L3Ed/jG0yeyb4pmk6WOablw2SSgk8bADZCHlGLuwlTw42b65PbIPyWuZIuQd4JizggpMLoyVOQjlri7JaRV8cDJzXxZC4fgJfHo2/hiiZVkIR95qClAV104llCXHj+57QsGshNS3SfCRvC3lHuV+EcUjFb8vKLFo/zdJKBQ+2QpLNIx1Ki49cGgrNlrDoiFRa4pAFORwWOcmfg124LkJhcgUiV5ZcIDmwrrad2B8cSri68hC/cgHXQN+MWFWYV61lKmEsuT4lQgFzRQ/1LYIGj2RSes4RpOETGxJw0b7u0lC8SGv1gOI/8Cq7VP9J3lgKNLC1MjC+RP4euYmFJyd7EhZSLJDc5gq+DeOa266Sff3M83fTFBvwhGqfd3UB41cP5VQlhy/EqGgoa2Cd2PY9jRHdIyonY3AYb6yYda6CObo135tbpJQ/EJtHUPHxMEGzkJ+BYfYTBV8LmRpZiEj9KaukTlMHlKwbTh9ar/7rr+zS9bCwf0ddzFp4djpLWUqoSw5fiVC6YvotcRkrC3mFdqwNz/xrUH65E9tlWySUHDe2eQg4v4kP7US8gQObRqbUnhl+4B5QOJcFnIzSOqyMgeh+DBmK1we6BywJM5R/2OFJLihPJ1V+jKVUJYcvxKhzKGlTcGNPB/mmi9FIeP7RtviM/EvtE2EQpamddJOAb90rc98JDmJWp6pQpYqxXFZSunNcxAK5QQkdrUWb1qWCOXcKTu35bOnEsqS41ciFJIbKbDchJAq8HpnsuNQJ2+LDWFrZZOE4k0evPoU+7USclAIQ2dZtX2S4GyotRSim4NQqHq2OShMpqnFYzVYlkwedkVCwS1lKqEsOX7bRChohxyeZLV3yJVq560/g3eThOKdjq1j6YRLCZtmeWrhqL2aBYN/gUWX5RFd5IeQrpU5CIWUe1uTQ9boHWs6PPEazuXwtvgc/oOphLLk+G0LoZwvkYnNMfluOq7Cm6UTh3mZyzdJKD4sihMQZ2ArQWW0ZeecPXGRiY0TbsWWtxm5nP8JOc1NKD61es6zLrw/aw5taCqhLDl+20AonANEoqf1+xEQ4OyesVKUidN6vss3SSj4NDBDsuCExGdA6naNUPVqq0OpUrVFbKU6Icr/p5wMTtq9//W/Ukr6HBqKr+NBU5oj6gPWJEtZ5x+qtc2BGRsPUtZtSJOzWHzx3FRCWXL8Nk0olD7gq+Owrywk1l26y4WhGPT/jWySUEonVk1xBvqzIHw4l8xPX5E7NXpBmNn6LUhyw/vusxLnIBR2LLIgrUBwc/ywE+9oQ+rY7Exuf5RA38QmscpWdPNDVb6wciqhLDl+myQUNBLG1NZcUYwIwW+6onkykW2SUDgli13XpsPXHhCDKYLTzjquONyHKuQspfY51PeGlShBEiRXWcfo81yVc25qDkKhbZ/cRcgQ51ytgA9Vw4S+0UJQqX0SG20xmf1xEdSG4NcaE4508CHm0lGGnlBIuLPno/jnLDl+myQUMLZ5TawJNg5fXDk2Dlvx/SYJBQD8zoi5Q/bfWITBaw4wOREdrx769in4IqfkYxXo+/J/biF87LUGPp+LUPhZSv9bKxTN4V8YE/w+aHGcdpaFcgf7t22DZClbu4LdzsQeOoGd+QNRWd/U+zviwrnohUxPW+lNaj3+gSFZavw2RSheC0PzZY7NoYWOzZcm32+aUEj75pAYzjLJwg7KzlVK/WaRsNCJtNi+k1+CT8YLfhZSlDkHJAvqOYuyj1Rol/R0HK/WGcuvs12zB/W5CIUDluinzdTlkOgbp8ON+iYBPg12PnuAMeea4P/pq7bmO1Rte14thZEcdmULDPMzGTu0Dn/kIPVSpcOffEUzfhZ8QvjO+mSp8dsEoTDP8M9xvGeW1uUnTUhiSiObJhT6Cktzwrw/eBk1mnj89xJ5UJdD8eCJ3QuSJ4K/oc/ex1fDbmidhmgq1MZQkEg+DL4RfAbsyFcvHFTDkQEcfdCX6jwXofCqHN7NQrehRD4nrEwmJYSJeowZSM0R2gGZvCxGKzWJg14j4H4OpeK4STQYku1whIMTZOWPgBwK/ePkJVJlBVyflYrbcJjzLP8zEkuM3yYIhbmMxmiFv9dNp4eUfIX8FE5Y69ptIBRegEOg8Z9MPUSaxcQp35z0NiTsmgyWDcnVAgdh4W3HZ9MncxIKz2QXg1ztb7DU9p/rWKSUHtQI1/o8m5r7cMKiWdpDqu19HKfJ5jB0FmtfaH/u8dsEofCrDa2PiOA9MCPtuUA1Y9fsmm0hFF4IDYDkLXsMYd+LspNRCcoiqf2JCJLcMJX8TyL0PQOVHP8F9UVjP+84N6HQRwodOS4Tp7I9TmFoMkC4nNI2dYKhffDeXhssPQuTBXOzxoGL/4aNo+9nQIZyheYcvyCURpSyTYSSXwmnKRpB/qEvclPoJ2o9qhxRC6I5q5Zt44+gfRyJ+FYwddg9WRhoOvgYcArj+Byy7+0QLEEo+Xlk7UKKhBUxA+k/pkfOwyFlH3MIjQYzZUrejX0nTER2O/7hKCQsjG+G59gf+sK31PdDX6VpSmoAJMc4E4KHrDmPBV8aJ+zZSF3p/jnGLwhlhwml0atFM4FAILA0AtuooSyNQTwvEAgEGiEQhNIIyGgmEAgE9s3lCDwCgUAgEFgLgdBQ1oIvbg4EAgGLQBBKzIdAIBBohkAQSjMoo6FAIBAIQok5EAgEAs0QCEJpBmU0FAgEAkEoMQcCgUCgGQJBKM2gjIYCgUAgCCXmQCAQCDRDIAilGZTRUCAQCAShxBwIBAKBZggEoTSDMhoKBAKBIJSYA4FAINAMgSCUZlBGQ4FAIBCEEnMgEAgEmiEQhNIMymgoEAgEglBiDgQCgUAzBIJQmkEZDQUCgUAQSsyBQCAQaIZAEEozKKOhQCAQCEKJORAIBALNEAhCaQblAb6h86cfZwOI1wz8KPsBHqiGAPBDdTdI7fEDdeC+UQlC2Sj8O/Vwfrj9P9MbMcnHfgFwp15+Qy9zS0lPTs9+rqTrb6gfex8bhLLpEdid5/+fpOMGoSw6oM+XdO0glEUxj4ctgABEAqFkCQ1lAdAlfUPSiYJQlgE7nrIcAleV9NIglOUATz9e/2PzxDB5FoU/HjYnAo+VdLsglDkh3q/tyzsn7E4TCmoYL3xxSSdObHpISb9MatqHus+x/z674hCgYl9G0oUlnVrSUSQdSdLvJf1c0ve6iMN7Jb2ju+b9E55Bv85prj+bpI+bv8+dbNZzdU7HE0g6jKTfSmKn+KikV0l6naR/TnhmvvRgki7RtXPJ1IdjpPf6k6SfSvpk9/lbJb1E0h9WaP9YaUyIxoAZfx9O//452l9J+lF6xrskvUISzx2SD0gCj1phfHjOkIA373+h5I85mqSDp/f/STefPpwweJukP1c++GLpnnz5m7oxvbS59wiSrifpUt17n0bSUdP4MVe/Iuk9kp4h6QeVz7OXHUTSeTtcL9st/jNIOqkknse8Ya6Cx5e7Z39M0oslfXHkGQ+SdM8J/bhiReTniGktsVbpI5gfOc3rn6X1+nZJb5D0tbFnt3bKMhgP6MC/qSTAHJM3d4vxFl3o6ztjF6bvjy7pPpJukiZazW0M1t0lsVDGhAXLBMzCxH53WtjPknS5sQa6wflER5RXcj6Fsdto95GSTjZ2YSLlu6VJXkNcLOSHdP25kSRIq0Z+0ZHWXST9z8DFLQnlrJIebsLOY338dlpYLxq7MJEzG0WW93VjCqkimGpPS5vRUFOQ11276x5f8bx8CRseY3qKCfdAdqyd7/fc05JQ2ODvkMYZkhuTfyQlAELr69+e3amVoJWgEZxwYoPsBOwOHxm571SS3tJN8uNNbJ/LAQPwxibE6xNb20nBZGQSsnvVyrcknT6x/Ng99+t2xPuOXVT4Hg0P5+ffB+5Fi2J3OckK7XPLkzqN77967m1FKGgHz5R00BX6CBncKo1v3+1nTiSfv4fwITA2pacnDa320WABJmNyr25DfeDYRT3foxWcJ2lH/pJWhIJGj8ZxjhX6iKbIpvuZ0r2tCAU1icSaY7uHoKKihWCC/DWRAWr9+dx1v0nqFguxJMdP7bPbWoGEcAZ+OqnFh5VEsg8Edc2CFnOzro//PQDiq7vnXMF8f5W0aLOKjPlD8hDedVRWNDLUdEJ3mA9WHi3pTiMDBtszSaygHby204Y+lcw32j2jpKsVdtInSrpNzzMwFTDDUGOtMBFemdRryPzAyfxBNb+GJDC0cuMeTQW1mGcgmJWWtPCnWCct12AWeo0KQkTzs/KXLnLxvA5Xdms0EeYN5hmLDC3rOO568jBuPYAzxM7czPL5pAWwSUBizD3w+KAkFgvvhJnOPLDmL/f/Mc0vTNA+8Q7qfB95OpAw0TDMycN3GJ0yaUmQnhXmF2apN+sYmzw+aHTXNTfR/m1dO4yvbwNzC62dDdoK7gdwZ87gNqB/aFfggPvCcgWmGqT8dQ9CK0J5uSQWX5ZfpwXNpCgJKj6+gEOZL7FVL1i4mD6i+WB+ZPmbJMjBT0Z7O2CgcdiJ/rtu8pw2TdRSv/CBYHdmeWOyt/FZ3LCwSPJ1J+9s5Xe6yc6gQLAskJJAEgyeNUOYFDdPZo2/B1v3hYks7XdgBnZeUJ3Zga1gLkJgfaYSZIzZx/tk+WEKTQ75VPAD2HtqwsaMCwudCZ4FHwJzgwVVEtR0NASIxUo2TUv3nM7tppAUmwELlvGlLRstsW1gsvhNgb/ZLErCWOJnAMcs30y+Pp7bJ5iXEIQVSHlIo0Y7Yw1kqXXK+vuYC7gEeFc0+ZLgK2Nt4HLIwpwD933mUgtCwR71E/oiaYENYLgnq+/Z7gI6bu1dvmaCsWNbIUPwqUONp+/YaT7niItFxqItCc7IK7svABkVD8IYElR3nx2KSglplATfzAXcAF1UEmTZJywotDFrl2PSWL9Pvpfnoj1lQVvEmTwm7DzsYFZwlGJu9skqhMKYWp8UdjnaFCr/mPh7GWOIoySYqnzvhU0KTRYNqE/QYCA5nKlZwAE8SsLnfhPF2YkTeUwgN/qThfEbMklWIZQzJce77cs9JD10rHNpLqFh2Q2QtQLR7JUWhMKuiXmRBdsMr/aY8OyvOg3iCQW1jfasVx6VFTW2j039cx/V+TLuaD5Ee0KFRn31UiKUpyQ7fex9DpE0C6t1QVxeS6AdJijvboWFjH0/JphX+E+ygAM7BxpRFhziDDQaEt9hkrILjfmQ8v0sItTxLA9L9/f1bSqhsIOzc2NuZcGRjclZI/jRuN/6XXxELrdTIhTMAMbAJuP1PRet7v7mS6JhzJ+SYJYSZMiYM8fBvsZ57k0lfGOYHX0RvVUIBSc7mnYWNETMrdq1xFxG883iI2ZrO2VZPNhpLKYs2OGYMzWCDwFWZjGwM7H74hfIgs8Ee9VGjG4v6XE1jadr2PVo1wo7I+aQlxKhEHkZDZelhgjtsgtkweFqJ2P+nM+YqFkIT9ZGA/BdsLuCWf4HHmN9ZHLXTGz6RPSEccyCbY0G1idTCeXeKRqY24McMIFq+8d9+LKw7bP0+ZNKhMImmFPWB15rz1dsjqQCZGHxQWQ1fZ2COfOMeWCFQEefX3EqoZQ2PKwETKVa8WsJ0oNc9/qU1tVQcFp5EwV2HnJa1Xae6zABvLqIre5397E2sZGt/de30D2h4HSy6u7Yc7w29RinHeX7fXi6Vgsae36r7/FTED3JAvkOhcynEgqOepzzWVZ5fzQB7suCw9yaePnzEqFAJpBKjZzF5SJxD5oD+UctBQe/XzdoDzjnSzKVUM7uIqkQ4jGTI7r2PeALfGrkSGXBethr5q1LKITRMFOyoK2wg7YS8i2sfYeZghOvZnewfSDJzUaWsMFtNCdf6wkFZzOqaK3Yilvu6YtAoI0RusuCd97iWPu8ua5D47ERA+x78ir6ZCqhoFnZeUIIl9DxFPGbGU5jImLeB1UiFByyY0lkuS9EQ77gOoYZU+PrmfI+ON1ZP1aGzOCphEI00Jq8+KxyMeeUfvrNkBD5g3MD6xIKOzAmSBZMC6vyT+lo6Vocr9aBysBOyQfJbRINyudG8BmmCTuPF08oDBo7Ya1g6mFHZykRCrsbfhwrqO5Wra59Xu11qOhoezhliXIRhmfx8a+U/wFp4wDO0pJQSKLyGbOYvl7THXs3CJnxsoI26UOZJUJhZ+6L7PjnYop+yX1YSyj4iiBiHMYQEyY8mB+6kP/CWvSbcUtC8eURmMjWHzKGd/4ef6TdXPYxH9clFL9QbRZibQeHrvO2PF5m8iWmit9xAbOUleoJpSaXxPalhlBYzD4zeCjsOfVd7fXkVNw51dmgUq8qLQmFRTYUQl21j9xXWoAlQmFRk0JQI6sQCr4GNluieOussZaEQkR1jvNS9pkb67wsg0FCEN75LEMhtZrB89f4UBrqlrW9a9tEJSM8loUEJmsH5s+XIBQ0BF/DNBRern1Hf1123pLvsq60JBSfF7Ju3+z91Hb5EoulCQXzDd/OKpm/HouWhOJzrFrhTlLjXndCa0Lpy4lYtfPeyYmDlrj+VKGWhbBplr7Q36YIpZR/M/Ud7fWEYxlon3eCqYEZR04NWhpOQHwPPmw4pw+l5JNY513tvSXTcUlCIWKJA9uGw+kfJPeC5GAlaxyHrk94nNuH4v17rTDfx82xLqF4k4f0ZVKkW4nPcVm1fZxRNkW9L0y7BKGUTB78G4SCW0kpaRDtjlCwd/yVnjknoZA6z6KyQnIk5vIcshShoJHga7GZ2eS7gHlNfs3chELFNGUUWUistNnnTbBfl1C8o2dKPkXNC6A6WqcoA+ZrEGraIdZu6x7IBCWM5mUJQik5Jafk7tS8L9qJJXZS2TG1Ssl8pfa8M7ylyYPD1/sv+vKCat517JqlCAVzy28KY7Vjtu+Y4GjOVlqaPL6MgHC0ryEaw3L0+3UJxYeiSGMm2W2oAna0U+YCPMpkumZBTcRDPrV9f84J6p+NxuT2lyAUnuXDplQbc+xDCwF/VGqbDEilNeRfKz5PpCWh0AfOFrHZpswjm9BY28+a65YiFG9WY04Slu2r5fJ993kifN+SUHxtF3NwHUd9Eft1CQUbHTPECh7uYmlzoQdk79kKYvJLbDivVCfETkv6fa2wsMgZQKXMQuTDEtXShIIvCDMnC1mftihx7N0ImdqaCgiEgjeE7EpfXIfTrPagKQiJMbDV060Jxdfi1Ba2jeFS+n4pQiGb+DqmA/hN0FpqpXTkQUtCwTnvk+Q4aqRpxG1dQiml3pNTAFvXiM929OFcSrVh0lwmT5sku/nKzKFnEWb29jmfEYL2spSGgjZC+nkWTAB2i9pTyHzm77VSujzt+XJ9PptSPoCajuPWSmtC4bAi6oOyjFVm18ylvmuWIhR/9AUpD4xLjbA5kD+Df81KS0LBx8PRGHajwAIgvN1M1iUUOsLRdVc3PSLHgglco+qRsmsrN0s7Fedq2GxVSIfCtVqzx8ffYWSqkEsFUUsRCuUDZJda6Ssk9INNermvYLY1Hxyq5Os/UKd9BXFpElF0h9feZvFy3Vj0zmfKciTA0NESOGaZJ9Ys6zt3pW+yU2HNxoW2h8MZs7ZUObwUoVBpbuudMBtt9fDQon1Eyhfy1wxF/3ymLAWj1k9Yep6/p+/claG+EnlFGwZ3/u1TYNmCUPAU+9J+TquyxW+lDmLO4Gm2fSjlEZTar2VWGJ6yfTtxCR/b3dH2bSlC4ZloTTZJD4ccTrKhs0vBikHkeIgs++QBpPwHwsP2nJEarZEMXvKISGmnL2STZhnLgOZ4AJvBXKNF+rwItBTev+Y4UHJsOFzL1ln1naa2FKH4MhGyoan2Hjv/l82ShEiuJzvZZigPZVDjc7IHS9XkgJW01ynJm77UhroeEhX3EnkLQmHSeZuYz1DpqcMpaRLkkqDZWP8JO0zfocd+8tEmTqahXZC2UENJk86CWomPJ/sbPNEtSSglsqO0gAlWqjNhwbPD2Cpg+k+iHzu0FZ+/g6pLqUFf5SrJZrw7C5TKXzYEe1YNEwYcfclAfqavlcKcxG8zVHOFlkj5vD0hDu2RXx8cOsYBgmDuWAL7btJaS4t3KUIpFRHiCMchXhLMHIpU2eBYh5ialLHYqnMiMxy+VBJfsY4fDe2UsR4SH8HjWvyJrNe+Q7ToK2YqprrlDAgt/3Lhnme2IhQ89kwOW9FL+0xgsmkxU+gsNiImjk+44hg+VHlfvp2BIaSGQ8kfMcnuTMIQTlryKyAozAmYnVCkfT9MMDSCIdV/SULh3bwvhc9YvKjLaDBk9KJpsHNzmI0/ArPvsCh/0jvtEnVAM8N8YdLhpIZIyHTGIYwWB0Zojvh0/KFE+FGYxGg/LFx7ULHP8+F5jA31SZA34w7uPh+jlC+DKUpyGP8gNxYKdj8LDfKkjsQmjoEX71s6tY5+LEUoPMtHE/mMzZZFjFnIfAQLMOZcEggAASeKVSlGtQd8EebHzwhBk25gnaqM2T6HGyUHK5ssPjbWDNh4bZwoKZXZPv0CUsbvwztwPxiz3liXuDTsKXT0GU2Z8Wh+Ylte9CxkJuvUQ6SZoJDM2CHVeKRpn51tqrCAGLCxSMfShMJ7MOCw/1Rh8LGZ+3xJU2s3mHw4EZnUTHwWc57wvm8+SlYKefp72AHDJUgqAAADRklEQVT9+blcwztQaVx7Ir9tF2Kjz0M/Er4kobBIIU5rbo6NK3OSIwAgzhLB5vshZqvNERAhQXCouh9XhDWPc1v4yCBsf2buWF/z9+TbsJ720/RbaShWk6BuBmBqfkYDuw/TpebkLJ4BePhmYG0b+ekDgt0O9ZiQXE14bBOEQt/ZlYhc1ZAl5EhdUukkOIsDC5RzTWoqStEgqca2KQDsSmBXklLYvaSl2Hv7CIVr0MAg1tLk7xtbtDjOXR07G2dJQqGv1GWhlXtt2r8HxyyQuInvJSccMqfRHkrHWXpCoT3Occb/0rfW+giFe/HVgB8mldd8+zBHY8YRjv+meMpba0LJHSH9GLMDVZRFgv2dQ8zsfKhwpNXb08hr2ZHriBJg0tA+ER9CrqiEmE7knDDJABMW7jvwuPS8TREKfYEA0NTyD31hPrKTEEq2P/TFIh9z9Nl3I/+ACAo+DRKtMB+4HxLHV4FKzr+SpsMYcigzfif6h7OWCBO2fcnPQZSD4jgWBBMWnwv3MM4QYClUb/sKsfD+HLyNis28Ybenv0xmzAZID9PJR8n65s/ShEI/mOsQNOYZjlA2QkwINgP6TY4KUZnSJseYY1oyv3GMo7mwZjA58bl4wVcIKeBGwIzFXGUN4AZgXP05x/5+fHNoSORFgT+Y0wdMGdYTbgvyyvDT0YfBH4Cbi1CmkENcGwgEAjuCQBDKjgxkvEYgsA0IBKFswyhEHwKBHUEgCGVHBjJeIxDYBgSCULZhFKIPgcCOIBCEsiMDGa8RCGwDAkEo2zAK0YdAYEcQCELZkYGM1wgEtgGBIJRtGIXoQyCwIwgEoezIQMZrBALbgEAQyjaMQvQhENgRBIJQdmQg4zUCgW1AIAhlG0Yh+hAI7AgCQSg7MpDxGoHANiAQhLINoxB9CAR2BIEglB0ZyHiNQGAbEAhC2YZRiD4EAjuCQBDKjgxkvEYgsA0IBKFswyhEHwKBHUEgCGVHBjJeIxDYBgSCULZhFKIPgcCOIBCEsiMDGa8RCGwDAkEo2zAK0YdAYEcQCELZkYGM1wgEtgGBIJRtGIXoQyCwIwgEoezIQMZrBALbgEAQyjaMQvQhENgRBIJQdmQg4zUCgW1A4F97zin53c1O/QAAAABJRU5ErkJggg==" />
@@ -1513,7 +1522,7 @@
- + @@ -1525,18 +1534,21 @@ >
-
group 1 created.
+
+ collector + 1 created. +
timer start
@@ -1556,7 +1568,10 @@ >
-
group 1
+
+ collector + 1 +
concatenate
@@ -1567,7 +1582,7 @@ y="927" width="69" height="32" - xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAARQAAACACAYAAADK8JaYAAAAAXNSR0IArs4c6QAAIABJREFUeF7tnQe0PTtVxj8QQYr0JkgVERSkNxGkSK+CCIggIiC9g3SkPHrvSFOkSRGlSZEiqDQB6dKLSgdBmgqC87sruWvf/TKTzLlz5s45Z++1/gvePZlMZif5snuOo6DgQHAgODARB44zUT/RTXAgOBAcUABKLILgQHBgMg4EoEzGyugoOBAcCECJNRAcCA5MxoEAlMlYGR0FB4IDASixBoIDwYHJOBCAMhkro6PgQHAgACXWQHAgODAZBwJQJmNldBQcCA4EoMQaCA4EBybjQADKZKyMjnaAAzeW9CRJJzPf+luS/noHvr3pEwNQmtgUjXacA6eW9AxJ1ynwIQDFMCUAZcd3Snx+lQPXkPRMSafraRmAEoBSXUTRIDjws5IeL+lmFVYEoASgxG4JDgxy4Dck/Vn376ym1f9Iurek+0g6ZdhQyvwLlSd2VnDgIAeuIuk10oFM/I9K+l1JH5D09c4we6oAlACU2DjBgRYO3FTSc03Dp0q6m6QfpL8FoAxwcdcllF+TdF1Jl+2s+D+XTp7vS/qkpDdLelb6/5mF9+9Orgcafj5R0h0L/D2JpO+Yv3+708dPnv77pyTdShIuyF+WhK5uf++bruNKurykK0i6lKTTS8L78NOSvinpG5LeL+ktkl4t6Wstu0eS30CflnSOxmdpdgNJLzLtP+9UBdvVZ91v8P8dqcHxJd1Q0jU7N+z50/fxbXzHv0t6g6S/lPThEWNbpWnmB+/9gySt2H4CUAJQjsWBM3Sb8cmdCItBbYh+lAxz6M4/lPSEbvPewTzw0KRT+z4ADZ7NxLNsGP5OzMLV3QM1QLl2BxzHJABq2STfS9/H+P6r8sCcgPJBSec147mapNdKulgCpbNVxvrjDmieLukekvjGdRD8uH4C2q8UXhCAEoBygAOc7G8feQqjU7Op/zSdWrnDB0h6UA9/AZHjmd/4/3eS9OhC+z5AQYJ8RLd57r7izvmQJGwC/zHw/JyA8p5OerqwGcvvdF6UL3QS15sknXjENyI9Akb/PeKZ1qZIfUh7P+l5IAAlAGWfA2zQf5J0cccTFvWzO3XiH5OIjRX/cpJundQKmj9cEicop1cmLP5IASX6rtskANlHnEGPxYkqw7is5yD395hOwriL6xxV6gVJBfi3pNufNp3yN5J0Htf+U5LO153qqHIlmhNQUG8s72+bpI2zpA2MWvN6SZ9JEh5q6JUSmFtw5jue0hlIb9eKEhO2C0AJQNnnAHaL5zl+vFLS7zmbR26CNf/Fkn4zqTwfdxv2XgloSixG6jip+eGeqS0bGxUKtyRtIE5nL8JfJtlxrJ3rH5LNok/iQKW6X7c5kZwsod7dfgGAAphfwowDewtgwibFlvW2njFeJNmFAM5M/5eAEpCekwJQAlD2OfAvaRHmP3xC0gUGTm/a/UwHKGzkCxX4OAQoGEpPYZ7hXcQ1ABTZEDm0Ed6XxpbbYChmY2UQGnqWMPFbus3Hxi0B0ZwSCny8pBs4dhHiPvhtiC7dGc//fgRQrgtkAlACUPY48AudJIL4b+n3CxJLiV2oDGxw1BNLQ4DiFx7P9Rlx/TuxM2BvsHS9Tjp6WeMu4ST/XGd/OaFp36eeHTWg/EWn4tyk8bv+VtKVTdsvdWHxZxywdzR2O6pZAEoAyh4H0LfJFM2E0RS7BbaOFnpVwTszBlAQ0bEJtLhzH9tJInc2g0LaASToo5XwJl3LNAYQS1LWUQOKdR3Xvg037nNcI2xGc6o9ASgBKHscwN34R4YX6PNe/B5a0DdPSWK2zRhAQaQnfqSFMA6z0TIR50Gk5hi6TTJc5mf+N8W88L+WjhJQAMrTSELtaSFURmJZLOEpemnLwxO1CUAZYOQuBbZh8LMbmmjIWuKXZd3Zu2A0gr4sjQGUxxU8NqWpwbBK7MiJzI9D7+mbXoL1cK9awl6EHWkpgIK7GIN3K7FeiVg9gXmAYMMHt3YwQbsAlACUPQ4ABoBCplUWoje0jgEUXKSEcdeINPkvu0Zj7Cf50TN3MTN4USyRik8U7VIAhbgeKzXWeMPvGKdtJC9qrA02bOnjMG0CUAJQ9jhA1KN1OxIyT+j8GMJT84vmgTGAQlg5LuganbMLQcc9bYlTnNN8DBHq/5/uAeJUXrggQEGyANjHkPd+4X7HtjIXBaAEoOxxgDgPq0bgVqVwzhjygVljAAUDKTEvNcI1/G7XiNiNd9YedL+TB+PtJdhVnrYgQFlFlfOuZzxfSHBzUQBKAMoeBwjTtro3RlaiY8eQX8xjAKWkbpTeXXIZj/GE5D7JHaKGhyWSEolRsXSURtk/7kD+kWMmIEUzW4M1CYMkKM5FASgBKHscID/DhrcTOUoE6Rj6WKe2nMs8sA5AQaVCtbJEhvHfjRloCqrD5mOppHYdJaCQuf0nI7/LqzxkhN9iZB+HaR6AEoCyxwHydc7UCAZ9LPtqcnPm39cBKNh5fJYr+UMvGbkLyDsiJ8bSVbucH4LDLB0WULw7fah8gZfwWj1fdrzeKEuZRhuzM5JNo5sHoASg7HHAn2x4XPC8tBJBaV90jdcBKLhGv+XygMjPeUjrQFO7K6ZEO/sY9VeQsoYABRAiqriVUFtInMw0BlD+JiX+tb6r5Da+a8crAgHnogCUAJQ9DuBhsZnCZLXaMO7agiSBkDBxS+sAFPqnSBI5P5le3hUW+u3aAN3vbDRbKoEsZTw/PogMNch6fghnp15MK3m+jgEUUiGs16z2zpIrnPIMr6s9OOHvASgBKHscQFe3Wbgk2ZFN3BrOjsrhvQnrAhRyfug7E4Fu1OkgXaCVcDNTgiFTXxAZxZ5IK8hEYShygGyBqL53YvilmhrRrpnGAArPIA151azvfSVQ//lKvZdWfrW2C0AJQNnjAJvLx3JQUtFHk5bYhSGW0oNEsVpaF6CcWxKFkS21JjLmTfqvrsATUcG2Vmruu+Sm/tWunADFmWpEn95TNhZQKFDlyy30vRdJzV62RQU4EjfnpACUAJQ9DlCgB6OqLSmA5wRbQ191Lp7jFH6rq+ORWbouQKF/nyrARr1gqh87tIGwM7zCJQZik0GNyYWW7fNII6hDFiyxSaAyDRHlELBL+cJQYwGFd1MW0kf1+ncDctTMtRnfQxXz1gUyASgBKPsc8Fm8/PCopF6UVB9sDtgX0NNZSCx6m7G7TkABPN7lpAwSGlG7vHE4fyCBe3g9vBuV8HbC3PvIgxfxK8TNvLHngYumhDxsGpTHpBxjpjGAQuY16hKRwRSn9u7y3CceK8Dfpk6gBhKC35K9PSW4BKAEoOxzAJsJOT32smt+5OQjLZ4Tl3B12qEOUQIyX0GJ/k6IN3+fQ0LhHfctJL4hbfx58uBQMAmJhPKSFClijNY1Th+UMagV4y5VssOGQhQqBmIMtUh42CswZAOwvBejKn1b9YiylABNibzbGLsWeThIOYAYpS0pWg0oIU0hVfE+opq5ScDSKkFxNWBB/avlFsFjGyAJ0A1JV8TJjI1yro1zsb/vUrZxngRUHIyQqDKthMsW1y2LZ05AYXz+6o7WMdOODYqdw4fg+z5YB3ybNeLW3kOgIJ4oTmwAJ9OQl8gDCvEjuLFJSRgzH3jbsCkNqaq18Zd+91eCrNKHfwawfv4UHW1CH7sIKMwLoEAeT+3aBiJNKRKNRAAdBaDwXiQCqt/bKyiG1hfV2jB2loywfc9xPxD1dqnuXyNKIOBuxvCLtIfUlAmgwSNVIg8oOYaE8o7w2F79WXoeYCTmhaTCFi9U7Tv87wEoYznm2u8qoMAGjJHEpbCB2KioNiTUsSHwHpDmzwaz99pgnEW1yATYEO1ZIq9rt+by9E0pxkgkCFQA6roQaJc3LmMmuhYbC3YP4jLGuJjtO8mTQaznf1FxAAz6wj383qQGYfTN8SyoQvZdqC7U4W0BFG7ko7I/hIRCsSSSKKnbgrpD39hIUClQhbBntbqYV9kaASircM08s8uAsgrrsLVwq10mbCqkzwe1ccBLKNw3VLqnqK23aLU4DgSgjJsSX2AJz4QNChvX2+61DkDZ8jkPQGmfYFyUJKZZwqOCKhDUxoEAlDY+bWyrXQMUPB7EkVAVjX8kCGLsbCEfug+QeBdtSz+73CYAZctnf9cABTeqrR5PHAcZuLULxQEOrmrAE5LpYekGwC1fIpN+XgDKpOxcXme7Bih4LriiwhK30WHd94Whc5tfSnYSmxVL9TeS2voiVpc308sYUQDKMuZhbaPYNUCBkXhlCIqyhKuTUoKADZGehOHjMqU4NGUDcCdbqoWyr23CNrzjAJQNn8Da8HcRUIiRIBz9SjXm9Px+TAqJX/HxnX4sAGXLp38XAYUpJbP2nl2+CPkg1i4yNN1EhfIMVcaCVuNAAMpqfNuYp3YVUPIEkU1Mchv5PaTHE30KwBDiTZIgnhyiTwm5pxbr1LkjG7NQJhpoAMpEjFxqN7sOKEudlxhXcGAjORCAspHTFoMODiyTAwEoy5yXGFVwYCM5EICykdMWgw4OLJMDASjLnJcYVXBgIzkQgLKR0xaDDg4skwMBKMuclxhVcGAjORCAspHTFoMODiyTAwEoy5yXGFVwYCM5EICykdMWgw4OLJMDASjLnJcYVXBgIzkQgLKR0xaDDg4skwMBKMuclxhVcGAjORCAspHTFoMODiyTAwEoy5yXTRwVF6BdNg2cAlbcLhi0Xg6cJd23zVvgN3w/UgpAOVL2b9XLX9IV8r5e+qK4AG2eqb2NpKekV3GV603neW3/WwJQjnoGtuf91OKlDi8UgDLPvHJpPNfGQgEo8/A83jIDBwASACVTAMoMTJf06e7+7bMHoMzD7HjLfBzgknNuDQhAmY/np5X0FfO6kFDm4328ac0ceJykOwWgrJnLB7u/ljPCbjWgIIbxwVxVwYVYoCnXV1D4GTGNws/ofx9ccQoQsa8u6fKSfkXSqSSdQtL3JH0jFZfmAi+KS799xDsY1yVM+4tKeo/570smnZULw84q6cSSvpNOind1ha7/StIrVyxmzd0/V5Z0lTSG06Xv4lKxr0l6b/f310t6saTvj/im3JQC3MwJ3hh4lgtyY0f7VrrojHe8WdLLugr/vHeIfMHp2pCYH94zRPCb779cssecRtLx0/d/tVtP70g8eIMk7lJqIQqQw7dMr+3m9Grmv0+W7mm6avfd55F06jR/rNWPS3qrpGeueKkbtytcqpu7a3Sb//ySuCyO97FuWKvwg9sU3i3pRZI+Wvmgh0i6T8tHpzYUYK95fijUzl5irzJGeH7KtK6/nvbrGyW9unC397GGMrVRlsl4UMf8W6arKmrfTiX5W3dGvM/XGqbfAab7S7pFWmgtjzFZ90obpdaehccCzMTCfkva2M+RdM1aB93k/HMHlNdxNoXaY/T7qHTfcq0tC53rPFjkLVX42cgP7cbzh4ULy/re9c0OtO7R3d387IHBTAkoF0l3TGe3c40Hn0sb64W1hgmcOSgyvS2BKv+Nqvb0dBgNdQV4ceXKExrel5uwSZnTc414BrBj73BFbommBBQO+LukeQbkavTjJAQAaH3j05SAglSCRHC22sjc72wQTod3Vp7jDuLXrXhBOcyAebUF8aqE1nZRsBhZhJxerfRZSedLKF97xl/CXmuff0fCw/jJLYd9hBTF6XKO1k5duyd3Et/te56dClC4xfFZko63whgBg9t2hwzz20cXSiCffwfwATAOpWdIo/YAvIAnNbpvd6A+uNao53ekgl9P0pFvMhWgINEjcVx8hTEiKXLofqD07FSAgphEYM0Z3EsQUZFCuN/mhwkMEOsv7dpxWTniFhuxRGdO/XPaWgKEMAa+P4nFJ5FEsA8AxaXoiMuWaleIvqJ7z7XNA1xDyqbNIjLqDyIkahsiKxIZYjquO39h2GMk3a0yYaA9i8QS0gGXib0vqW/0ewFJ1y+cpE+SdIeed/DtqGHw1RIL4eVJvAbMj5vUH0TzG0qCh5Zu3iOpIBZn/qJWWtDCnmKNtPSHAdFLVPAWyc8SdyI9r+MrpzWSCOsG9YxNhpR1RteeOIzbDfAZYLdBdh9OUgCHBCDG2oMfXEPLZuGbUNNZB1b95RU/SOsLFbSPvIE6P0ecDiCMNwx18qQdj86dpCRAzxLrC7XUq3XMTZ6fR0i6iXmI/u/o+mF+fR+oW0jtHNCWMD/Ad9YMZgPGh3QFH1CVLVagqgHKn/JMmApQXpruAM79fzttaBZFiRDxsQWc0PyIrloSeRkjkg/qR6YfSQIc/GK074IZSBx2oX+3WzznTQu1NC5sIOidmV6TwASbxc0KmyS340L1N7nFzqQAsGyQEgESTJ69N5lFcatka/LPoOu+IIGl/Q2ewTtPiM6cwJZQFwGwPlUJMEbt43syfSm5JodsKtgB7DMtbmPmhY3OAs+EDYG1wYYqEWI6EgLAYimrpqVnuMDNnqaAFIcBG5b5pS/rLbF9oLL4Q4H/5rAoEXP5yQQ6+ffPJFsf7+0j1EsAwhKgPCRRI52xBzK1GmX9c6wFTAJ8a5+kh+2QvYHJIRNrDr4fWEtTAApGPr+guWScDTZERPU91zVg4Fbf5WcWmL/+kwjBp1X652dOmg854GKTsWlLhDHyuu4HmIyIV/seRHcuYreESAlolAjbzGXcBF2huzcZsOwjNhTSmNXLUWms3Sc/y3uRnjIhLWJMrhEnDyeYJQylqJt9tAqgMKfWJoVejjSFyF8j/yxzDHCUCFWV3z1xSCHJIgH1ERIMIIcxNRN8gB8l4u/+EMXYiRG5RoAb48nE/A2pJKsAygWTcd+O5d6SHlYbXFpLSFj2AGSvADT7NAWgcGqiXmRCN8OqXSPe/QknQTyxILbRn7XKI7Iixg7pzfbdj+5sGXc1f0B6QoRGfPVUApSnJj299j0nSJKFlboALi8l0A8LlG+3xEZGv68R6hX2k0zwgZMDiSgT3gUmGgmJ31BJOYVqNqT8PJsIcTzTw9PzfWMbCyhIQpzcqFuZMGSjcrbQmdLz1u7iPXK5nxKgoAYwBzYYr++9SHUPND9+Oa2fUnvUUpwMmeescXjfYjz3qhK2MdSOPo/eKoCCkR1JOxMSIupW615iLSP5ZvIes1EGqRID2TzoaWymTOjhqDMthA0BVGYzcDJx+mIXyITNBH2VDZLpzpIe39J5asOpR7+WOBlRhzyVAOWcLe6y1BFuV06BTBhc7WLMf+dvLNRMuCdbvQHYLjhd4Vn+Bz8QtYeIxd2ysOkD7wnzmAndGgmsj8YCyv2SNzD3B7igArWOj+ewZaHbZ+qzJ5UAhUMwh6xX2LZ3OBIKkInNB5C1jHUMz1lnrANLODr67IpjAaV04KEloCq1kt9LgB6H875N6bASCkYrr6KAzkNGq9bB0w4VwIuL6Or+dK/1iY5s9b++je4BBaOTFXdr7/HS1GOddJSf9+7pVimo9v6pfsdOgfckE+A75DIfCygY6jHOZ1rl+5EEeC4TBnOr4uW/lwAFMAFUWujCLhaJZ5AciD+akjDw+32D9IBxvkRjAeVizpMKIJ4+GaJbvwO8wKZGjFQmtId9Ne+wgIIbDTUlE9IKJ+hURLyF1e9QUzDitZwOdgwEuVnPEjq49ebkth5QMDYjiraSzbjlmT4PBNIYrrtMWOctH1vft652SDzWY4B+T1xFH40FFCQru05w4eI6HkP+MMNojEfM26BKgIJBthZElseCN+QjbmCoMS22njHfg9Gd/WNpSA0eCyh4A63Ki80qJ3OOGac/DHGRH5M7OCygcAKjgmRCtbAi/5iBltpieLUGVCZ2TDxI7hNvEJ6HTKgmnDyePKAwaZyErYSqhx6dqQQonG7YcSwhuluxuvV9re0Q0ZH2MMri5cINz+bjXyn+A9DGAJxpSkAhiMpHzKL6ekm39m0AMvNlCWnSuzJLgMLJ3OfZ8e9FFf2Y+2MroGArAogxGANMqPDw/ESF+Bf2oj+MpwQUnx6BimztITV+59+xR9rD5YD6eFhA8RvVRiG2DnCondflsTITLzGW/IkLM9FZPXlAaYklsX20AAqb2UcGD7k9x36rbU9Mxd1Tng0i9ao0JaCwyYZcqKuOkedKG7AEKGxqQghaaBVAwdbAYYsX7zB7bEpAwaO6jnopB9bGYT6WySAgCOt8piGXWsvk+TbelYa4ZXXv1j4RyXCPZSKAyeqB+e9zAAoSgs9hGnIvt36jb5eNt8S7HJamBBQfF3LYsdnnye0iF8nS3ICC+oZtZ5XIX8+LKQHFx1hNxXeCGvfNCVMDSl9MxKqD90ZODLT49ccSuSy4TTP1uf6OClBK8Tdjv9G2xx3LRPu4E1QN1DhiapDSMAJie/Buw3XaUEo2icN8q322pDrOCSh4LDFgW3c44wPknp8MrESNY9D1AY/rtqF4+95UPD9g5jgsoHiVh/BlQqSnIh/jsmr/GKNsiHqfm3YOQCmpPNg3cAVPRaWgQaQ7XMHe8Fd65zoBhdB5NpUlgiNRl9dBcwEKEgm2FhuZTbwLPG+Jr1k3oJBMShpFJgIrbfT5JLw/LKB4Q8+YeIqWD0B0tEZRJsznILT0g6/d5j0QCYobzdMcgFIySo6J3Wn5XqQTC+yEsqNqlYL5Sv15Y/iUKg8GX2+/6IsLavnWWpu5AAV1yx8KtdwxO3ZUcCRnS1OqPD6NAHe0zyGq8bL6+2EBxbuiCGMm2G0oA7Y6KNMAizKRrpkQE7GQj+3f1zlB/LPemNz/HIDCu7zb9AEu0GsMj3xb+I9IbYMBybQG/FvJx4lMCSiM4Ysu2pR1ZAMaW8fZ0m4uQPFqNeokbtm+XC4/dh8nwu9TAorP7WINHsZQX+T9YQEFHR01xBIW7mJqc2EERO/ZDGLiS6w7r5QnxElL+H0rsbGIGUCkzITnwwLV3ICCLQg1JxNRnzYpsfZtuExtTgUAQsIbRHSlT67DaNZaaApAYg5s9vTUgOJzcVoT22p8Kf0+F6AQTXxjMwDsJkgtrVQqeTAloGCc90FylBqZ1ON2WEAphd4TUwBat5CPdvTuXFK1QVJbhoBgN5+ZOfQu3MxeP+dvuKA9zSWhUISK8PNMqACcFq1VyHzk741SuDz9+XR9/jYmfQAxHcOtpakBhWJF5AdlqmVmt6ylvjZzAYovfUHIA/PSQhwOxM9gX7M0JaBg46E0hj0o0ABwb09GhwUUBkLpuhuYERFjwQJuEfUI2bWZm6WTiroaNloV0CFxrVXt8f53EJks5FJC1FyAQvoA0aWW+hIJ/WQTXu4zmG3OB0WVfP4H4rTPIC4tIpLusNrbKF7a1bx3PlKWkgBDpSUwzLJOrFrWV3elb7GTYc3BhbSHwRm1tpQ5PBegkGlu851QG2328NCmfWSKF/Jthrx/PlKWhFFrJyy9zz/TV3dlaKx4XpGG4Tv/DiRYTgEoWIp9aj/VqmzyW2mAqDNYmu0YSnEEpf5bkRWEJ23fLlzcx/Z0tGObC1B4J1KTDdLDIIeRDPtCH8ErJpHyEJkOxAGk+Afcw7bOSIvUSAQvcUSEtDMWokkz1SKgKQ9gI5hbpEgfF4GUwve3lAMlxobiWjbPqq+a2lyA4tNEiIYm27tW/5fDkoBI2hOdbCOUhyKosTnZwlItMWAl6XVM8KZPtSGvh0DFfSCfAlBYdF4n5m+I9OThlCQJYkmQbKz9hBMGRC6RX3z0iZFp6BSkL8RQwqQzIVZi48n2Bv+uOQGlBHakFrDASnkmbHhOGJsFzPgJ9LNFmPmbj99B1CXVoC9zlWAzvp0NSuYvB4KtVcOCgY8+ZSDzz+dKoU5itxnKuUJKJH3eVohDeuT2waEyDgAEa8cC2BeS1FravHMBSimJEEM4BvESoeaQpMoBxz5E1SSNxWad45mh+FKJfMY6djSkU+Z6iLwHj7bYE9mvfUW0GCtqKqq6xQwALd9cuPfOqQCFFGYWh83opX8WMNG0qCkMFh0RFccHXFGGD1Hep29nxuBSw6DkS0xyOhMwhJGW+AoACnUCZMcVab8PFQyJYEj0nxNQ+DZvS+FvbF7EZSQYInqRNDi5KWbjS2D2FYvyld7pF68DkhnqC4sOIzVAQqQzBmGkOHiE5IhNxxclwo7CIkb6YePaQsU+zof3MTfkJwHezDt89/EYpXgZVFGCw/gHuLFR0PvZaIAneSQ2cAx+8b2lqnWMYy5A4V3em8jfOGzZxKiFrEd4AY+pSwIAQPCJZFWSUW2BL9z82BkBaMINrFGVOTtQ3CgZWDlksbGxZ+CNl8bxkpKZ7cMvAGXsPnwDz8Nj9hv7EpMGkoglJGXmY/KKbfklbGQWK3r4GGKBAjK1ItVYpOmfk20ssYGYsJqnY25A4TuYcNB/LDH56Mx9tqSxuRssPoyILGoWPps5L3g/Nu8lK7k8/TOcgL5+Lm34BjKNrdeqlRcAG2MeuipiTkBhkwKcVt2sfQtrkhIAAGcJYPPzALOV5nCIECA4lN2PKcKqx7kvbGQAtq+ZWxtr/p14G/bTsST9qSSU/CJQkbwZGGPtFn0DRe9DdWmpnEUfMA/bDKjtC1CX3sFph3iMS67FPXYUgMK4OZXwXLWAJeBIXlKpEpzlARuUuiYtGaVIkGRj2xAATiV4V6KS270kpdhn+wCFNkhgAGtp8fetHaQ46q7WauPMCSiMlbwspHIvTfvvoMwCgZvYXnLAIWsa6aFUztIDCv1RRB37S99e6wMUnsVWA/9Qqbzk28dzJGYM4dhvilXepgaUPBDCj1E7EEXZJOjf2cXMyYcIR1i9rUbeio60w0uASkP/eHxwuSISojoRc8Iig5mgcF/B49L7jgpQGAsAgKSWL/pCfeQkwZVsL/pik9cMffbbiD/Ag4JNg0Ar1AeeB8SxVSCS868k6TCHFGXG7sT4MNbiYUK3L9k58HKQHMeGYMFic+EZ5hkALLnq7VgBFr6fwtuI2KwbTnvGy2JGbQD0UJ28l6xv/cwNKIyDtQ5Ao55hCOUgRIXgMGCN0sqvAAABlElEQVTcxKjglSkdcsw5qiXrG8M4kgt7BpUTm4snbIWAAmYE1FjUVfYAZgDm1dc59s9jm0NCIi4K/sNzxoAqw37CbEFcGXY6xjB4Ady6AGUMOETb4EBwYEs4EICyJRMZnxEcWAIHAlCWMAsxhuDAlnAgAGVLJjI+IziwBA4EoCxhFmIMwYEt4UAAypZMZHxGcGAJHAhAWcIsxBiCA1vCgQCULZnI+IzgwBI4EICyhFmIMQQHtoQDAShbMpHxGcGBJXAgAGUJsxBjCA5sCQcCULZkIuMzggNL4EAAyhJmIcYQHNgSDgSgbMlExmcEB5bAgQCUJcxCjCE4sCUcCEDZkomMzwgOLIEDAShLmIUYQ3BgSzgQgLIlExmfERxYAgcCUJYwCzGG4MCWcCAAZUsmMj4jOLAEDgSgLGEWYgzBgS3hQADKlkxkfEZwYAkcCEBZwizEGIIDW8KBAJQtmcj4jODAEjgQgLKEWYgxBAe2hAMBKFsykfEZwYElcCAAZQmzEGMIDmwJBwJQtmQi4zOCA0vgwP8DDCxJ6p7X9/AAAAAASUVORK5CYII=" + xlink:href="data:image/png;base64,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" />
@@ -1803,7 +1818,7 @@
- + @@ -1815,18 +1830,21 @@ >
-
group 1 created.
+
+ collector + 1 created. +
timer start
@@ -1856,7 +1874,10 @@ >
-
group 1
+
+ collector + 1 +
concatenate
@@ -1867,7 +1888,7 @@ y="260" width="69" height="32" - xlink:href="data:image/png;base64,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" + xlink:href="data:image/png;base64,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" />
@@ -2098,7 +2119,7 @@
- + @@ -2110,18 +2131,21 @@ >
-
group 1 created.
+
+ collector + 1 created. +
timer start
@@ -2151,7 +2175,10 @@ >
-
group 1
+
+ collector + 1 +
concatenate
@@ -2162,7 +2189,7 @@ y="251" width="69" height="32" - xlink:href="data:image/png;base64,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" + xlink:href="data:image/png;base64,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" />
From 89650a293f2a148aa8f040f81cb48eadcc2b0495 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 2 Aug 2024 11:08:17 +0900 Subject: [PATCH 06/90] chore: upload jitter.png and add old design link Signed-off-by: vividf --- .../docs/concatenate-data.md | 8 +++++--- .../docs/image/jitter.png | Bin 0 -> 118229 bytes 2 files changed, 5 insertions(+), 3 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/jitter.png diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 4e0dd2887dc8f..00192d55a2fff 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -65,9 +65,11 @@ The figure below demonstrates how `lidar_timestamp_offsets` works with `concaten #### lidar_timestamp_noise_window -Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. +Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan like the image shown below. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. -Take the left LiDAR from the above example: if the timestamps of the left point clouds are 0.01, 0.11, and 0.21 seconds, the timestamp is ideal without any noise. Then the example will be the same as above. However, if the timestamps of the left point clouds are 0.010, 0.115, and 0.210 seconds respectively, resulting in differences of 105 ms and 95 ms, the noise is 5 ms (compared to 100 ms). In this case, the user should set 0.005 in the `lidar_timestamp_noise_window` parameter. +![jitter](./image/jitter.png) + +From the example above, the noise is from 0 to 8 ms, the user should set 0.008 in the `lidar_timestamp_noise_window` parameter. The figure below demonstrates how `lidar_timestamp_noise_window` works with `concatenate_and_time_sync_node`. If the green `X` is in the range of the red triangles, it means that the point cloud matches the reference timestamp of the collector. @@ -180,7 +182,7 @@ status: There is also an option to separate the concatenate_and_time_sync_node into two nodes: one for `time synchronization` and another for `concatenate pointclouds` ([See this PR](https://github.com/autowarefoundation/autoware.universe/pull/3312)). -Note that the `concatenate_pointclouds` and `time_synchronizer_nodelet` are using the old design of the concatenate node. +Note that the `concatenate_pointclouds` and `time_synchronizer_nodelet` are using the [old design](https://github.com/autowarefoundation/autoware.universe/blob/9bb228fe5b7fa4c6edb47e4713c73489a02366e1/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md) of the concatenate node. ## Assumptions / Known Limits diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/jitter.png b/sensing/autoware_pointcloud_preprocessor/docs/image/jitter.png new file mode 100644 index 0000000000000000000000000000000000000000..c984e940171a647289e71323849df461021cac54 GIT binary patch literal 118229 zcmbTeWn5Klw>`Yrf+9$#gp_m(NW+#8B?RdX>F!q8ASor%AfbeGO1HF>G)PHEcQ^kF zz3=Ba=lz{e@BX0dT35{&bIh@Ju)+%|3^Won2!b%4Ka)^|pu4INgtUYT1Fw*`{#XS6 z-EtIru8fL`Iyoo*3p~Ykl2mt6vNdsXHE=M7l+2u+oQxd|eSh4AAWG=D#1mz=pBvNO zZe$|~zs@UjYerb_YlO>Lb?L)710;fo$zBgcl&VPQE-bmDH5a9<>o=^-RbxRPGrE^4ncvJgeOyoTWfo~{w(;_4!ZcNQK&>SKW@Tfe+IYG# zQRWVlHb`75)TtfK*T4&VT1^6((Lz5IptMgATpS6Z3WG5GZ80z~ST(;s%WR>;?ZZ#Y zz2^5kvQk83HsZ?3$(5P*XKf?HnUN3y;Ik+YIQg%*kQu{8(TTmAfc&lh%o3X}1Nyre z;3b3t6$Xn|Ih-KQ+`2%){8bN3GW$JRf;+Rc4yZ*N!0QzaL9J$|X^?R_2BaF97V zI;v4-!m3rVVJdol-xc#eS7yk*&Db>bMV?)!#;H4&)llSmdfV&x>U?{))VO=UUv&28 z&l-=zwYfQi!%X%!t1?9mXKO`Xhk0?j9_E*4hhuu)m+0(uO}+o!mi9a_yUm~FuG7wA zXNT+csZM0eK6f5eErbh>7U|7SOq~7@#|jG#6}s4IS9g7-y)(W7dMkz7u1@ka@=bWv*ypFUCH zaLNsF%Wc^+4*SnLAf?4H3>XH^)>?KjUy3JqeQ|c#=-Z0W^BjN`-ZNt`WBAvMZcO8| zK%W^n?-SHw_%cffLjSx5YSF?f7JeH$9DZ)v2>hZJ8w`S@+57$Np%%byv zi+o1ycGAKno?@j12)YI{|p-gBN{ z#w{(+L95LP+$`#+_hOaS^-wp?DyeM4PT$V=wtY8cxOlVkALj)QS%3_YynA=$8|4+T z6_r|EUteEdJ~ADjAf1`=dasMQuu7~n>Ath@aXLwW!Q^9k4k+#Hb^xBSH^Dy^pPPQW z7LrdEIBX}i&5rQ&^u&4~#OJy-<=Dr+yp&|yu$#pj^c z7Yh`k*BAS?b-V4`Z?--6mwG)HBc)unXD<7%FZ!p1AoyXgZFtdbND@63el|r6m)b;HT+=E*n*w6_dcL zUDt+lfb(5{3Vg7(wY9W_1m)VgpHEf9x?Ssk>$Ca!6x{U@R- zI10ppD8{(DW;I!3py4P~8Jbm2+u+<%TG;oP?caDI8e|6|czkYQUj@x}>Q#S4y~j*l zmgktagZsJm(e*#ka0lxqsztX{kmDo_4HrA?3IVJ6`_TJ@%>Y5aIjp55HpIS6{xdk- zIub;_G_qK0^#8=o1_=-+5e^xwQW924%>P`u$@M0bDui?U!~c2Zgy7~I-yi95} zzpwmKyNSFEcm6vd;Xeaf<51oDC*n5+{uvUp9R0^D_;4f%SLgS#50af4(Oo`F~GA>Sw8BYu0}+AAEBZ4B|gsB>dzMf4-|6Z7g{1A%E{4 z{St2nyKrp+It-$v{hD#RsT9KhrmQqvmdS~_dQ;i)f-AS< z^dfcSMTq16A2SdqfR*3nhak9ciIwSgO{Xlb8-$8Ht zE*lPn-=P5(6a7{!4T92ULixjT3TPYbb)?ixN!4yc3U_a{1eZ3VLD()gc97D;27d%T zo+c718kXbDVLw!HOAzbO-X4NtI2!qNkJON$n{W^Jj-<~Io#*XW0>))gj z;7hXa{tU5`0d;{@Al@%<(?Re8C+CXG%fq;!XA)yqt9fzPOR@c|$x_6a5bcd2HAVA> z8{P~9IU9Z+isz23h~@jji3Bl8C%1euF9klf<_&|d-q<0BvAO)AJldbtI?5aFy{OHN z;4NI&e@qA|yo_B43X(j*fRz5Y7o&{U3_j%(V8*DT&Lm2fGKEW~mNKu`1B`W&t+mM@ zxTHob4NDUWB8TSB95SsZFURT7fbSiC$}8Jkwbd)L8X&`|t}tvKnr#TUpn%fQ@;3&x zV0KVE?#=1TYFq&~1jsI%D4;NTfS4dMqA&dAH6EluZgW>5L2%<>@ue4KP%s== z2|4FbMUeVqHE_JNHfZl5GAQfeH(JO-(05|Y^OZgyXCr?@-5a(%GoQ3hW@Kq(5JJ{$ zDHl1wAIdUpC}!wUrjUYwA_CsKAv9d+?kPX3FLqh-$B6EjnnOPC)lj2pcYw{LWUxpH zm6bq{a$+U6nIAZk==|IM@MC}>ZKi7g_OwVm>ZFONN_8bO9m-7wE!WpZ@&W?`N8*mQrYA>6 z%1wF`-<%%_gIuI{eKzKttaJ}&!>1bX!MYfv|C#e_( zQefSx!SkSi;y;k!!*pr^`Y5;Tcs*$U@y-LcU*UpV>WyCYK|%*V#L)>^+)m~KL7sbx zb2?ht0J56be#NAX(rlek7w#4r%o@1q_EqCl2<0Ge{5Uv~-}CO;v`zhcE=Y=~_z*OV zr$hiV#ssEzNIX?aj>F^wgXdg05bE37+5#+^$YVK7VOTP*qNa1$!_`0Kwh(sf)~$Zw zocdK_mU-gT!Ur+FA*bsQ zrj_#@r`@8&C96VQGujK5$R3?{_|q6SFhAgP;g;b~T%7LGsu+O$6$)ahlF^%-lL7p1 z3C8t)(wG6ApPx$_HT$A$nG&+7+a0XD#5rxDxT2&6ne%MsxWToHHtu3U^lD*Q^!ijh z5HoB7-EF)6*k-0~;yeLtArBAFZdIJk@z%7q-`Yt_8r>_|laZD?u66q`wYy(&y^fab z3b8JGZM_8>BV}NJ3Xp7~mM<7Mo70AG1YPR7M?i6bU~WiPwjCmYOycl?!}p5f#=UodDLJ#1y@jlwhkr7`!=q(X)Ywt@>l#?Q75T&B|Ga zZq^$}`$;l{umBk4kyV9aOe=RUfR{zO^#UYe4m`O{rOBypy!$=HyEw}oxg$YL8Y{Z~ z_(^F9Ag_js>y_vH2X$vBWvR6myHck1a({uI^Q--BZ<;KA?tJ7d%6s4C9t_O`91rBdpBVq%3P*odisfWVaPRV%&7 z?x>b+*eNLhek_FhUUVd3gLtxc)$%>!G>wKDt5>qD?{MSrqGx~bA|2DgkKnNjhBME( zYTD2g*$`_Jf`Sb3KQdfgWj||aR#*V_%CH6^9Q7C{lmSu>q&bU+KK?moMK8f=dQnS& z@hmO#YB{-Lq=ioxqtvwR{ewP&Is-WLYk z!9QBOEbD7l3-i!bT!rPC4>;D+*g>5ITp5W!AiZ%OC_tD3+&f*pT)aLJQ`wx z*rjARB~}4&2*FfR%2`EEcn6X#{QrYF%@U7zz4v)Zd2O_7oK|V$wD&;WRKNF~S@e9O zzseo827s^;@&fORWBK|i(F=MRq8aZ?+Tm+tU$NfTI6feAQG+Q>f89jzk`IfBv#s776c@8Q&i^CFu`t5&eez*04%JA@TuT4um zLHE7IcLdBgMa$Gwe#0gJ$}b+`&Yq1{zWB&j0)iK?GIrg%_@qE=4yS^WX6(pOe)~Od zI3hzhN_PV!tzoWim&dl-_lJlCs1rLuw8|6Iy#G5Obb-%;vK1Q@QfS)^kb^KG<7`kn zf>`?EQ@iHS*FPZkYtFB0=Sl0zX_rasDGt8~foCly7_8U~<{>u_At-2LU3h>up7`2b zD#Mner0BR6lnhnUb0K1MfAb&uvHvP!EWo(wWw~_}maS>S--h{QyFo@o;=( zIL|{}Vqn0lxq*YqqPM?*I4ygZ5uVmwddHl@7s;2vtM~>p;zXYI?v^&bgSWG<_H+i~ zU_)sZQ@!4gEmx5AnLyg*i7g#wgTu@ypAE)xiQpqaX_&0Gsgt9)6y8&*bc3UR@jCva ztXlN9U|7h{#ZN~9{v(6+CgZ;!7@4R5pnWt}ySINd_5>I+ zfFV_U24pBDShqk>o(a@JKnk&_aZolZmo>VI6QU`ALJW-pf+GLgQ`~g<`C`y1Q7Zp- z`1<%YktX8})XMGay#VL~!Dv84`6~oF5g&%l;%QN@w~)VKnaJA?k$rF{xWVj^0w}OIoS&hp)bYC@|cz8h-_QRSbenEsuWn z*$)$|x%H;JXn$6UUfd@}+z0y@WGo2g6Iv}09z<8_?%BT-|< z^5+t0PHadD;veI26EXWY^QJIump_THy$Evehb>;BKyW_l!mFoGFnK*-pzLrGNEq!OrQp(kUop*li%+Q_W0I)2aQo_ZRwH0c z`Bjy#dTe|4O?7eO=nOT_^40K$L`&}Ov`{h)opboy zK0(y}dfvTFow6W`ek1Rff1$~=nFUo(8a$`1Ox?V@iE_r5f~!8mP1 zw0juK+nn9GS;|&jg5>tC6O-(+KY?h*mi*R3$>iy!-hFy|oP5|VOGs8RoTz^Gj)nWBwJP+;}5TMk+g1{CYs=`e>fAVmxGS4As~=KFHS9uy=hP4f42 zEG;-BjJEEVJgVsgf%WQBYnI-jc4_wSNu5-6z})bU-0xt6a|C4nE*S@PW2io?Pi|h< zqfcrjZ*4i8msnt%9nx2Hc0i2+38@xh#;rJ6r0k0RGRXWkO;Hz35%I)yMYHvXL!2+~ zw`)-4|67IW+Fd{SSxVc8{p?rvD@*VFvRN$p!8NV|9_#0bM>9iKV=Zma>&L&IPd*C6 zb!B=xj%`q+nfV?jQJ=RN8k*qZisZoj4SPoB3dbImlL!3=_5f|yOJoS~e7K8BmX7%| zQ+hxLp)3d5_e+-8O$iK}fmTl6pD3N`1II<<8H_IFZex{|4ukkvgCi41XH7ZV+a8-e zTqIZBzz-?{^mj8Lb7dqwOtU5ZEVyaGP_Z1%Tg&^Pd|(Kc2I%K z$P(Q}gq}UxW`Pqn5?~#x)2-NM zeiJ+}*wCqb2m65pW9rRa8isW>>)5+<3SKOAq$9)8&JX)*Z<@_NE6fJO6 zW`#50Yz>OkPdV58UVIXoX17O<#(k+HO2l|7x^&UH1)cn6qvKy4Z{9Tm1FM$*RIhyZ ztNjnf)R8m7Jrn6r_&BE(QJpm@dCq@x33 z@6HHgUbYybqeb`*R-bo^wJYkn8xW=GRWrI2?J^!k>-BFl7{=KRenr*9Q2^n^Nf`A} zx69E3{;Te{+grj8LS$vlL))|}*aQ0SvvZ>X8tjxTQ!VeFueHpakis?1eO4xUMvVIMOHWu>8UwBm2 zQB@JPZVw}eMJK1Iy}<)vFOV61F&pU(kD6H`A*aE!_pto_C29+^8^FrZh9th?iu8yq z7g>CaTMjR>fGnz71Zzr_`nTE*t;Yph=HazScxfAXc5U z!Q-bG$6R1Cc>#%caD5iYH39TSDhIA6H;GwwDvGm8Aq(j8CNMjnt9k$$7$wn)zg3kY z=o96}?1(7e#uxh?_q-jx!{a%L&58O6z`&sQLkZvKKFNM8t}2-Ck1#)-+w;KknA4TV zr7_x{H%<+IyQWZ}rX+3zEOJ3`sBd3V^^=1~PMz-?nJAgR4m%}LDt;`sT4c6HO}`lj)>_*#p1Rd>q*afg}su}{r$cm z0$BsXP%ZOpoUd`whGsZcH-PT=x|%Gqp}7^{-a|52F?#Xf&8Sn_wPn!#RzLbW`smzS zTfvqd-t}5o9N5#4Uzo@ z>za|D^NM}k&v#|1-fN{sL= zekiRKmA?|5!;ePP;(;okUFYy--l-WEyWgBDkvAg?n3y?J)5o;UJ$EXFlKqx)v`Nic4=7fczTrCV+}Hsd^|vp!aI?DfBRzBi_(%i>tV+>ajZ z?X+Ok&hE^Iu+Mm3U*6D3Ri@cS+?F!VM8;o&QpJg8w2Yv2gK*08rQ9+oVFekAW-zaD zEc!Hq(pg-AixpwZW(&aSmh*1yQd}!59qG&@^(&1i0@&fYwQ}(3R~~<{G{VVp9EMX+ z#(3Ze1r%Cqk8v(VG0{{3LVwp#`zGDhv2~< zR_#(zp7plm3JJwVC?fngXxmY>v*Gu)d+&ozNC%xPF0X8F6GejlZdIyAv3~PFy3|O=4f#=6HUCcZ zG)k25=qqhhmyzO4XZ0a9U?{V?gxMJ1amgJw9+E1X5*a7Os+7w_erH1`h%{m{eyp(e z7)<@>lym6Q>licIx~EZ$IKd=|d=)|Q=7K?L?WM_=Qu3Jh=$Cmr*aVMhd~}^|lb})B z-RhJ0&fQx)QnOnal$gz!_K9I~bwKuOQtqp-iYIiM6+seCtk#0heYb)$3$z~#CCrPR zdPo>#vGNG9okZj|H>L(&TDm)^jmi z7;UR}62s$^SbV!cpZi#igO>gd29CAeit;W+ze8&&SO4M`7?-zQDWJ*Cn|thY!~T(A zt!rbO9qbADz~MS|jpJF%0=ww>c(=hx80PEutF%(MU5`ATyINH*SITosC8WidMn*+8d<(O!d{4JQMQ%RaK>q{bb8_SZ*csh69!-s_j7Hve}+ zKQ{A!HuS&Ruzw4r$=Wy%3wmudlQ2CUr?N~@Ut}8b5O-}sMNMyL6nEMDUiKYbPtB)K zB^E#Th19YOCaF?S%?NpE>YnJZkX*KQOkV%q9P1bGeCc{DiF9^KA$Tzpaon&XcZ`ws zm7>w)BF?+=;AaS-o%hXI^m%*zX1q^M5ZSL&zBc7kK9>7^s};Ln=k+ViOLGtNQK?+{_5E}O^b8d};TU>1EdBUL5Xc1spVqhWrJVAHXh zu7UjJ#%UYXeLgzsF&Agab^_`l%){=yMxw|G$0aA%q8-EKy}bv|AHE8co1RW(-Lt02 z`6_hocXpDil1KQ)PjVkMRJ6`p6Z7iDo2eSRxwVm0eLf$AN7c3a>CR$ZMBnz7E@Akr z*+En7-kAYTutYkZKP353PA28DJjh9}wuWCM%GN2ll{}a1kMN_SvJymlAe=ZKlwl`` zRAxF{jFO*moqa>?0NBdQ!0R1~sqMOx`H<_a?JLkwat56YKzfJ#W;J;CH2nZsNpV@N zXP``~Tu`xm{rw*P`j}JtNu%ZeW|?w+E;Cna<*ZYAMVP5gSE@*S4j>FBrk)QXOzVC% z(Kj8@AYf9PO7l5*>T)H|Qq-N$8r_Tmfrd#u<(NiKdV+FRndHPLC;svU)|QcgnN~)C z8vCY^Zy5q z7Jv69OgwM=0#cFEmlyTB?WAi9Gcz-9?_l*M3m$)T?5jRqO4_boPN4-71&z|h6wj?2 zsmwf4BLg)MlUPKgt%DDl+uDBVYPu&?Hi7?w2aC|9pMVIbcEx@Q5Zl%>Gef-b6OYD6 zac8RvX;$vE2jrnw=3QT;smlH#4^&Ef?0ubvjt^7pv_90`NBRfJ+)zb?x8VL&fgJu0 zP5Ps+_;doX3ZDw4|3$(Jpz_1{7+EN&G6%$OCRQexdy=D8%okg>b{yA9r8A4F-Mp z@fw5s8t_?XH^TIR9VJ(O3$vOmRg62USy=bzzh5yyX%#r7v)+RJ?--7aTzl|S7bE0c z6X`yqGd2y{Bm|9TKyT8Xsc$Z|uyixxR-8XZ$rgxvP9GhW<$C2q4|_8I=3L#}4}pcn za(C<}C2tcWd&A3X&*2|V(uyjw7>bBI)dHp}1F`?m@F&+>*oJ9h16DT1sXA@mPJ8%i ze@I09{GXuBdcz>*9-Zd3q=)6+vX~kDF^#YP-s|KKenNxdBjX!4P$&9XCU?V4tflS+ zWXHI>SqPeDTse!6Q3ufVw8RopqSiu}15XL==CNz?3F3VsvPiZp)pmP_haMhXOu}QV zVMt9v2`{qSGBnY_UcpH=541v#`53H&utLgbU}NKOLDnwU(GFjTA6X=Y@(wSCD>h!6P(>H!;Zv3)ht%Vn53-6V3fVp2oYtv0l8C53ajyO%Si-S7|KVZ( zL*KMt3CRHL?;cP;q!B2~kR(M4gRx8o%a-7R&Cf%Gpc{4cx|F-xS6gN-ycDM^ydyc% z&~)gc{r-p2fV0HdFr$>uWamFE2K9%$x6Q1B9V2vn3 z1|pV~dLXDU7K8JEbvN@@Sa$WikK@DIdxiS%re)91Sm3-QJgi?%eo71u?ua^@d~xkB z6e!zI;0^cGR4&AWu|!sgjiS~X4)5I-Vv?{3dY_p~30eg_q@&A#xDv-0L-$I`{W&HY zPrPp|ml2cuMr3u9Z#lis4b8^_w}(F&kZuHXwc?FXu@n}9TZ1p7G;p_jlxA!Tb`IQ?p`cf_<%Q&$* zSo66`xqLeclh}yJ^?^%DS~p#EZr~EN7OHZ+H&PfJ*IY|N(&U` zDqB0G>1&Ns9LEM9wpkXqsasF9S(qnYu_3P|d$L~P zfzG>#8kia07bT&3R3$#_Tph&FB+(}iPBb4?d?F&d^og}?SWjzzlnJ~89cK1CsPgOxDsb)1Zz^IBcn(K;3;1ho+KoL8MN5-9Z0?m{O&Anyb+?{ zsI&pgX8=sXmU{J1=JTEn_b(Rba=TAtL9;cT{qSbs8kYJA1c7Tr!yaAiU9hvVo=_HA6~i8?=)XBVT4B<=Gz z%@^uLl4t7GKoE4ap_GP2t8B)+NhyOQrPVv4JISWn)H}TEliMu53s|yQNl8%G6rxmP zoB7^oSaeP$9lnA38n3<#Fa-Vb*5@|P>C+%A+c1;Rytmn1CLWKque}_UJU*@Ff9#EU zzQ3dkdX?1U!wJb{3)OG)!2d+4!X1~PEo*qlu6#u8I*8Ml7YxX2QXf%JtKME&RDP=t z{xCSdyzyFipHXCEQ^<4Xe(0#A36y8oj~4nPeg_89 zdw#6e+KnLWW{10g!=behK)e+O8}Y(l#|cg`(Pj+jU4A$;h7tcNn6r_K3Hrrbl{S| zQxLI4t<C}6X#K^27$6*yq=ANM#+q0D%h1MTjw8gLlSWmbhzb<}uX>#Bh&&V?k1 za45seX9pL*B}dHsdpCj^HO)zbpYo$~pw^R1dae1?qASRGp_E_-FAGtr5*An&lJ8%HtoOe*!=)Z$r2 z`yT!@gy^(iF!h5eu1MC5QU^}A3-wbQZ5$q_Lw8DK!&}Uuj7^Vj3o&*B4In{#TbsIb zt;lr#S%&OUYxKrbYR?Z8@|Vi^utP&zDXJd==}V~89yzC;qV39zu8D8y39~=Esi&`7 zVE%7A8UHF?)RstpTva~<^qdF#BSc-05))o39Pv2@G(`D(Vg#@m2wiclY!Af0pM6t+ z)}UuH5{Di~9!8k@z4QFVXXu1qo2R4D4c}62 zzz+I}$9tLG#JoD}ryizi@S&)$8F=zUJPna2a#Q=P@R87KDMf2eWN-pB205`0>?o~N zTFE+IuFH_52guT(WXH;W6054}RO(+JQsGV_A5|;DHsh|1%03Yl@WQ~q81*NWbsNFp zG1gy6h#R}R$kt>f+lGg(+R1yrRm+mJhi-Vk^J#vMHLZr1y&~pUC9pmZm*YBwbGN+gA#6f zyo0J0?}`ddFnnEyggFU-d0ZKY>8U zP$cJ(FA#QQ7c8Py+NojogJ}8yr^C%Ti}rH&A{*mAjyUh5bV{3phn!;CtayuJr$+Za zmbN!a%@F14=O-T>vo$GqIZKb2%=bLS&@@M;(k2J_lnV4o)KCqG`~1_%UA$>{elZ#< za(8JUVu)w<%;p&HaFuuNZ7M+hyJhTzbd%0iV`ugw0vz!c+z;rr}p!u)pQ< z!e|-LF@SCi0Pw04Y2A)}ckVZNyzhIknD89wwjIfsC-$?SE+n18kjg(0-}Y(EN@X|8uiogV^mCjohFFv5J;QcH<`wUQV>7VL%sItOItW$?y@`7# zz2+oBOW2j0nR*#5Yiv{hw`?zY!dcXv5pKCBmX=`pL6yYIOGRlx5doC)IJfU|S8P5n9eVn~hM z`)qP-So{ssQ0|df=x{uqk~C-#=+~#+1o21}n-hk=qM*-%l^+Niz&<_sU@iy(7B&qw z$V5CDiU_(Q-OJ}5mB{{1MEbWt)9-Lcoyo5A!CU2)GKh;RG|L_oKbBd`Q#@?Zq7Q}I zcBZE#myA?gx^>yKlT~s7um&w@6RhH234ZdK`BMx0PpA~waDB-!L*47%UVeLV&VqQz z*z_F;u+d26CM>KpMGtfKu%PT2wkGZBhuw@kss@9_?|tSZCiIdcF^f3Am#j6bdIUe< zIW=BMv><=$hX3T-J*~sLl<*hyL*H&s)hx1-VmExBW9$yQw)~imw%dXiLL9ppq|&|I z(UTIC|D6X+_zk0S&T~+Ub84<&)7d^05lM6;>#&|xT+NBGPjQM_11d$6wSt3oM!c6H zcT1Vj76j@yTALVnqI)3rq7L>o6eFpZ?xg|5W1P z>toRv@`Ed>Z$%#nlojP>(w(g zU#Wb!SgITrrkyZ-B*q-pRQF}#j*2rc#z&MOg;0$4V-X*U^cU&UswNbl40ha9fh zM2&zaIH)I`!wSi(TNX@#{c0Q_%{9yaiLD$^6SS z(o{dv60;>D{#E2~CVd)_))Mc>w1-urb6CmrBhsE}R3vs&qNrDLdLQW*zu$s!!>0Jp z&gM9|*3(DGvMKst!~E!WgK^YKj1u*G+E}S|(kQXb?t0m~^<}jkg(c0z(iva49a7eq zMh5dfgxY#>iEg$ghb-`YG>Cu`C!YxS62gA3N-EHbRW{Q&66$l8$rgli=GKm+bfh~} zRWVpSOgL(1J#1ppyiBL&G&rIRQ>2sL>ww>LMdSEa-Q}JH)Ll%P{f}cR{B#gc9*?|z zs6rwF=sPx0^qVOneqxk7vQ1^Wji~vsXVr+Rhw_-qI^-F*qSr+P^)TUJJUd8apH(?c zMm-!I(H!%n9tUu*>lqtwgfR=FV9X0F&4szQ1Ze6IEG65|H;=pYz2 zoGuAqa#|xc{#-I<(|AfDx~mcv?W4i!6=gtB+hq63%TdV4RM^G2;-a+4!+ppsf=7J^fl?QzZ z=x(1DOB3L&adR>^B@8y!buS#^j;`b_+#%-Ev2%S{!u4b-*w@YIdqJgUrpJxWQJzpc zQ(z?b;lk|q_S-Z(7DO6ebA5t=&a`M^>H7I=(%^>4{W()8Jjj1T@vxr*dt*Q zz)@f_!{Q$WJ^*=5UNo#n5WU!qAX%a&WB$R&z0`{waQDhvr5r&D{)g1w-Yv9aI(5Zp zSQffe3Sv1>qDAn75eW$=9rO)GzI2lusQ@VZ2R5@Ln%$#0QuhEslz2vaih+9|H!aSU zNDyd9ug$+LgVL2>Cv(G}MNHUBCh2)Wo;R~!mfZ}yxt;F5!G>9G6Y=<@ZkQhFmv2Ww zg_8H=vKri86e!+E$epXvW;g0@^4lG%(tKWhbP#In9Yg?PjwrZqF^NkL;%; z0@-r<#6zTHEEqW^H?ha}(gKcT6k<+l4}L@CN(-@2e0|!RwSNJ7Jb`1hq9g@0w*n)R zC@U#IH$v#;MCXFkXLYi;u={FB)0xdGr_bpVNO-)6d#`^i@KYwf@FO9l!Wp4q8nrl`Q-B@E~ytRABRpZMRhbeI6hjaeApG8 zJ2CtEi)#XVfF{?70YpNJ!7|7ng@J3V{gJ7Pu?15Wqe;fo4ZHmI7sgB~MlXU>)({=N zfdAjC$+!Fa2ZhtzYmvBer_r=s3v4auo;KYBm03txf zWzv_cN>ihO5s4+$OpXO%MpJN0YbZp?I(zsyks?osKK*{z@e{1&G6)rhnq5 zniWobFN6=@0uoFeaKDrQ<1tGUchQVrmp}pTor-o(JDqql6;cdsjA84q=?vY&rf8+&eKeYa(ZNYw||?P(^O^B?pLU~Tc1&{6Wj0D zAo&lld^Dh4w2NAtM&Vmv-oAJqgA^XOjSSM1A}ll7Os(qnL9 zdU=SS##E2nJA9a%iV^qZ{?FKxRuHv-bW_Lvc!A>Mi#KO=5f_Wzdi(>)iuOT~{Ae8S zcO9Eou^<(W54lIGhfR0aJBR8Q45m?59^jY~|F(^OvU?h-&Yk3zcc_8DzzNeqMAh%P zhs;+i{7&ebse0bBrtS0O2FSi_k@JjeL@$2!dQFvf*Q@jyFzid23P;9LbPlCFRxwSI z=3tfSJ1X@a_^@Q09*q$fK6>i1S9ARId_&a|&WDrHmFPdFAG}4oAs=X-RmRC_9EBFu z?bGvYsnHv%EjwX=)9HCa614$iv3uZf*zyI=f-ex0>w?CS(3tIgn^zm$9Cg-8Qj;aN z!u2YWI$ie|pN!{}phqk%Gty~u;s9qm_c5p^F~1E{5mo;; zhTC@;q*4^1Cu(3Ao~GMhTj)ReE+|^5QS$6ink$T7IqgJLlS4Jf;RHYWoAwr4Q-%t- zAvAV#`1$D6^>?>d7smp=XqQ@!$~iX{kT_Rsu{m4_`m}gd*F6zU}$PsO*)_vVi6L^ksAQ+!?2c zsYQn+qD76A(`9MDuz2ofTQ& zmC4l?#n|i`pXfvSwx(G-Nm`O~i_v zSn)8)=uvmrsmjUlPh58P*J$6xJ}HgJA!$~m-%e%nwi4W1-4{{B(r~9;VF|# zRl3LudG=5Xb=al#t}^n63agRO>@NHd*l=elja5!Vtk9R$k<0(Lq+Pk}L$ww?SF{S! zG{MVi4F{0P=TC!4MEC%U{msm%;@$VYp!-Aoa7-KG+POW);SSNWefhX55bMfo&3a1Q zXFB+-<rxIHuJ?c29g)$bgnvOgq$RLn`QE+d)hmp295 z{DpN`LRLs|QwNdak1MH!NXdP(YVL#!1W)qb=Oi(!7d`XtN@%IRr3%^K8R3<$GTuFm zF}JB|4P^kE{37~bCw@Z7Zn)Iu?oWF}@P@7HQz0Rg6`!WiQZzY>o-~pzhomQ5wael; zr|#|5n?$)mPE}cjQ_W?|l-Rn*(y~R-8b;>r;_=T4-{0jm^(Cef_E*P>!qO{45fUWo zV|yS^uzhD_>+{B=syfissPek#j_J#)@Af*MIvKX7yPo|*(jyR_-rzWDq>|M!Y_X8w zXZxE7)+;kYTBGW6f6eaR2h-Mr5Wi17b01gZ=Co;V3q`JOz!q7W&_agw=NArEGiBnu zelzQxej{r5b@}hDwb#veDC&OsqHoo#7mnnqHJ+{IfuEo02qy=>zA%2=a9j`Wc}tgy zxazn*p@<+Cyph|4CaLj*DzohWQS}v2QAgdkGXq1Xq_lK5(lAJOw{(Mqf^-a`bW4|X zcS(cNozjhTiFCi8-~a#C``%itHLNuYCeFF{p0m&1`)-W^UI>!Y9d~Qb+EPzXYepYd z7>I&PbY0So8sf@?(78S!+av!+_0u49%eyXSeh$yJ=9ejQ!~69n=U>AUV2o#X zIsGQ*?Tl9DeTtv#42ANgKuPm(=i~N9;70zPC7`|r6e1IrqX;>X4DJGPE6|k2aAa)i z7o(L>ozp7zK)V+!R*7{ar5<-o@DVuy{U1i~|Alv~n-@PVUjpoCa?iu==f+)Z>JQ`3 zQ(lin7o zap@=bC^zXemZI?9%K_MV{|sgLS3NBNg5!9=lk25p1QAEa{YfkTyZKm^BAPgq>#8?@ z8H&&ndY`41j$$j&-tVq!&7-`QS#0SfRK7^MsG*_R6_?c=lnKVzS-HZX(u+TmeX%0T=f7LjKNht zM^%o4!E68TWDGFBc!MXhm;-yrPs=32VtWQ{)0|(CYOTv{L8uMGY)w|A%UF*Vl%f`C zetY>v-IZ@es-`-lZHRO)hsJaRSTji%xSK`l#$ya#Q&gPQz8@YNX_2YL6P*@RVO_?n z1x{#vrne3e!6aEiS-(@4VoUG43El;1nn znSV{V9+<@&%YY8>pgsqem5ey8Y)CDR1gK&vPk+R9u*Y_}K^o-A1*pltzMP9c1svnY zIf#iphde)V@06GFWJJhDaUS>SgdDY4XpKQGinyz)wgfr>URvjQ=IO(>$w$)%;GwY5&`QIgAkJy!Q$+Pb3WBRpH3t}ZSvS4RuKpP5D4u2fXE zGtu`lf1=FQOFyx9l`4gn1FCS_}~{$Boh$? zbDPR*2l7=ZLa2yoC`0>Kp}F}&jf4PJ@c1!=)q%jYZ~}NWwDb?uj)0%c=@Y;*+n{{f zxH;Pb$jPFI<#i;aq-%h@UY5e^cbUoK0ie8px^jNL`a8_=?Z5u7A%&gPn0@KUSy5T(s_8NG%_aP5;T!(@g^r8{<}$ke5(m zYek7YFN7v6;oz8z#pi?16fY)joD}o6zv_fZDp!RR-1q4xkN9Q4+oye>02bB9D+Q!v@>b$0Cj+hk=jKMY|KX8GfO`;=INrW1I}C7-v05 z#TQ%zoqUQfEI#pz(O4LI2VJU^y3(;v(_DS~V_j})$-vsY7d2x{hmMKsvq+{~m_cBU zAho&5a&z%*Msbedw5L}fvs#tC>j+Mq)|IGsGpxVypLD{qbY??}5qXejTgu&=GtOKk z+Z$mgIJ7ihEoyL=Sxs{`c*k}#G&D79k%O=FuFy`Eb?zKdnyGU=VV8xYY5fxci_XJ3 zvUtHfr2{ZV$1$;=3ZsrS?`qX6h;N_*=8Ar2wkOLcBs9 zYSXPn%N-dE?6&*)F>}({>&|p9VVU@nuvIK=G&w2%^PZ|a@13p8nB#EdBDdSPSGZyG zB|ScV{Zbc_AwKTDo+&CgA6M11M!Vj3AD{Z4|JHQQ;Nl55?(~l(ZHxMTSh5@4N!I4H zcib`3;C*F+O>)}Cnb|qyZmAM21tz-#gQoa5*WDa-j5Sd#a>2C-b{MCKryLQX83v*O?GanutA2-81mvK3;Q> z+j~7196S>{Y1R77S%j$AQ}-eF52G>~Q_kFlpz-QQ%K;8P!>S(acBl^nx4mM@Jpy7A z&lj5gQq*BmL*rEs5&aF%w}nq;%+q_Lb}qBu_$vsV`(*L`PHntD7kyg_xWg=J^Z%1T zs?)i~kxS`+yG<@BO8sHaNV!KYDvNMZB_=YuSrhpl;DZMRUdvEZ=XQ!*nm#l?EsrABgP)1IfF+^(#4NPb;|5bP6gl8Lxv->`VyI2uWv2J9X`<~fHEQ(|F;l#sqD zmKkQiz#S!fNjMqZ=H=EOZH#;C0%#DQE^l{_>)CTfA6wVhY+3CDaEB!RDtR4h6>9q) zu5^$KuWm1t)%%?~Q1|^A+;V1!iP)=Zf9i{#agcZ}xLf0ws+Z)TAd?FXJ=>Wye+3KV zzYtaK0pO$i#KZVElpc|hkxF->nkrziyS=>3%uHyf+e!28s{j3Qz~fwisQ>k9zJZ~k zbpC%h;F=kZrlwu3OfH_DO=V?=kvwBJfRh{-{blho@CVOV4s`} zqxri6o;p{jVS9`5F`4(v_s-urjHe!N{|2-fiJr=jM^H}*lr^{BhjTv#Q(l}T=9mpn z{*&m?Yn$}7H(lTRNX6fNo8^s@U2|x;92evNby+0pC;9hhU8+pUqs58?d-28A#k~j8 z_VqX)KcBJ3%I=f*n$xhmj*(wfsmSezwd%GeT`3_U@rCxIa+mrSEx2dnkc}7Z%lxd! zSK$NtyBSL>k74F(&G#R@%5ERy8za{#xEMNt!DE>ObYuD=S1{1J93lr$C{d$%6Hqq6Fj2s1o(%Ga*iy_|e}Jm$UtE8XAoLjNU&LGxzq z9J0#exnUKDNSO-?XB^&mJ6(Y1_EF>P$%$f0Hsg6S2}#<8PhkcmgYkLS-quzRa2C{h zUIdIQ0Y^?i7-QnSUqBuIKjwu%t1|wmT-koLsKmlW0f-;ah|6R87>)( zw5-zmsfoY(;yp)RB9jP>ogw;31Doej8_5^hkL|Bs;Nr?&05zBjw_&aL>;z6!Xy}%b zr#72>n4HCons^r5bjwrG=*T0VV^LeD4PzW3?h@{3XmMT7P~-E!`|m?KtC#=fyjXZa zL|?I7uJe&X%WztnmXI%ZvN*>f>3C0u_Waa323bkiKp-uT!C3e`;P@8p<@XQ(zmi+@ z+bOt-6385CODWuzqK^CY@CB;P7dx=W9L9UHDfA86C5g#CgTyNfWe^F zB+bpHYQt}_6_vOf04Bf^)BobvCu#jt;GyB0NLlbo$oCxL!RV>4`#*JS6Z|=kX{Bf>_{`NMr817D z4@23hqcDR*^|m&lhP=38(ln{xoeyYs)yGTx8;PZ#JWfjjb?jc{=e?w!GTl21E=HST zxa(9h{K6R*yhpo+I-~Ow=zs#QR(VIF%S4DC?U!B0<6GDkl0?j;wouimh#^RyD)D&e z$lkd?29=xMJ7H;}#G)GRioIX|`@5?daYP9#xyJ=Tz!Zi171F&YK82+|p{e1lDX-pv z*EruQrAdW$S)Y-1t37tb<0IT1@L^pon>ARw>EMVYvUJbOy)iLvq&@UB4kcD8AEpv) z@98lhkUp*ZI)&*vo>QRtYqn3pzrV5M@=om!#n^C?#=<4cwr=OQsvn#hr*)gyPPFLGOE_)L>z{y1+ z>YcFFblraH$G_%#4!Hg_0%8h}_Cupy^D{v8Bn;9j`?dBkx>i1S_|H*uZgy5BO9XHy zk~f-@RpAmYLoU{yt};BRt_+AhdQc7UA_39n4wPDPphW8C54egrm%I#NEPPEs4*FY5 zg-V9g{I{oZwqD@VlKi*4M>K=)Qw>F>6+O=+v3v^{0}86_XkP|Ow-9>gzxWN6u+C7; zTSP1eJoZ_vZq@lbhk*lj-TK|zT1(m7pNS=EO17<_S$zfFbkxy@vB`+<%O9qDGgl;)_nGx zuYGTrof%j!2R<95+bW}u*}iI37mD>hUf;jda|HgC5J&Nu<-l2*h1ZCh;4ZBUw3TvV>O}->^F|mHmtH zAe`a^`PDqOxk(NcD)o5XV45{CG3ouz;%p<4pxFL?8ILimh_sa=7p|sU%QPo}HYUwO zZW2`DD2$Y3Vc>b=B%Ez>&d=aK(hToz=ExJ)0n>z_<~r({dYf__^!9F z&HJnnQ8xYE^1$*>EJ=4^=RnQv>Te0*s(wCMwYa8yOIE+M^nqR8HRCm&VKl3-Vn;{7 z8BstWXLmnkz{5X>)ql3bfLt$F<9+Zvpk8&m-A<-iJVl_q>Do>2VJ^OdlnIN>{9IoF^%S5u*qvp{J`7X~y`VtEl<^TTp6e&ity zzT16RW}7qN5_W1GTR408_v?+GqY01l*H5qJ<86~=OzfSgPYo~RMY-Q^e;3p!7@c`P zp)jO-B8nk;wo;FTnGY36#f0Ud8x2txL3e(+C`~lG|$sK;Mf3>Hkx0Mw{!eY&T z9qU9tMH^-lDhm@2m3-adUu_rjLy+Eq%WpUW0xHg8_>$T>z|h(55dG4D=dY@a133QY zr+K@^stSWSlvG;c0uT-9o?F8w1XoMNL(51CewXqZv^Fy9p}%)1@tXAwI^R(OwQ^@k zy}7Gi6K`aU6(Zo4wIZxi_m0w_qqftgOGUB@y!Hqq?_e_O=Yr*%biRJJ=NuH zF%vQW^}EU>se=@84`Orsuioul=PSsEGyN=K25?rT(tC+lWMHgKOF2%+TZi7Uv~1yM zR(JDWlD`FPu)klp9~iqrqFJjLGfvNbfH!)2Y(=9Sghf%@eUPOsJVA7U-A|O`fo4Bl zZkaORg?To4%*O*VJGDolwrPm1oW`+m5V}Tv=DBNCn{D@1%xd7X*ZnsmLCrzTeNEd^ zq06F%3j_F-njDNb-P>{#i@0_-qf0?ypv-2YmAu<=8O0=C+ly{aax5Os9kuU05w?+~ z7kfM~D%=*lZ>&-svZ*|Mq#+}UKJ0Yz$|wfb>BQ)L({Z;wc)$?wfDc-JD7^iCED-W> zGXWK0Y5sz2!!I%Uf$QZwegY!J*E3o+*lTIb%%`xYuaz0PgtyU=5)_G>JwHy4^e=cHu%S$*AKsW1aCc;YshO_ILCM78+E8* zVwnP&ZT#KOJyVq4ARL!^OSLUfv{4SZD8vye^5S$mBs5+}6K7*j#M*w)5MIm5Pl5@$ zIg1H+xbJ+v2XXT85lH*HSOz&0Ypde_-kn`6<-px@d6OnI#;Ne>3xwBO0`VX#@gx+& zD)%X&PmAyJY>>pWY?Rj!E&%cEo})DDTo^^E4(fYtU@%=EX|~YsVkB)EasghO;F^QY5Q;_P;D2H6}Tn%^8OjM z51V~9al;W@Yc+vy2qzDDV{7>nw~H(vQAGnKE-$4%G@~hg3SsS78hnuVYD}wQlH>t^D_6x5&jB%jDSl#^>HfamZw&*68 zp@a7u?|K{ZTnv;@um3L>0H=uREZ4P`u_UdAGQfgSz zU^K$^kcIcESCMynN{s*_${L}nVEAO=6&95=c@_rgKaXV{(WBXQ7}heId5$0^ws9mM zEJpU46;T(ki87aalOI-@V;iUO_A@#_BdI84n)=`9{IgF-7W)&J-1)E#cre`V@OPqu zRK;$8C$SmIIJ974(9E3WA}V1cqy#HC2&lu!ZHT407v|8}VAh`-^NL}^xkuGh!bUn6 zj`-P5#KD98Zp34Rrf8$4WZ6ADj{_=qr`&rSYUD3yX@2I-nV$%h*q_ z%BujwxEOF+E-w&De+3^Gs%jgKr&nM&%2Uhy;O`rjQ41MG$&gZq`%Y1R;7?2__xsMb zOz*-=Mv?=X=F_0u=RuqJ%*o7v$eJ!@$kMq{eAXMFx1_ z0`xbZRUV|>H()g0#pD#HiiTq^v6?3 zU$u6hhJJecM>{M}CZeyARvN=xNNA>bHQFoT;&y_8;A{Yc8~H9`JToI!d2Ne_pA+FH z?&cyEws}Qw7S=OmU!Z>A473IJ=YH}ei!@mdNOtzL^arej(Pqo#AQYcI^=riypOdf-h*XKAyolDaPdZN?boncdOZ)JpPunhk6 zV4?7jP)Fx9s%rq>5$MIG+**(%^jQD z>#?7nX6-p@SWhkQ<@gY%@%yGUz6m56IjX82S)fgf< z!UR0W%hXTUyE$uyBLDhJs7B#;mV@ZdaLmQGR7#-&Bwz~t&N3u~0{e*|CPj28Bf1n= zEQl~04=T_m{F%UJG#I5`vcRImDJneK)tuQ$<*bXN76<82k7aPcW2>l+c2j1I&XEUW zdP+a%UiOp)4JS-#3dgS=y>`)?WuQ@1Dm%>#guyueYwWf;Z1d?$TCG*>pRl!dw+T;l zeGd5fP|iLx_|Ef_S2zSeQ=e4jW*Zef)t(r-Bd<=ahH>*z)C}FFmXU2HVWt68@-uWs z{`Zo!%2J)qaw zJJV%n{B^ZhbsLTFFr+`k4}?r?K8uX7mB>V$y6W&aE1Q+d(-O_1tJAg4n3~D7N`&rL zt%JE3?9^(&H&p-hf`P1PnEMe+MZmb$3IdYK!fT?C?v8$F)0_2<7!I zO_D}et64i&%L5sbfFg-#<-S9So2P2j9KJU3XZFur!9LZ_?@Qzp>EAm+B+cY;ff#LX ze*xp1{Y(iwzI4CM)}3{hNTNV9MCTk1nWY;V;#Gdvza#ZzwTt~WBKL>smQXGz4=1pN z-hqz+x43LjHVlS0&aX9?VBgjkqY9wF;)oA5{zy7lTT6A>fyWp zqvNZw<)eHnhly#WJ>C_G6Ml9qFW96Kc?>zD#`+M^E_fj(4e1RZe55!BbEn*k+18o} zt$OS5bM*oy3OP}fx+}G__KY&HghpqzWRo)KWWi#p zl;>6tn(hu_|24f~Su8tNr5Ca|I)W=)vq@5HsRqv!pHXwk?tFr#Uy)b&Z=BeG*3%Ss z#6BKxOLBD+<3d9--^i~sd)eg_G6pijg2Ws^>r zlp=|y)b>zYGcgRRLS+nq?8?ESzb)f;=6Tw3XNpk)ODPLMa z6))3k3KNK<=oI8Aiq2$B{3b}e3AhC0r1i7|XySGzawIPTWF3T#3ipxRZ|KnuaiF1% zQe@AFahXLaBDv5Mubm)_GF*K(PNbo*&lv3yrYoEy_DdUE79l7Vz`1c8SbpM8^a-g@ zQQZ*kwiDW*hn4tIw~{cMFa*U-PhdiK@NI=sZU3uqhi*#5*)RQnUnK1WUBy_>hY+EJ z&yi{1Q+?CMGq*(jPt-_POC|VcfjyAboX`pveNVw!Dw}7U3_}>#*0B2p$XL@37n@Tm zTU{M)CoSx#Do#a%h@_)oO*|FReD<(p?E4x-OmF$Sl`T!dff~(p{?FO_ivAXzCNEDc zsjS1)4_>fRTL^q0x+8Tz8#MQg8*dcX)1Z26M=k$TtpW?t@PG>($;j|VEz~Zp><8p4 zA)1<7Uc?_*mg)=wMQtq5XHges=@%w_W;=hbfKM znHRbI-|Ex_TXF6Ips6@YjJRtOFS4zjgTm&69p>GfO2Q zJ_&gn!qx@l#$ThR`CQs-*L|sE)SUyJ-#_RF^(qEub=iMDsE#KpV`BqHa_~@3xXHjB zMnbK6rkI6hp6@tfrdI9CQ}Y@TCI;*FMaeItYR9^N26o70&6xYycG2-xVs^ITP#F$J z-0&uX)Pz^Dd0h#ohyzb+UY*MunI|dsl4kv07D>a6^5o)#$&rxDIDZqFK`R0g@ z!>Z45yT~EJshK41w?ZJ?sQh@5T-0$pQP*i;XGyqF`w)AWVbyZoqGNfELe_t&Yp-ra zY{G_bs$c*gy;ML97licN6{hyasiIp+yVm^h#gU6?u89|}SwxcsH);j#z*m=Am8b1j zH@+|phIF}Rw{qABu}7}O2(!O+ER%o|R+$C4<}z0B&V)8MMnURd?G!TJtkSj&W7-8X z*$7Sx;*0R_8>nfV3g!6Gwh!EWbvNm-#i3SPcu~PQF=v`6y&nG^l+1L}cKBxYF56lC zV^F*LQW_T3C5v%xqKrBYQq(h#G%t@d*r0%z#(wg{lG6U=w>uNiA486e$AHRKbC;yh zZRtF}Q9Zj$6zDuD0J~IqjXF^H9Mw#sRf;ga<+Wu&PhZXv4ut9q; zQZ5Mdt{e;}eZ$t36a_i5dHLRQLmpZl0p9pi`U6x-vaS|7kWaU-@}C1T#SFbV2Li;O z8RTML;fTfdVt5L|ssNSGR-9{JkbIR{DqbYIVb1*WL$s}$6}ii%ihxgPXsxj!eFW%F z*|xPzKxKts3wgD_I^1uvp%(30BflpHnJLm%nF~@*gKv5;pmOwj`=JM-QD3j7Q_sDs zbqRJOi)usyg$5S07z_ya2&QB&rQ1h_srX?sUq-EYc-g!G|D^MY-s@DTjl~mg^;fbk z3g?Q~Pm9uskI$Yru4w@IYy_KndOB(FnwasJkX~Wgy1#HDw1}b&#c&k6Ke-ExT@)n_p0c)*e|H-T44ni~8_=^f$owf;HUteZt~+-asLBSaUXZsz=Ykd zb4?+}VCK#M7XHdW*c&;-w}TO$giAS6*={3AyWVl)MGks6gNh>lgpN{(Li6&yYS<_t zx|rO(OLUDu$6#^WpG=j4N6|1`)f8J$s>?cWhq<4PBHaU}6+adFU;vQ>1daG6fKG(+I^bG=u?aX?6_s_ZN8kjKv9J^J(+O8vP zK7H+BXEF_|^%Yum0-n{RD7Yy0bzgNJ$nNlyd-^*zScj~|aCi`V2||QQ8e>-y8pz`F z0cT*0EdIKu#HWk2AHinq{8O}$C_VvHkb^R2o!fNeBT^e9EEpxh7F^2pCp7sT#kGGY zGQy5}47Mbq5dQj${P?^$nSm@58a9|bhUP$>mW$_bAX*aPI_FBD8^pkTsx+=5Cf|Io z6iFQk!RK8I@Cw>Wnz&+#n-O_mhjh@ZOH9Ay#^Zt4n;XowA<{eb3dYR4h%Q4kA5D%z zUv%fIAS$TAMf%^15>x(A7{Uj_;<{<64uM;+q=LZhG+lk(@4#1zbKz`Nv4qkAzWjX{ z++TmXy@XUqiN!DI%M7S+)7ujD)(ZRuav|xZcMMqTv5S3CNiZZR?NyUYBXmz1+$d*o z4A9)8*igwLgmPsZpo1iT1iUqd^ii8iQ_02mwU|)RVr5t*^p(<^UbR9~&Zx3E#z*0i zzEU_(=2wOZ-msjreFn~*G zkx^IgtrL8siKJWk6KuBaP)@Z?3x4tA<`01j5>G|*%`f`IjYH<$cMd{gLnXBsnKG>U zd6p(HDiW?KpUl)@cNNJp;4SsNsd2WR_^F`H&*-09K!Rz7QVEgjP$9HpefjxaH8UNA z;Abf8V>jVnMCQ*HSTtyAf7o0j-xYri&nY8$*g=22F*o;?o1g0E=`bb~+l^3{tOF>s zEtL_4j1yi*ZkwjG4(vG%3D#r~1!_sR@^*7N^bCizTCZ^KbAC_+THIm;GiZ-sypo?# z^pR5HhYMjsqCE|IHrP++A3s`Tz*i2oL4=XnYZ?*6O?4X6cel0+oeY|1D^6#Iva`g{eXo zQ;7ypg?z%mAXRTQmI1+-4cdg8PqBx2WiMX-=B!aL=#nb0)v{ReN528sFEf0bb=|oN??XfM$QzeI~2;S|qc1k6BG zbwdcDawoszSs^gKC_>YQiquJ&=p<6K_Bn!4Ip~DU22m^>?SQsCaAtt2y>daRIUwy7 za;yqPrfGjn$LjQ=H3K*XF5{ZSaCY8)u-&lhRmtyU^4jTi8cT_m6v83!)>|AFwdk*M|1PN=O7@7z+Mo9w@MW*H0GF z){KGSOiGE(m0Il|yzja-dwH{wIZhfIS5=OQP<_sy9&)?I@H*-or95#A2C^yS>*ynG{*w#J_&EtCHvV8t7QCVbwAzpIDKB-L=~dv#|tA!6XimW|+E!xT6%@?2jB$^`RyrCpKC} z9sc1pBTSpWTKlzn0#~aTU%gZ|A9a?NJT`RT;AKb*S58pgR&j}1W9@B4il|C-%e%Ww zwy#jo&94tM=?`n}(VKUU{}!s`*l{tngS=4U|(k$#&%$4B&0f??ys{X;b?Pq_PET zcpj0KAdv!2!=I`P);;7R?mvjLA57D(F6j+c-LEHMzPB0r3!qs(;=TmzH$_#gzKkN6PO zC!0x_w!o{L3ms^swG(zW-CRK$m1Q}K%p-Wo{Y)b9UVc*60N&2Yb>?jBHYpu&n;hT; z+?3S@xPT_m8frX=o_dYj>W3_{;%6V>oUUnjG8Iv zMk(?*wE7DT0`$RlqFfxP{W@vy5?)sW5%dZ(aSX-_q{aq(V-ZUQ)!|YoHpOc2v3iAH zvW#7Ua?GpGqy4rpap9~^VAO5%GnBXeB8xPoW&zqq$A^#E;5^N((SxsxNWeV-$!Dvq zX$$QZ>Q+Lu*QQfwo&k`AaaXbwYvj4e?)!8G^zn>Ji=LF^7INi}*`O~Y+smH};V*MQ z%DMvi>4(+OP)SmL-$&eN7wI>u!LRkg^DVVL?~B^D&PCJ?thnS@Na*|)#K#_X{j&mgdJg{vdcm zqm1TJj%l1cSI>&t*oHlkWzOQ%4u4ElC)VB@ZL_>({14jF$Z*IjK#|wYt1RL%00}3a zotMhSB+y(hER|)l>uY%ygfB>ag|%LPoBwzZM&r*obi|TVr1NwwltWb5qMKv>(xVvh zQC1ym>p4(io?rE0bHW?}^t4Oa@p}mUHLbuf?`2+j^Q4UeV`M|zl!W4NdAKbj8qR6R zCswx$^MAX?x8i@d`EGx>t!(|LglRoGA9q?| zKGT%MahYx2fP&Euvk#E`KezQ%S!DN3EC4G{_3@^}B%>VCRmPrn`?u9S1C?f~#cayq z_sq*rkas}6Fd~PJgLk7~j1TqCD*zB&MwkL(8s0uZrb2;53oXYC{tBn|N-X3KlbCoU zYBz@UwOhB6)m_xD7NVw(Y*0k3K03}q-NJx-yAToC;!S$MlB#Ps1%@M)uQUS*uq-t9}kEf(2P^oO3!fdnKe3t_x>is5usODH0>Khb7 z==@pV^#9MAp^#!F3^pcI6a>G~{!%^EX~){BrrAc>^M+^;qHc-p=J5!3BJyUm@wXq%k}(jmFo37b(Rg50 z`hFZ>u_Je2igFkFRw-cslqgef-7^?I82k(JZ|#_g7e(vTV%~@n{3dTp@_b=?{e<^# z6SKZVY}D=P8)?mbbi;Npa}Y+Q=x`jO&$&K_1ByFWIks z8!H9UE5^pewe5{|kW~Bkd2pzJ_to>}k9bHlN&-cV7QB~6@vK?IuQb>s`F!f-o4ERA zwc^vVh6Zm#($8M1ub-95lFaUzpba1+^fg3x0_((evLqATw&WJQ_@k%sQdE7IN7;3936e1si!y@@ZSvn$bRQchpxwwc zd3*^vniujqY&A)`ELgD)h257!LjkaX$czi^MU$m&5(I=N?Nw7*&zHwR*BKd`iKe*| zbfgaN`eQfu!i!xBOf5#=);3Qx622|!`UdE_>@_8@Z+g!7PNVJhE1(p3_KONdE6_nz zhV;MJp+=1$;T%v&k))Z=X;a1NW|`8N78(U^Hbl#9SF(!n%Yt2g?_#wIeJ>w6R4<1O z2G;mxKw7VgR+0yjuSCmdl|R)8R8&E1v15H6c_TU$gz}@N{XTICz{;v@73mjfW1Ui3 zoy6DgaOgqE)rVIIRZC(^LB6rMpfEzyA!Eq)17ZmobLu2NIzy# z=xI)taC)^@Oy*@~<9ENO>bFTUroXSq!Ac{{#(i--k!w5gXqrYJK|`kR{@P$I&a2x& zOB0W-=poDj$&oXJI~SP|I3;d!{y1r5e)SWT1XCyTjxW*Fzw)R4hU7pg4c>&3C!^r^ z67-=nsiK;VdChv}3|D+%Z>Eiy36Oe#7nQLd8&b2uWTnTWAfE@`ISX|8Y!nXthi&6o zyMeF4X_N#uwG#-1vHdlCZ3dl5o5W--XROiaPLocbR)yVwT1*|Vdh;ak2*0Ovn z6^zESm9MOhs71*veQ`V2X+S3SR`bz%-Oq7_y3m*P;jVBR8+aQ*E?a7=a|K43eA~S`6e;& zD#{lLHnJ}rN28_E&R9hi@s66WwjSe|{UA#Hx5=hWRBEpj*Y?KGreL`*FAFo~{MMDb z<#tm{gH@v-6))62?+1s4j?~fr#WC=a9zk=I0RJdIS`DCHB7tsr*Qmi2Z1A&Bk$((l z#BUsqw9#|cQh^QNZ)*(#r4iG3l6 zoQ)5YZ_>4qan=%dx!v%(#?WEqGm)fkH8o|tEJG|8Phsq$YPUDQuRtDQXx77%Ny_Xs zUi){|e3Z=m-d+&4*i8`SgK2$jw}Wz-fK|}RughN$DLQ*C$sEd_q#MG!Y$&746^bJa z!*ZKhV@^<<`jN#eA|yYv8k+JU6s8UbO-!}Cf;7mmmOQIn$dM9s>-b`=*n(T8d|vxR z3Y^KJN&+i><$R-T)ono^^yiM~9SP2Y%Wsr4=Iug7ZVc2o^e~6sHa_o?kY`#^a*1^0 zZyeBQ9Hvh>%?K575cPEdl@~2g!WdSzrGR%){wo5mKpssf$oy*AokhykZOU>z)Zr+@Nzy>3ZP$mv`q5sO=lMCuA@i8S%zTzEC+Q}E@4~V?H6CytHB*b zMT|0~SG;$lxs|79A-~D>e9MtSMRwDjT0>z`mW;4;P_`s`wbGzs3Nmi(jcR6TU=#$< z^6N)K@eqDh&-utA8pI+B0IQCL`|xp&3Ab2My7itYe>cH;InBuq98XH{V!3$Mx66|P zq{MR&dIi)9L|J^%CePpbJK)~P-qTrp>T<79@x=<}(qD>kv$45nB&nRF%lYe~M88vQ^IL3*=5t)@@cZ_7Wb;qS@wn(vMGgqJD~|qr~%ZE{=opbf;3MobhqgQ!I_W<9kDf)3$1!|_1oEpnwC$x?1kzQ z*tsSt1hYQ5vU{PB41n4y9;(oS;uRK}g~L&f7pG{F@l7GvWJ^US5nu-T z>fQL0<-n#eZ2kwrD0>ZE+-W8um30%*sLpz%1h}*%@bV55AIkWJNg1PoO-oZ}vN059 zC9%#{-)v7T6a?w{N}L>w{B2-aFN?NU{af$*4;PIp$;BSom=!&6&WvA*S5+m63TasJ z)vN|H41)(>Y_ta;X?R}wRlrUpK!9%wT%>|cgM`GUZ8K+?JsU!ii+lyyC1M3{nFd|fs6panmpM||xA8a;@{|>CML1JWylTr`5tqeD5=Z_?MkEMIS zk~%-2=d(G_3~KW{#LrNd%9e6+%+@;mV=ejE>;}M!?&@(aZ2A6otY#ITK2w4vGtGWO zdQ&l2FR7cv2~LLWhYLc<_Ke@>`xUb8=DXQqFScNTM0Sgft>&=x{-S_$9a9-0pxQnw z+yx;u_>Q+bd;JToLuGUqmwJ%;h5EW3%FJlGz8y1&Q$IoO)53UYauSoKg!^5iA@?i< zs50lX92PcjtG#O^-ph4zvXo!54!yZ)mc(DD?<6!;w3xQ1Nbyo$p3m(H8=Ix#Q{ zCm8nN&3=4OEGu#_6+^iy^+b|AYW_yFf)#7wwz4h|fU&e6QP;HtNu4?I{f*{QE5geB zDwVgM$lmC`;#(rgmkM|K&R4zg{)fE1q{X2?*GOopW01&@mjgN*P)fFJ`)xP`$^|V| zwh94EzC2K`z#vu2YoRP&H30T@jVY<=tr=s4F*y7jsO91Mar*YdAlDt*v)zhuPCpQ(v;}32`dg8xo%390Z5$rWSGu$`>~_Bnbg%Jrq-UWZwEnA*aUVmA=5!A2knF|`^L)Tl%d;BQ_L$Bc$!qWoJ>f4z#4O$%?p z)-c4$a@9{`Y$7-48b7&p(%X5n!C#^j@~HWG9|6W?^|x>g|!w*54ol2vU8w#c#mZYkfF=7ZCg4Qyx^S@B)lQaSiS*?9*@J3&$>!%SAWdU?e0 zUHZ#xum53n-g1BUHS?fDP3M@NiU}WRdr@S-8fHE%uE6B%{7u4kLnus?O=&J`WWfO5 z82oth$l$)>52pwO$O%z%?^M-4{~wyJIw;C6Uhgg}4N{Vl(jna-ozmS6(%rd$(xG&B zcXvr6Al(fjT}tPDzkBD-Ftfuy4D;@J&w0-Cdjj&9fEC^J( z$3Sqs&W3E8H!rTGmmGII+5mp1%OuFOxTwKKWp$V9^cQn)8GD)pp&hPqlP$Bzg>ty$ zau<$dTiJnv23aZKKWX`X5TFYqQHE(oat4De9Y<4AcUwQPbX~hXkLy2;|fqT}hK@p75|-c!UGlrnJ;x^Plv4S;W!xPT+ViAX2gNn<4}6&wh&7pU7aU@k9%mXo&gnMnr;H z1;?obUGEwUD)PxaI%AI>m=T}_97kcU>G>b$YLk6_Fb|si6#Q;wd!dpD3~*^^=2mAS z4Amfzs?k{Z`+}RRvh;kyq|Uoe1v4j_JdhGjoSijT^Dz!m*f0*L^=qI0lJ{(~DTN5@k=ZE}&Ge@%|(0x)4O`5;0{oDX)9Y%@t;)li|!*z0o-tB^+B z-6ju|$;Q(#$oSbv17@AilTbw4l6oBguYl#YBP4m1hp8_+p#N5;U!F&PVbT;&`5S!f zE)se%wT=YslbFo79d2&61nN}r?a3Di)4qf*TG74C$j)v@y)x{FKFtSn2J8G@V3qyH z6EKY(jLt8h8wHvJ3_{uIWD_?ivnB7#kI6I;yxYXJ>g$r`qTY(+Pg@syp_Q9ZNqCzU zS=@CI>5!rZhj5YMvIjfPIM+-HMdJ>CZj{=nxK03GHk`Kx3oSP6-UBmH%0UFbM6Zl# z$T$p%b7chAp|DJ~nzfW!WMPtq^wq|@5#((Aq3=usWSmczhx4v9!epV%IBA^Io=@cH zYlx+%w*24-d($*_+&GRWB?>F;4C|mIyj*c!7?+1=@3Q>zPp1nYJ@e?z$K%N8z?bn^ ztQC=;vB7q;3o!3XkhKFE2uV0-gtba;!c9lYn?jPO{8TiIQIe{)#8~uTPIw^| zS%TaSZK&1;{MYXO{Rn#z0#TYn>Zbn{0mv?mY0H%_xh*i=XEcU#*f|2W?%NRg`V+V=#-b*EbtV%gfIe4*%qw{r(Y!rv%SfShkbi z9mOr4BhJl&3%3@fUTkxn%sz;~T2O6p{(4gTx~*$eF_O>W$Q-q6&y zi#)zCow@@y3ouBI-3I*7)33pJf?p?dBv-J+#{2zhN!c{S&Td0&n#~h`0;#aD3Bpu6 zg_m3IX#@TvDO-y<$LX3EHR+8TOxrI$$^tG^p{uC zhX(lKN4$#rnnBQT?p#6hoW{_T^tOuz!m*`-NMbz>G}LlNax6OFW{fk-sl|MB=ylY< z7MzqRXeNf)aev@Dn@N0^ugfL1H>3Gn@CL5b)3#`OI z)VUIb=Dmwux#y+{GHg_xStzE>jo3X=3n4PI)Pa=BgP>4^AcdY?q8qW=I9uygDoJoL z0p*rpRIjUTYM5H23R6WyQYMoNX2UP{au}>lTg$>fHV$00s%pGg;55qn(mr-~a@#qvc(@f6L zW#^*O(C@p?$lmqE2>ksq1{*m!rG}4R5ka|mN5`o`lPxx|g69&1Vkoac^A|dz)9D@vHY6dc1fR_uRZvtUKwJGR&bB9O~5E3MH@(Ud4b3r7O@_wLT zeV%dPlvmWyBWAn@;0$)k9R72-i08TRCC_U!87SMp#_)C!ai(k1IrCT2YmL^od)=`a zi7j4Mh0-Q2w2uu;HA{~rJ-RRyj=^vh|zljc~xKcOC**IfAcEh-8Ea*3jen+ zB_G$^9k1T7#N!ctcmeLVQxi1Mgr`RvFez`{(3#((JzS=?{V8ALRsFw`j&Z1Nc`VnL zn4~pz`r9>K-%H@SK{<+<-uX)f#<$jWT^+Vxiu+vy+|UFHLLj*7sWXiZ&EMTxhbQEZ z&^F`i?rTSwe_JND=(iPycXV~^S{xuasE+Cc=(~C&nqqZil?Bg5z$}RyCZYvDnljQ;kvN=U2%Z%@ta&yhHZ_m z+>}C>7>S!e(toOy>i!#+mNr0n3+qs+@6zdY#uZbMOBEx|v-3a}w&4-GZ6f3t$5eC| zG79QyI`4UDt{IEgomkT0QxU^rqFQGNUGoJ$D-R(B^20!Hz z%g#|$5p8w(m#>`pp5tuJxY6TRb0>}yMWSoqb5KGo8bM&=VoJE){;-sD;npPu;j%ZR zB^K5RQ*YHc#iye`{OboE5^jzhiSq-U$OfQ^+8Ozpg2Z|J_-@}){|OHev{&|5oVYbX zL1x}qpaossrXqWyu^X293le+``l@DUi2`H#C#9fWH&z_a=5U}~&1uy^k#6I4X|A$K z1LhYgZMf9{eW65g@(_%B?{nSU927(**~-RL9_ZJGz1;sOko9{4RKSwa-X3(Nce&BgK zQA)q!H67^Z_uUG-bInz&3tQz*#K_dH2)*$a-|?=&GnU8+rr+>VVOW^SQB`0Y#u8-E zn#)0$KvW+3q2f+wOU!&Z(s@l!GSbV%s4h-R7{>4MV-9#t>w@PktO3y=V?DkPmsUmV z-~Fvo zx5mVBrvBL^0wdpT!axk>Cc3gB;!Z%nzX3ilN_P;G3`>w?IN)vp7_Iv0 z4u~ha47v?4b99X5OUoz>Q64QIpXEH96VpXxt`llmU|0Ai8Q{V6MzOi&jM3Di`m=cp ztsbb>nkf$7QvY-0;AL4nuH=_PR<+s<_IcFtNMI9&9uz`H_r9y~M5E;6}#I%E>w-YRp=AwP+W7@UBnH7c@U%y4<4X9;-dQW_Gj zBlfs|uw8ND@rEb4o257((1k%L0k7-2f6d3%gmn~DKP#b5T{V)nA&jS!Z|vU0mftI+ zWa(sS8}b(&n--p}YdwHMx!`h82>w zC<)j>7z?t~=s0h#y*Y|5dRYXshYeC(A%gjLiU0BM#fFJxCY~_r0!!C-M}v?E5oYGz zYvJcL&*Nt3-PNqprt>h#ge6XBB!ay;MOtbR6ws%%DZ}8x$6_^Bc6nnJxSUx}ej9PmhxO8XkxP~5_Z$@8r!V_sJ4^k77V!20@aLscv4h-}n6WCI?ef~c$kQu5`5LkV$PJ0e1i#mhx29O13iwD?xD{kz4BzY;H(Tm)d`cP}s! z@Nz9d^fqB|QMd1OQA!Yq_$C~fth}d5y)2#AYkFP!XG*ddMxi>rvthiU0Yk{wzvre% zs!S%zY9(^54N2NfRLJ7+&Buk8t#=$AWc^#a2$@BG4lP@REpaON%LM0v>$)6zrw?p|#Efk&`5vEk{-R7n8s(l2n_~)! zS-Vw~^Y`^_ZChK0fg#7Mm8BEm{?I>dv?}*a$eh0neuD&9*B4t4=Da$Sm{>&ai7@=m zz^1mk6Q56Jl{6Q5_`obFuyZR%Yv;-)NPb~P1x>fCP$KuFD$1M3aK+S5Y%zVXjtWUo zTE`|>?sHQ!#us>jQZu(Nm4Sen+tT=PA{?Ur+=)OVTHSo*&9T>Z+1U~`1_lPcK_O@U zVbt!z$pwao(d3Y-l?Dl`Hc_Heh3SJibzNPUIV4-UO-Im;6qkHJp;wDAJ6b!B#0G3A zs0XH`pI9KwJ+9u*8w@>G2n~B!FLm)jA?Mzcl43qeFc*Z@H0kQ0dy3B%=_kr2Zmg=V z$0G}Sw&P;oxkv9WyY-HyO#9qnxNFk-II4-%x+kRKhEw#*wkIq%3wJoPPXrI3i#tVf2)KG6;8^YyGKlYnsVYmJ( z^b=(*nvuR&cXJYEKd@3I_u@0k*1CX3{PbG~qA@MKCNa#@UgkkYpbH4V{uk}14Iz_AKLJ*a*2Y#YB__GJ-0Y4s`J8oh0ONdLHGL3p zy#pGqL$Igabl1t#p;u8P5rS6R#@hZ|oUvoZKA-yb%;Mpf(yx%p-%hC4pq7a~&v4fG z=@heAwdj0~ud+9}b$SUYcb!yM{zJIyXD8aE!g9Bhb2cqVU1DI(RpUHR0>~K&MR~}M z)9-2TLahH9vw>TzV4VAI3+&te@Mmr96}o zVYf{&?WF&$(rhxN%oB^uz!5}&Pyq5@odG%Ra;-W7SLqWam*0=5dC^%|{=?Sn9HKa* zMcwrySD}JwMK~g35ouGxSHjt}YHEY}a5J#Mj-N&c4xH-)tFlh&2Bw=XIM6iy*>F-s zJs7@yIf#SAG@S-rPE8b?&78!i+}s z2fn7`Fg`l?SoEZZWY?Ria6e5JH;YjGuro+Daz$A+R?wgWHL0BPjI%OhkI9# zTh=4^Ta+fEvjlv47q!vOZO`j-J{^$V(WuR|+ZqJ$8Y@VO`fQwG} zPjlKlJVJyGw?RM364d{qqyet4*7+ur<%SiEEF;9GY^=SxJnXwdA(y$or0U+8H5`FQ zE`hUptXyQO3p0pq+zO}5FqQQ7MO8;-{fJ)1GWtg0{q(9yD~>GcRNwpd2oc1>-7`wa zVBb!ku`S=X<`yImLY_>dL~AgDAiG~Tt}vkcHGQKv#^kL+i~7xx4AMpz!t`V$y)fN} zkBMl#*z!F-$i2vpXbk*g;fhPK_ODW9J~z8KSXWZ2pL3=|s1{c*{%hA{HJZSemZ7y# z5uYG~g`|t@&t-WbN2n(k0fzFQuO`Ht+ZsW#jcE>1)kQ~3j>R7Yjvq7mu|}CaS{3zR z9v#$Qvk0wUS$EhV6bvV0Y@S#_e+`@{wAa&vtDsXe4@(d`aIX%|S2^0k;3Ni*VAI-G zZKQ9n^3zPXTdB~2vf;#C%0i}OIy2sk>g7v8x#yxCfs4KYvY{s|Li`6)q4!ER*g-pR zx?#F7F2q2o+wUCR!9rk1=y>Q*^tQ_angceaa_#;v0izLH=C=jXs8AVxZH4)61OU8* z-l5KN)HXAYJR1+R(T#CG`_^*h!?R)fOIs^su$~QBrI1(o% z<;+_AEtCeJl98S{U}3Ob_kEqCpYfw*x9=+KE^FQW!C8!}jo zN>(1Jw7~;NlH5#rw6s6-<40~3%=g&YA@NKzEi0Na`D^p4OxsJ=b*oQ3Rfh)#+GmLb zbRsj5=rD*|JL5Fpc2w1#s-k`+Bfu<*2s$We@F*ngKA^3XTEEjoyb%73od@#e@I2i3 zhouZlWKSHO3f6_uuriB0y_!%$nv`K4_XSmi-ATd!Hv|Brwbg;UAj`;wb-n-B0u28H zj7l+?mOOZkomQ)sa>oHs#YNrTacRf$-zHAsBA?oV6EU*B@8VgsEzslkvby;3gArBc z;}^kS@XL}JB%qj4D+c)>dQ`fkAmsLaW|NG1G;UWdemW7FeNU%}qSgHV{7xz-GkB@A zYk$RAU)`-gd>FlRSBAX9q+xg>E6jjv40rDcpe8Gz1Vmmy^Dq}cYjFI4bHOuz1R_SR zBU$rNrNL4`rmaCeggk>-Y3|OY>&WnZzw9FQIG~?RpWy*hh^vCp z1N9r}J4p`meSF%+6TDnU_ElB)=tP>x898wS>(ZNRfU8+Q&uNo-CxiOkSsb_u*)X4m zY_1>zU42Kvx7|0CPlaW77$_MC?5Q&>l*&x58NWgTfh36^0iVl@NX^>vARGr${~ns# zKQ@7Q)R6+E1W1^BJ5LC-G&phYaj{-$2TFcli+w2|-%zYxwb-c4bjnP$RM&1;(YcV;$1c{RUzW$y;zcq_g)UszvqF@Vl!AJM#)I4r3u$5ldG zt++xh{QlG-#IB@={0{R}yxZyS3u-;kg(*@h2fgHV&V3GAYbV1xFnvdvGB?Udd2(M0 ze+v(_Qd&pAy0UJ616{yW$*McSY0TgDEkY9X1WvwJDj1Q~MFc$Jnv-|e_$M0ImP$te zUvyn^#{yoi$#wd2LO@NYR&}zQ`xcL_Y**QxBL({p4zchq)S5)ZYgvGB#7SvQDyrgg zOY3mTKk#_O6fQ(+oz=B04`fd%tvi#ivEruZ)*1sy4Xc!AQNs+`4>$HX*YdYmzwfUI zrNtfkTm8@s_9=yiUyy)Leuy57v1w(x{Au+RJF2C4V^w5rpabkmBE!3z&Ix2j){tJE zUGGd}RBN!*31#b^@Gg$bkZdsLmpoNRe1cD6&{%RD)&R zoOYNN`AGrAd@7~}s{WIl;Tpfe%Br@G109`}m{Jk082nHD_gmJVX4M4MMyLN_<5mv+ zCE@)J(}i(70Arc%w0CGDgR1Q6$5h{@bhYFt>*e-r&{`D z<|hC;GhR>9wnAC`5MuIfsi`in<%QK3All#sLd)=rh{c!`_X|Wm>%+zat_-&3fgp3% z5^x%MeH4rz#*)|hJ;ui-P}SiuUOty308o6<`#nA9yk5$%@)F$L7!y|WbUHcfANB%g z)dvC!m%n)%Yer4A(&aEwoC={!?>}`9)cEZ&_S`hp=yas*qV?Ym(0;r;((3W~Z?9f@ z>P31BG7l<1thWa&%FZWZ$}qJ3!g9EfQ8Qc}Ur~4lfD|jhPv5wSwkG@NM&0RN}Ql(b&}^>`9aE>@FKyJ^b7X_V1P39MHe;@htbzd z4k&mw3;}6$>+iQ^;Rb5s(!=W-7R0~vfIQ0dKu^pd3@ntXf)H$vqLa*=$1FzfhRwV= zk@s=SU8lhB37fo|O`Z65bp7PAxh0GO=T{>bNw|RFq0fhG!ZeS5AE1KL-}DhRx`=@r zuNw0-kqZ(2DLK+d!KD&oBRNhKK#|y_$GXgoJYRNjm*%Ek`tR=aw9TIH&WsH2F9qIY zSBnxAIChTzXXI&@lgv>1Z&EEaNiM^!5u@PGZUSS@>U=VQy=DKwj# zC;Y90ka{%yX?Hw}yi6QqKKtmT0q60Ee5MQiJRB^mrXo`@|HEY*P;Djy3ah!d^Q7pUFtb@D~g06`IEc#61gM|XqrnKEoNVE81@zMX``?o zo|~)TK*Q6wlW?%3ILOs*0gZ6kH~rrE9Pv$+Zzn&uL*+gspF3d(-6){engLZWUIgN6 zhw5Dcdod;fcXtsM*z84$@I?Nv@Xv*g zy&-1QcAgw`RUXd|BlQix)rNC`wQP7@t|fFeB_5gYcOXvYvlBs^oSb~tb-Mu=>zZ@~ zAK{@RVkWrpt2lvtnRFsjYt+N$yy^?ViZ>R(AR+63je7{?fP|ZQDCqiUGsl_#mq^7ovuu-`($lQ}0+&H}f80oq)Bxc_jx z*?uR~a&~&jHcU6tl;9td8~bLY44RrgBf(zXv&+aVD7~!57` z#){+PRG^&m#1h_-*Fw1r;wQ72RC^MVznWoLUDhSyq?eyP5-uW9aDT%STaAJwl2|v% z0m=dIKO`+pBfb(HqDY`=Lhq$&((J6_@-SO)Xf8-4{Bo@f`{h_pEw5mlHwa6W(TRdt z-#7jx&qB$i1sFD*2VDI7oRV>u^ZMMQ@3Z%n*z`ona>Tto5e{afhf1M1KGJTTKM)h9 zBWYq&--^)$x=c_^v54LM7Fjl}2pF08OWK13@b(p#NX37XFBg0yCWN+nQ!2$dH5Dl& znN#X8Gqg`raqJ;KK~caCS@b4k4$L5EDpnWbH1f|#B)7a`0-A6^9s`=J2G}JL{I7Zk zD^@)iE|7kNuEDY|u{pL4OhddTtKw$bP`CjqZQl~fSTNQR?O(~Oo&V>2I{dvvmH6pf zr75NMa1m!sgs6OmhJxT38~lcq|6Ywxo&JwEz|ZMY-L89$uR)h#;F#XV--CjFbardtaa3K+`cz^cO~I+fC!^DKHq2Rks9a$_Sw$; z0CM5iE6;dJDJ>O43-kFCtpgugrtk68 wNgb0RjeFxaF_1%Nq)_H;E>UUjtih8@< zWr;(%Ab}5w4yjS3%TDE5oJb0u5@1FC2$7T{xkP4M+cWmTya3u$y{+Uabeu77fWCI` zAGna@k>9ND1md#3#xZJ&a=af%5~%unkPH9(^j=yM1p1^qV#KN3;u9?U8dM+lh6S#7 zK4rY?vVMX^AaI4Wmkfk_HMh-GeX4Nuo?Vu~Wy+CRgnyCUAUP^NJf$<Vst$v|p{j z{MX4NNcBHR?Lpdq$pv!sY=t`3e)D-vwf+^J`){XZcP-(_16r$w`}w z*BD~)w%Vy67PKc(ZAgPd>MoPpc+Ls{Z zF{vto8erIAzH}<=`F`|!i#`r<14myF3^fK2$koFhSqGiBbJyScm$dnKF>$5;nS#vu ziAQ0f)P7z_x*0h+IRR|efDbc!TnzljFH#K{KJZuWerh+_IrXzE$|EkGw>OOtsp?Eu zbLUX|PgUT++zaGB;M?YGEzpMV?mCYT7vr%hOrfbo(pYSXfs5HkEYttg54I1XnOl!G z{s;F-@FVv^lc1z~gz1rr!ZhoG-K_5iYx1RK11@T$=OFqHbfL)a_N$lQQsw0xgiN{B z*n-edFgHsqQvt6wPMp$0*|*n z@SiWoSZ&bT6bXKVY=ZB_xg*s1am zTu1K-jD(ERRoWDj#?fJC;xi9)X*6DT=;YrNBW&sl==X_44=%9eR4J~=xJ^8qjql~^g zNl_9qOhcVrG%TxIUDzmmf)j>3-hElTKJq+cc`t792iRQUeyzmg!Cqn#$g zPa_LN!%VWh@>vL@-^_ma9J?WVuE+@~P);e1Ww=VoolRO16c^N-Y=7umotMJLS{Ako zp>X=~DK78mBWLF{OG`QqG}WxuzgjvX`ar~7$6Q!Bc0M?Z!PMTrsH~la6@H^fQ)Hh6 zkhr<^<9fw{xMVhnq9ISq+ti>|FOL)G=NKVBbHYvWtC63qLHkTkWW&yC)c5L5UD|4Y zhETiy>m)goiVictu=pW<3Ku|Ekw?Q$(S+-pJt+qE0CwGU7;Ud6hTS_sm7Q?s@1dAM zp@K;8;W=C?Aefw?T{(a9oN_=@CjQ$fe07CCES1FW#a}KBo2s@i-JV%ze4k|DHGXMl z{M2D^MjTpq{FP9l09xX7cr3Od$0{W*pC(erB_DR)>ujA-*2<8Z+H;ycMO2J0TNrHr zS)CpA4f)(eHxgONB(i?MSs(mH*XMY*ql5p9^K+~jhsM+c!4224itg-}^|VHQ@l8{U;h9=zH-x38_f+^|>oFTfD1C&%Md+2TbPqFlPQAs|~v^gP{(o zSHTXpDzYp(ZN`qc87E~`O`Q5MvL1gE;bZFz8;(qLf`IhNN`kk;&XRz(~#sS{`7a@kn-75R8b}%-T{?wJ>j6E>r$Bh6ZQtP{lwj5PL9v@Ao1hh zJ107LX;t&@DgXKU+Go6fQsjSENy4@C@v~1VbC^0XHKX>l$_x1AHtH#h*zoiPXMvjX z3>CC}r2hfcQP8P3$aQJi-9rpTbv@Ph1V5+S@{7nDrAp40iA3yoN@DQo|NLp!orKyJ zY|5#+?&~Map!c@7WKuc*Wd-++A$FNV_6huz+IbgDp``2jsYsfZSXvPgBJbM+eiDXH zcdUP@O&zr-jryu9Ad1SmAe4)>AgX!*MuM5TML%n%8|pSYocEi@n5-eY?s~`WUNq~N zIS_mJ8@iqSUh~@U1$7y~FQyt#wbFLq1-|3GPx5^u{)K$XbJFklyBVlTmsi7u{xP?iecjFd%G#63iUH$2%)XTfjjMtD; zMjTx7bGZtQWTd%*q7rtAT(Kv-+$bb<%IeKWx=RNvuj4GU*=ctzHC*z5K%gr|@$T#I zmf0oZa}Hs?yDaJ0b*~AJX+Wx`0?WqR5)VrO8v{|>|M{SK>*vBh_Xoor?7F~$In?Ou;R7?1oZT8i2dJxwF90o@e`DYdaBu@HT z00bD>ES5 zzq(nkZnIjh=o+B=57NQ^1ukUn$ zQ0b38=7fy+cX=rF%J#M=>egO#hw0iTU0K$;+N%17MQSxyZu1k6pO&c8dNAa^EV@r! z>RN1^Oza@p^S)sQQXrAx8c zdi%a)wLq?G0dub?z{87B39+M)sxpoT8LQ>%_{M4P53#CKpJ(k6g9i+jP1Vb1JqiU3 z`I`&8zVoN)Mbaa$ZRtSOx?oHR@XU~`C|+Xmcf9FHhg2`bkFM=6$NQ5=f}iVximIUD z^XQAQf1hzhQvxd!2reTAG7gvcXDZ9omJfxOCV*^5NPwt3(M?D2Uc87lFI7Q4o z=WU-uvKHF#bOJ(9QZK82cPX)aAycY=YGa6iY4-kIRL`p#JlAvd7N@*E4squCfwY<#cgxmO+O}n)$Nxe`ZqA+L+aL9< zOYL6bnHbS@P|7`YXk1H0>3ZiwBYlw_y&R3&svh#9&_bvQaG^X{bgSgQc|Q&Fd_b8> z%5TP9f21qxsB^I&%^E)ny|1vSfJUY5%86SPq5M!9V?7w^|D<}`24Ttz$F37G; zO5>XWzJ(jX2a#OG}FqrM`y4#gBmrIF#=Q;Oj48#l+g_OM(Cpa52oMC3-*aqBx)j?KwPV>Bih* z0c`;r#SRPL$NDDOO^&RfVPtDljYt0BWx9yJ?>X=>zU};6fGu!g$@BH(XDrv`g}154 zKn_A_i?GKN5F>xwK?A}Rat47U`X=hTn@B`amHz}?sJOnvZ;|+BJmy}V(89%(q*rHT z2oJ-_vMiWfRpvLa2awxL;@6$cYYuh&m{p{Dl?!@rVYMA3`7KT! z7IOJ4{sDh4gNaKc#;}#(^0B;0`j%3~v@F^5c`z)F37BFNGSut|h#dz<;!ME^g@kTm z>|Q1Vy(P9pdHN#bx<{8z<46JzE@l9cf62raT@vnQOA8RW-_va`45Dj~Fx%BKWQ7AU zPsk`|dH?6g;e0!jhxVb$=U-%wp!dU1z*-6L?_Gnp7ei=x76hEMN~nfcgjl$_N=B|8 zOrGnpuFby^E#=xCvkiOo=OkZ@(aR(=7L+j0zA#-MH&4zG?2INFy z2~=&(9eZ7`S-a^PR+JEqQ2C`8e*W)SdA=D1BvTizdDE{8%{s^(f?FAMHJf|isLou9 zMEsjDI96#GwXN!Y9PMib@rz9xVVB%5QYE)mQHfkbbJ;}ZQ{PGWDqLwR>-U~@y z*#3Ym_Nk%b16rJ&0UqQqJc|4crGdoR4!hb+B+%dn$ZWM*gt~uA=O2)mTVpoPzL!o0 z8X<;|Z8e)=+{gz;=dCIQp5n`=mtv~@K3B_0TEdP6y{=-tqlSUEQe%zwI+|JJ^H=))Fys1Ws%XH(M>f5HK}Z zUFyK;d#0Z+4pv?d^?FAAA(%0f{z1SbyJ*9lMKPQQ1*3(**!SQt)z_`y{k+1U9@L1Da6A za}m0vl2h?=9a24?|IP*N+Jc-0`4YT7#4;_sA6hE?i2%Z$oJGS&tg781>mppML&lme zpeQ|l3p|vX68xdRGeTtD3_H=4H4}+0WKRobL23@aq+$n8%84jmuEuUjU;cK5CAjbA z3nyx0@T_%YSt`Rus6$=MLp<2`<`@0^_Y8o^icoe3+(eeJH5JkeB(}Dy$;0( z^(K+^By?{tKJ^;_Ytg@xoJ+$$sW;c(cN;QE!J{NTZ7s{(`R6bLt^FrtGKaXJwXx^% zHs`T=RJ!}$osIZuDsOEO0To3?lT0}^_nCXvY)FX>Z(uGl&7Zzv>r0hkW-N&{7m^Ox ziGajTSUywkEj@=z6-Bc}J&>&z<-Rv1w(bDtSAkVu=3e0bIVqzQA|mlU?M4n5hK#(q z$y%zjM=6LM`<2~!JPJ5ecVo$S8>v_S3&h&zwFCR4;ICgHL3yW`dt-=s&Q@C-j~9U3 zS)9<#(v{nO#3PUv`-lUu=>2bm{dNW-RvkJ{6&!tVBHYJ;9$5cvR3mLe!hXB+}ALdZI=7xXeF{@5D+OP>t5Y0zu7BNXbKQ{WjdQJM!Cx8<3J5B)0f zZ3M+!5PvSGG6=XC2z=RbQ#QT?4oV;C9DR-?OfcfVd{`$JL3daOQ+@f8;Xpb;V> z@9xdyR4@eJ5we@LztZ(OAl+jd!))}rCv;GaWZ+_qTDygJ#!eY(LE$XiEhPYhTYrS< zlihnaSezt3Z+bqlcV3<7J?a4)2^%#N4(E!lGT-C-&4AAM6hohlM#e8iLDOA`_;qRc zUm$3cjK9)H8ZfSdKI4gtjRv;gVjg{9#pwo7+ot^ee=Pv_pLKG;45zg|EM46se7{?= z1gJ-sh`Ixb61O6vAjoo5-)@qEBu=J7ad~Mz{he^k z_LS@u4QSH*k*s*zSp7vyBu_9Hf4+X|T$^biyhMRtF)+a0j*HX;j6 zC_Bl1}AdXMQ(yEV;@*G4f4Chiu&5AQFPan^lpYWMh=T$ksMN@tmyS7|Lh zBLdGMH}k%4&Nl*QxNylTN`8fgZ*T9^B^5iQ^4?&5X}nl3z01b8McI?kv9+FnsZdF{ z+hu*&rfyhKPa$T&H2$C=9GN;sW@z;^79yQpfdJ{N_TDa5GPup(e?4_DPK^wf(qnR$ zh2V|*=3*-h&O;hgS>Mr#DAD)MKycHxg@sOBT$zcA!>;}g>whc-4}G-iGcpx`n1k2Z zH88y}oW&~CQKx7i?%{r6@`O7-58B21N#jh^rcvuV{=NvbtlfTpJv9Ys+gewkCuQ** zX%_@uEx%3Q-tmfL%twt(q2#6r4i-s~e%x|2yt?>q0lGWjS~Yqt>sZu1GVMCeP5mC!)-(2sX0@~2 z>*hCf>$X6AGSIsJG>^W%1+LUF*EG0}rOkfqAbVl=lYPTHchPe5v7^&$m6O{T$PAYe zyh!rR{?Q|be8U+1z_L-7lo>wQ-c(GauHFW0upqCAe>@+3+`P-GU;57tb=5dG3rVM4 zcz?Y6jp*M0G#8iCcaLp;azdc!l_2V3M%KG^)3v$wShwDDci`wKZG7u$Yrn~LY5BD~ zqW^VrBPC2$#qc<%{OHL2hS0KjIV{UW8y<>Mayg*({u{rmez_R&$f zBj3Kz`LYZH!e_M2F-mhep_0J+(w9?z=34^+9cnRQ!L@8W$=cF-!M)_!4#{h9O8Rby z>Zd&s)`3lt|phgpF2A{{~cyP&em$1D{X(~CfV{k-;UDFr-1kQ9$XVq zCr|>d2jhgV4a_2{o~g5UuQJA$GtFwwt9u;kB>H@uMl7-PlrwVgmrtYVXiL|4x>*v6 zzZOGMEM7kvTlVJSak@q2w-Xuu1}C`4y0qpuJGPmNB7bL?q9jF$*I|wc!smG7FrZa^ z9u4ZvTgc_Qek#)GZ?tR0x|RN@sz+|=F}Xo^+tlOG5L$cpu-R5AcHUPf^6ySHH9zmq z=F?8#t==O6E8h5_%uk4f&|(hszzt^6g>TER=d6!Rc;}-=c|u8Mix;#(yba>*AAWp6 z?Lg_Q%<4V}WoqDe=yGe^NU~z9&N=JZEt+$N`(3az=n`iu9r!x-=1ogU^fBj}@KH-Z z*U{D{&tk=kuPEm=g#pjRtE_*EA@4U1%PeP&9asC0E7l1$S|%++vb8tH8F|m#9x@mQ zC_y$JD~m79_V@8WO`zG$BAsPC{QeT6x>6lObziVRRF9g;$7r+?kE7JQ)(a{wLfc*2kB&p*5@(5|dhS$PCLW}4adCdP?h+P2cF zFu&eD?ADyw=?3`QM`MG)zczoG_Vc)BR5Ilbmn_>3*? zVHwLbm%=Y!_9#|Y_)9kTxYhD|yLt05ilALyT-AB>Z!DpF$}%GB#QhG(9O1K|z{Me^ z{u>37()Of>;bHXi#U^Gw)d=oD>+G>_AHOXo79$n^fen_;@$#{rwATqxMstt6A$Q%W z3JFuET?m%7&{K4?G&a(P`HLocygRR-A{pga?h&dSoh9u5$Mh6PpSON%xRl4O(f~mF z(F9%28UCUWw6AQ@-R$3DezcOyJ=_tj9kqss>cHrE${AR5UhmA?2@J{fLP_H7XjAws-wbpGeoGCCjCqi%n!4mSE_TO`C;K&y0bD`>O_%y=r1k;&F)GIlIe-0`pxRS%G ztOV4fg6QNv6h^R!Np%Y99}p1g{&T>XlWEvo zi2Yu=>jTYRzQCT<$;)D*8f#RiSGv<*^bW=HNyk%enp>*j+a489s=C*3(XXLoRci_R z9`L4q;+|gVExo}}wOa?*A4GtPn?B^rvB0w)Q?bJaVkPa6#tx%ZL=cXg>rl#`X5w9} z=a=JjxFVeO^aOS@i6AbwJlwG>M3(bruPyxMEM4DHgF!PJ?g(l=;Hsx>`+L zyReahz9v?-5kBb_H(&B%8b`2*w)L$At(T0F0J-_PbA85D`oG}9Of@(7pInVM9x9Xm zojgTy{-zTu`WDfJZQH>nAk06NB3m_DB&rH;-Hi7!i+bve>|$4g%-8E;zb)%iG&H*X zqN5e>(OdP&rLHv{lNG0gK4M)-^4Ug2ZczBg#KmHCo#Wl@{2;%zL`-!D5%pgG30*WQUZ&)+ z@w}E$rSYrzmJCaelTxd7KGR~zQ|moJ9XRlF-8YyCp{4L;Bld-q&Tv*i+eWEzZULDE zA9{gSz}CFH?edCh7v6Uu^2i;Y?#mcyQg5m~{F=5u>9*BvQXQYD4ljqvdVu}gq4QD- zbT=&gqN1sJGxLeX|J--;`1ts76)38E`Zvj<---z`^xFQ4^F`ya_boX+6;!xKoS?nMWqqp=zH7rdV$Q^ zi>XwOzRSe&F-YIeaZh&x7VcuxL<|Exw_)P0JvXA*#bVycXGE;HVmxEfoqB=z+OiC; zZqAlA5=DemJw%Fh3On)F91{K|r~U-2D-Z1x1!)1JC7++ausqnWc8$_rrUVd+uE^ek zFq+|??n$|753-*Bho-BHs_OaLhn7Y}x&)MNkPfArOLv!acZ0M@cXtR#cXxM#baywr z=l8Dl|902yb7s$;Jx|Q07w~ebsMQvOkV;Ar5srGEBu3DSK6Y5Tw6<2j(Q!o=&JlUI zc?2xRZhI_(fo>5?C2>G8amH4&GSFl2B5QFJzIxkLo}7yWWJypmZYI6K3qt>Vh+iPBFCGuElpI#Q8Rp% zV9Knzk~%z)^DgMxk3zBD?y0nZn`@V^2`%xdu;T3L1wrh(w?_$k>WioW* zjx%D7%AM`1&++EVyzDYi5h+F%Q^x}ZpQx*EZ>D($Gm(MZuojaG5(b1{;pKzSSi%Qe zAJTz!#|bd)w@!kD^h%SIt;!GJ(gSZZYbe9MfBgz!&}3m`%%KQ1(MVPZxrw{}p9|xvZq*zJj&V75V3l@`Ck3 zEv&y0{i7qNQuALWei(os95ODod*Xc_>uk3w=?DC&D1|qnw@D)g3E8c9m$=R*orWt^ zY38W-crHi{@QA-*t#L{$FY-ctU#q?CeSO}rBgJ=H5Vl@m1hhG6;5$A{#)c_1-u-&1 zrbU9%+loeG?U(o-1!Qr=xZ1B)#<^Jn=ijs~G(LIZrnyY+lT}ZTA}=bpBW1Wft?LSu zv>%mR02mQ=!&ZT1J{^HrFwTQ%)P0S9=stSC1}S3uM!|&1Z@t&Qx@D*Or#tZ)R188~S&eHp6H^1IH!U)zxNiES<2w z*ax56(M(x+7Q`mUnt^I|Sctn?@BrkpTwtc0Sfdt$YOx=;AE557=HdLdEliC#N9ods z|IW6OF~ly0UZY3g8XOnv65YDI7-I$6&>DF|iq68LPMIo&h2vo}er4_`BSXo_9+?HR zXA@!IqFvi-;Wh2p=1{0jP2yebOuf8EV`_8^_B;3|!G`z>fwtWu5nngIU_P<286w7$ z!(U4*s$g!k(m8OL{K>D{XTRJ0Rz010rc$cOdwZH4XO}L*Z)!@Ft#F0icDq{W0k!Vv zLb26fEvq3p{5&jpzs_^%|Isbj#=VF=#DvwTTbo&4b2B}_XI1H~^oSVg+LxmOwwQyT=ukA*JWXAKX2!p3=nK8pj-#S!OGALGmHQl(XYD)nJ+O;{w zze8H;CU&v=-8{TFUO)1M+slW*ny`BgU9HxSlb*f`9-Uj9NR@E~(GcN`Ya_<(@kp$OngS?@#71QQp0?*E&b zySR_?c?r65wa|UUywli%?N%5La@jalS8#Iww!On@7cB{%zV}924OnR~s86z#Ad)W? zafcY*75{6E`{q13uCrFy;zSqz6qO^0u_5S?`JzB5;OSN$P~Zx=uc+T2_(vP zC8cR@P_oee!8Mn;YEAXn#%{v~^o%^ssiF=GRpX=j^!>r0%2WdTZDF;Kl9pybb56eR zOV9fK*1>FSM$8`?yFd8-bxJ;Q)RSp((h`od%+gn>(`Ft>YRc|CdjS=AAlR$WaAA7HiVJjQkIQ zuNRD|$bLr+Wo-m(KLuCm;PLXVztq7Q*qmBH`5F>YE2NvJ9!t(_5pC4y5C&Y0Y(_nX z6K-=he-Ayj9-C`hXtg;O<6Jc-x77a0cJMk8HhL3KzrppbE2bpmJ>!( zVWaC?JrY#GUSPD;W>@#PE<-*uim9A^5$;ljx)I=CjG8JMD?h5 zWo3Z8ib{dEf{M!A#DuSpJ$L%gpFg)V&)w~Nwk}+?zQ#iP0e~%dNW#hkyDV4TtV=!o zCem3tg&VWlm$3`N{$4I(02hNO4i;dRl`pK%=XfsmuwbvF?F*k&g9g-6x;VN@pf6zi z?b1jkt-PXHZf^kP(lEji^?6h z@;X7@a4Nt2V#`(5j7d?xg}4lA0*QC2ziUQ`G*MyzAdM7svi}<1fhLR+j$9z2Z`F?+ zc9_Bf2(4u<#9JpFL{=7kFrQR!h3|#vTVZ)RW`jf(;((Zie-(n8^Oq*N`xDS#XyfTQEBSi>*xtK<~$T&$vH# zANg2=CvuA= zAf2+AOs&0t7`oq%Ed+?d=m{<_d+r=+H5w3r-h3)grb23=0$^AmFPiuWA!UhfTR z$*6=vL$(nRJGRDA=xsS1MYgyd=sLsEThuu)xK!5dT+<`|t(KB4oAUD(BqP~jpq;nh zvf1!WI{A!J6b8(>pz*VkV<#4>(z{PC;n3f5k3GlQh9SnByT;BlSa(Vx)1}js>IM1zUXQ0UH_$9B6whZSW z+};9>tuQt18XSH}pK`jU4{6>I{u7vStleFBay#Bs!u}nP1t`%cE3SXkAB^eX0IU$g zem@H6>nD7Av(ICMP=T9W-I>$=9dQHn7!u$t2>AkZYytHF&_F`AZ=4Q*vXWvz-n#elcC%~eueg_)-C_080E!L4(I z9`+lC${)2#=aZ$|Tjyvh(mLzarV%^hXw4D{b{TFOQJ=?AkfT@+K#$36d3$}*slXZg ztz>9Q38&YKm|<3y-|-u4sYal?;@fhnNl`ue&|qqc+`2|$YqOwY80v+c>5gr>ay zGUb~40pa$K`O4})Ntg+Q-1&+v^bAMj)h6F(C&hGcP7VDVle|MQa^($8- zTYs+v9*+sqAud=ub3$dyvd9;ILn&9L;e-h|yC?uC!y-*+)?R0%J#c`nFqa+Jp_)27 zJk>8ru=RN|dydJf!Ij?YqEJVjk6*WLk)Rt`e-}tbiFQ0l?0Y8A&gplgNe0Z^$~pJR zT|2;m$g!&IgnkD80O75un^5*ADCvO@NA3qW^%=aZl1O)jsqg?zV!Z!Ka)Jhdz+(|V z0tF&wi{;Fna6`e1W_24xG4h1Rx$o#RkKR-3Dry;INO}lmYC$0p{;w)g@X=T666(U^ z1@hY9$R%FM+I|8}n3~$ZM5(ky=u^FD*7N1sJ_0d~>~Y`LQ0>{$`G349#E_M1E-xWK z!AM~WMt^Afa6XRO446rZUoSgaVF35_EB?+kzq4&jOMX zZk=x)pw=}%6sgKheBzgo^*`t0n1U{WFpXk~FF4U=!26tL&OnnkG{*4^RE!>DMN4ss~7vMP2?lj zhY$60dzF~J_8H?&tzV>-27h5{x4`agSyyrHZizSV0bsbV)e+yr;E= z?sTku%l0({5>FuW;C*PGtj^F1oa?-{OPN~bCU`h@SxE`Y)$Ah4&dv@nv9xq}H%y&* za&nS{1#!SHxElI#)gLjuE=Mp z%FkXib9v|(sPGju6j`qrQ8ho|Ch_cbm1MiUHG05MLguv`Q1j#XJYVhzs#6iZx^5*j zlHcRlij4imgC+F^3?Ce)i>vH||H6lXtUpE?WD91(!AV5+Yo7ZDR z$`5Z~L1k^VdDa$E6!;E^5-_5wsWpBMfAzfcnwNIBmJ*sT{#O#ZHP22WcjpIHBt?m$ z?onhY+?$lin89=^#6tCnzSRR6o4~>ho~{-Cc4)NOC;KaN^Ic*KbaUek*Z*k& zIy2~r3msmKtBEUChniN=XQZo=c|@QvN#@||N>hSf#`61!iHp<-i_KR)oL; zK0K|p)R^a}sS_Rpa|aE!LkrW*sRHx{QEB=(QvIBE3OjKr;bLtrStlp0PIFFTPq1S5 zghgo*Xx|=Z2*$Ug*OnLVlvck6FJB4P5|VmGT9&*Q`8OSK06lWYIm@K))Al6A8vGyS zV(OwUzwsD0oSjR4M2jXULp5GzfryPx1Sj(=;2KR;_iG_NhR;sVYfD#5DIcI-*s~3UFn;OX1tS@(1r4-mV2wrK8rlTHyXI7fPa8eQ zVgj(f?LH2>pA8>B?AksX?4{sR>hQk}Z6f*|?+T(5@wXHdAOV;jDH~>1Za*YsM(LiX zg`Vc%44)(Lrgixt7L8wLw2>)!Z~sN_QW<`t?~{&x{{Gak_PE5~YZ5Bn7eU zANKe_=Je%`k`fB=ybHVV(Q-H*5w}G0Ef9>-8(WbwiJ%fcC$rQJkRz91viSEL+z&r4 zUDbwvRK`$)w@?5`+NTj^3yb;JW#n~IeZ!8@!kba5Xj;#qr9?|^YriR1y~~fHAs0&w zUZ!WFfs5L5hBa(qY=8GCJ*k&E?|$P4v=1+zs#M#RgH5cX==j+aqT%m z?PV!8|%8^F!m@8 zi@6IXhBJC)GL8)V4|@6_f}_P$j}2`+g+>1^+pc=hVH1*DBRp z)TyhfuK$qqy*QS(Vs!)jdbm|~N@3l?a{^^WQGv(ba42~(UIX@bYT(_KjSbNcs+WZ_=gigf<#U#p`Tm~Y)z z!`1nxvkFK!TAWW+7oYD!rt;fg{!VB0ZwP);sT^MU1A~*|VQ4QWk-8&#PM^RO%sh8DbE! zYW-A;o9uI7B>8GBIhqy?L@8{L;p<-535f}v zUE|?sDJr8qX>JU(O~vGdVXlph^&!*rll=aw4h>(z0VPDkn32o&o%nv8^Av3Ep;lw| zez@v0)go0l)D>$2<-_%C72lJu$ZGu zFrF2tt*M!rn>*C@Wk{s`jSF;SklgmI*yZoIF|;y^Lg~3M>%^%g^v00tB(nCCyI^8c z!=J4?b0z8u?5t3>g?o*eCX8vlHWnw!QaLoI>C_`jJ>*83;Nj~cAn&*TEn_yW|4Ube zV;Hmz027z2jv@-{@D;2M8#f)bu^cbYB}XPG{RuN4h3uanPHX-Z@vgmGPbJ5`JOCZx z9aYCptU*3rr$tb*B5rL@+2b-$zPOa@d~eUS>RFB+vM!P!LyQJs`WIO{ft@iJ*^Skp z0IWx?gRxLLT!A0ZfCO}cv7ZUh(K*3i{{g^kab1nrkYh|&kJ+lZdLB-YwrftK8+O;G z1F&{XF2w^n{WkbWTJ4smrA*O2J%%mXh=wS7?c^x{N!)Y-JMkQ2_-KGfDm3`P!33(T zh=0SGXBj-@O8@B55P)mZpK;ZG#-m_Y!UgTU-42PQuXH2;Mb;eg>3<-AiI)MD?asluEe=sJ+DUAynb*4uIld7;}uO7lRYEb zwsXM&gWmp(NcH+Zb$|i8>VTRG`GOtyGyr3xr*TViJepeOcNP?ge2|!-4$C+SOU~}b zofMzH=WA_y_^qw_x{+IU(+ZGE3NoW57=OTo17s0e^{PnZ$hiKxWdK+ilKs9giqyVZ z^)SYaudqQZ4eFvVlU2MN01EB7#-9{{{~wgxFb66ck)r1Ij>3O<(Vl5I)9DhUuD3@x zZO^OWnGHYshSyqMuNbjkjV|&COn(VSj8@SNGXX%&vnbov{Y`T)Lbn>#`CmqFQ#7*W zca-T5FQF3X)1p}Xt&S!?bb?+~!ae`IjKToDTns>#S&*@Mbc}JFz&I*Er2pE4*X>j1 zx|s~o`S_XtM#9$9>6WUSmZYVPX8vS75X<74B=Of^0(LGibhW|;$M?RRjpHOg^b&Kp z%ApUfvO&PPpKI}BCE$0@03tRp0KTrtmK?`;i*?_5^yfyypnKA3vbQ*eVwNq5tG_6~ zIi~T4MRsT~6LB;i-DPqBmdy6bZ5u3X9x}f!)QG-bf>dRyOn48CUfERf#U=~O2vlH2mzSt*!Gh1 zSx+qd9DG`us?}NM=ijbQ7V%aTqXcuP0NW}sB0wt+^Nio$LO6q7pnIGq- zLSn#|=#4vu3i0{{XdT|1fq*WO;_CZ#EH1I7s46IWOfsqt55e|^%~YI?C1V$1PCsLH z%g+b)6Apb~(Yp%+iAC~Gm(!UVJnk!AE{?TNebCn<$4`H~fNDN%+)j5uA1GG5| zIr({)O3J>Wy-jOul<=}HjUkDOAcqe+RRbNNdI(I8BKODceCuyP!BjgvCf+e=vU?47 zTP*hmR9H*ZrsElW9za%Gn>YBNP&Pe>>hM1$6Zvo6%Wbkny1WoG;_g0QIPgY=i zZ*R^0sO-Pq(Mz=!E@%H*9S^386$=?aDtzoW9coa)X+?5gbl3eEqc%vebLv3nf2*1P z*8Fk$vuvKHvg$)SpUpMbYr&l^kNUJa7JZr?%J7F$z8Y#^pZVEw<1a>Otcbr^>u`h&$0!DPbO^ zl&F{v+S)r6<(KVuxx*LTd+mHra=NKMQVTWZwRbXE*hm0q=GW8GSp1=cy+-gWcpIk~ z2$f-hCwz~)uLaf!A$jIVD{dDcf>{r8-YE}$%gYws$1SeX%$EbR%CCiqVxwM4 z)Rm2n-!Vu$OUGD}LSjTY<0k{Cek<9I%ne17&wRK=A< zdFl2%yF_}56jH8xbKMAJ`4AKbO?6(ygYOP+1O4)F8s3kcyAo-eLm`18qrPA8y+S*u z=QSQ%q4)bnLGxo?pFSQE5cJW#>NJ_$7{Bh%?=P@N)O?2I{k;o|gDI255g_RRV1x~d zbr%Grk(JCA=hiabPS0->^D@f<`R!5}p&<^{Y=B;Iz#)ymrK3Qr`(}9knA_`e^@&(V zRB3fX6^gpav;5D+7jedMIDly59^`ss5T)7<_K-otP@=Os8+z{*dum9&)8M@fTbcyV z7|hMc7?I|4BVPAzFQQuUzGu1!$VmJD}+q67+x4($|cQiqS!tKZim0Ie$@dcO8UbU9REgsBSx$VDq>_L_V3L#-SILpfEDra!s1|(MoX1XY6%J zNLj33v|DVzwkRiyoq~-C`AyqBZ@G!G-rX*K6fsc@yCRj0S%e$Nx%3ZFArP7d*0X*n zaDoC#3<1@jntdgBtOPTL;Y(sRO3)ogJOn3clGjCC$}|B5${SHVML{0``E7?Ec{M`< zdQuRI&+c7><Lz@f%_{y6AyTS z=Tl=td3Iq=%M18Mh6Le4U;Msjo3+67&4UQ69}j38$S+YO=T7$hR+LyZ~WBx zm;>gAVT3vXkF6DQ4kgH9WVFb^>iaOLjwmhFd;xR-?JI(;lNg|96ulB}=@=@<{uw0_ zMGD53${+8gp{PpfWgCoS-N%Kd*;@Jm3~vvepULN-V~?xE&t~no>1wF5p>swq2)h9) zt5LNahRs4LJDXLxn>E%vPEj19)DYc(LjPyADL;VF?b*lKXl!TI>uyz!_o7EpjxXN& z;{*|pvzA-_h^hX;7>GEh(yIJv*vs(9ncP3AU;8&b&1yQ9cDLpuz@d7Y_ykIrCO2$7 zABJ@!MRQfPoo2&6(&7ejwY#blf>nT*hkrxKY$-Mq^|%Wt!5W;n*5xk|Q-QWCiOnWr z`&kA`PomIY9%m2q0KJXvsc4aZpaAbwr3CN(YL#k?7|cvd_l%cZgEra%t8d4B?&8W2 z1QJo@U#t3KT9s~WnGI@RaQ9#!XjtQ!L~6P*N8i_{!ak9Fv8CD3T;sO6?i#uT!xu%S zwJA56LUJN$a*f0)-u63&uv%T-CCG*5H_zq83OUJSW3_GdY6tl>VhMtE;&Ni-SJQ6}_94e%%qc)1+f4 ze??^tDpm{&qsdNU_ouR|IMb+lEY1PO$YqQw6=fR0s)>&I6j)=e468vU5upX_n`<{e) zhl{K~iZ}5_l-*E@oxrIxk40yF-uj>Sjj_XSB&{+@MaS?aRGM0bW}4xRrv2$UPQe&~ zs(+?5UJ3$$pb2dzs>9#5ja(gcq)P&rr#_k?!M@K}w1oz=(87#yTRS5NoVv%$pYz(D zz&JaYFKRF734tD!PM|y!iVr4&?AN+due9cF%Un7G?GtLV1pZzosAQ=o5CtfaBcTd@5Z`d5H(1Cf++^nj_-i8ZJIHT;v)fob z$2Sqz8ZD2=qx|2M2yklobSJ{nr9qkSM)7u(%0v~*OMc#c z8M#>@=N+c}4-80g;ajQESKOgP@iZ|=fMSVmKZy=IsM;n8x!NS>kY!K10tKtqyi=vT zI9}N=F&OflHv+^$PynOZw97ej7~-vp9aPx1g#it#j+XWgiMr#xna4dSX3*i+4{72i z4{HI3O1IIhCv%E=!Fw-$3%ro5#(=+T{A3p~q>^*+1#w8Qhu`qWW^SfmDm@yl{o{uBdau1ElGiNJ{2MO;<( z&o+Y0e+v7?|6v$qeha^K7Y$ENo8FcNLH?Q`U7DCOAaDAdZ2VA&2w9q(p8oV}@@bS896)?olE?&@&x zA4&@aow8I^ANmuCORdm6_o~85zr_DA%5CpJ1*|%8DMO+ICsuH}n|G+=MKG4E`2HDN z;aFt#4#~-u)+lp!n(E;^@7*X4UGcf2g#P9)XWP@0V#3<9N#o+}-%)$4Kgn+_r?hU; zn=9%{N9Ciaaka1scNYWzi&BR6w#zpw&S(Y!-`BiG!|-Y2sUiFHjX*PTZhbzZ6?mdf zSRih@;mgw%xB;V$_%;aYPS>gE9yjfK8UnpNR8dFQCMUYXF_+9-+MDXz`}qAJv!GO= z`Q)ee{s$2Si^WugB`kbh8_OI&8wbh}0uJGTlaHnjSO8c8^WLkZ>+J5IK#MerXKjmc z;x2`U@qGHPw8@CohOp}K@^~lU+XjJ6i~dXR!_}UY zXm$yf2)%Bb=fmX=d{F)J%XX|B|HF3d9**UC-?hO(Mum1;GqbqlKhW9%1CS}rz{(=X zK;lx3$q+wftlXc-TL8eW9G$lNMbT4vnXr9u;3c-C_|7SN&Ks!Z?&D5k`Y8TWzYj5G z@cr*NPm3Tk|Ub;5x#m<{qsC73>YWs#v7y^` zqi-+d`L$07Hz}VMXGkLPhhRe=z4nFkLNR&(ymS~;8LU*{!^bhNc0gx z=2lwz45zavGj2^3bM$zY%D@z;ITwwzt$Q<5wyR zDF3Qlr6ifAJ>@%?f_AO1<=f#nUwVh~q|0bIVz>?~dfeVy+%U2I+;`~<`Cb^1!BgjY zy08h>#Mr_~wS+L**jY}zHkD+eY%YHp`;SfW4mX-irem_vC9kyJE&O4x zf;Y@1RD0cp>Q1oFtCru=SMFwu#xy?(hwg~3BL$?X#%I;A<4{*kgEmMS^-KB(&9d!vP}({T!@{QlAV$TxZV{OTQ#mqFC*2K@5j&r_Jf)<4$6B z4$1TLArhK$jy7dy-|MY4nIcam>}3WGIsbG_&k%UIEg#6IF%H^!JKc&e4J0^HNd+N$ zoe@0En$cWJFRl%mxQ1pIf7FzP?&!JXl^F^4e&TcAQhJe^Wk(Q~v$6?9@b$o!^Ypd| zFv$T2`u?UQpfx&>LSnQPA{(a`^w_rop;Dvs$Dv>G-p2hN@+*%{5C=xsz24sWkWKFr zOe^TmPlD2+&a>kWb01a-emjEOVKE5_-7F;@+1p=;m+#3(Z}V|}d)k9CbW&lF-NV#V zn?rK?ecKXVf-x%DcY79{c?z@5TT0)zXZOiQz2fKu3%%uHDncWv{sdDYA20BxR= z@BR!URPpU_&ET)N=L{Dh25gr0RNMiYDp!oL}{s&E^^_S?8 zEM%ZXcRmG!0&w+GB?lUaW~{FIe>hjc&1Y}OVaU3wAtVL+lApR?mf}pX<%bd}ea@(@ zwO_5l7OIAj50>HVzgkePF*&$OM$|v3CDtNibo%OW-j5O$wZ6CBxt(q)GJ?XCls6uy zhyqB*yZ^&WDjC+hCsv*2hxl5k2GxBbXu#zP9rfPLKp7tfjIVqedJiXvqVrIN4LMbc z!wF;hkM9Vox%T#aQk7wtZ4ak_f+G#7I(iYKy`yVy^P!*cE7aJzUnO9`4eE^@fNVN& z;cB*UrYb+PX6>Wht^o0Mzg1-f>n-y3w!lq`Ty|i0NR!wWZ;-Hc?bSUPl6dctiozNk z&qrzDyjGCou6dP+IYE_|TdCj9LEU)WNIt*7Sb?~ft$>p1g8=u^!)BdgIPI`?vZ~*J z;?yEz++}W3JyS8S&FdMzv_GvNeBH`!Ei7u;^@k2jc!uSJX4je>Bp87|{y^2Git+VDQHX8*Aq`%b9rl>oC zzSz@w3o-n-=(U0p!JKl}=6_m%UfK+L6)$6<-inP^w(h}+Bxua7KwggU3w~Vm9mfe1 z3Z7)m0@H?n|K>fxSlA8>+om9;Dyf0rPThCf#1=g<4co^8zB*M*9W|OVP4x8Wguac9JjIRh?xO*VxPF2M!hOC z>F|9f_YFo3HPzy=y>$}=)xnp->oXtE#rHs^JY6#XhM-AvM&CY{cDKAX#&G zlOj?XsdPU*%K9UPWqB$^GnwnltbV6kv5CG-Ak4mtgaL32@^LDUR}fFW*LXaWqo*@I znK?={nCyXl!Xq`p_z#`oWqg|AKXDn!;(J=ZxNd#VI`MmrC?Eb3XO@%rhbYQLhwHXK z{0lxcr^XAU_6y-5XB8w_2E+OUdRuX}9?0)VnJ%J;^5Qa~FTl`DA(BAOHtO$bFms#~ z6XS{Q7sDY{nVLR&-_6GU5{qkMXkm$m5Z#vh_`5QOfEd;hN|tW8HY(YqX&k@%sKFiy zh^!Ard0z}WF@>}2-ZD%l7K^gwVSOcm;sf`Fis>>M8nh(S{%%zw*?gxz^?eR)@<;{BuAd+ zG6yT{in6&20L|o5UnhvNaP63x*w%g_G8ox;i&R`}qstKJ*be3%Q6cHHIE|$-_oB$$ zh;Yi641=@wDQ9K;&E;+Taz&Ru*&qFHbv8n#?iho?BW=w(K z7|w<)d;UQNoWEW}`!0V2fr~$nb0*Bn;I?(w;}25slpvI#NT{4okEMYna!a<@7k7j7 zIPoO4Kke}uu)i;+wk#q+Dsgwk2-dpbv63@N10I{`1UKG# zLvt&w`YXJmLCb&Ul#V@6Gu+8dwRT*5O=2LTB^%|sNnt?Etz2ywLi{?oq(Zi;?fG5s zQxF5+pY9)(p5p7`F@KIAQ%&ml9~y-0{_WZ8>Fap9jy8MB&zFQ+S|j&}LsP7UGYHDY zHhqfYyH^Y+rF%NHt7x^cf})Txq+DN(b+-L_6N25jWTe$76PVr^N_))> z)zvC_HUeUV(G_)kN%se{A54GIuxU98DZs;|uz{Hy=~u*gczwY)p)I(I6EmfkxrXL} z*Mi5FSb2@lG9)_fFGk}Wdyyc$Vd0JZR!pqJmZu)Xk}6>VgPy+VjAlO+U)30wbjC?B zZ>&#OY(@-O&z@VKyd?#mPo<{SgR10q)L=sv+?1YH%p^BrMGn$0GY&GSQwmn-h_-}{ z)@*ZksTl;rUvd#nll8q`SeHM+4OF^HF0xMtsf)HIjUnEKLY6OXMKN9LP@ei1bo)o@ zdLD&NO0J}1C?eKc>~?J}<)iW5$I_WnDP)Urz6W-H5yZ>|NpSteFpK-}w}y@?S}r9g z5&v*yX*#V6n&JV8`g6R9eT)d+IKo|Y+K zl#TG>`pW#&OsOI-%{|q}NC%~VAx|_l&Gb`pkA9z zo!qP*hNU)6d>1w;#FJ?RIjq=NzN~HgGM<&Trn=qm`(vMMckxhN;T1+DFHidAq#`8y^ zw_&L}!%MCOWgy26IytaGO;~=|Td)b)%=IP)Zsm`>XrJ|EFGwczl*AROVM}hId*);? zPX{eB7F_e_jc~0kzWb6zm79%5>~J&7Xeh z(w4N)kvxK)F@`eN^1T-~XB3o(`I|dC;rW|;P?Vo3`r1!j?PzWSnxG_^h%FU&ImHt4 z_E_mQj~OTa*x|_Zn}*5oqqMKCPr^q)_(O}k9xLh4)MknTu~4dOpZnM(pHJsN*JwYt zVhYXIvhOv@ZV;?cOYM`>cw~d=TdU6;!-4UC;IYu$ioe&a(w$_1#vfb1338CCi5#B9 z*#UK9Y^q%YWm8%>3n7w|7^Dj~OrJvRbb3tuxERDT`f*bpuO{JeMci#;1UT|TQ&`YK zx9_4>XfL>Ugb+uiB?sUBwzt`@^|+d^h6O`sQ^N;=#u5`9?&*~_%kz<-E`-JkTuOWY zA`_?_a%a#O3j6R=r!bw9;!EQb-FH&0kho9Zs05q3?S5I3+{?=MM-k$rpqOZDH+8R! z1rb|$z3YONcZV8M_q`t(sH#G7+8Wu&Y}a$uh`4yLbJp?&ICqYLrDNt zhu7H5yJ@lj2G2~uqT{jdkpU=5-lYs^WAEkLUSLibTfd3^p%CUZ>`p0%qh)xQVozZO zGqZy~t^$9xWyb=M6*csN`TI5tXT>^%H?{nRw6s4jZKorcQKMEUKMJ^uNQ{w}qJ=8> zV3Q8ZqlvR1(!=n!4-jF^ z$hDm96^Q7cGKH#xGh~((wALosOs|BQ+R@|m`~BgD7Yj#ku8yQz9w5ayu2WCkiSr+b zB&^N|lj=(}GG4)Rh+75MjR8*gbShe1*tNfLc?>T0((4v1@PQr z_6M2;hYtv-59~7MVj3yE_(B?QA4R?ijw$W$Ij{?zp&f+Vn*0=H%eT7;ZJ!Iqr@Jy{ z7s9@|%!mkpn3UAg7hp#3t134B5Gq@p!Z`}1IOHJ*n3@(6wc(hX7Mc&#Z~(_(On<5k zHh1+}9q2PhPKge|sVs(I4Q@;C^0TnC3B&}ZGIl*&OxO|2NZ*Gio%oR2r--tseVe=W{6aO&l1MY z$}7nTBn|q|b#VF)03C^H_e{1?{7lF$=|7uR9Gb?vNTRe?GLmio+H`1KP+Ee?;u;6q zc&r7AQ+xrP+0-slaXQD6bday;Y=%xS=oqd@ZM|jF5f zwby+Bsj5CdIO)T#vN?Yr6W-29gH>Y#p_*nb%Hzwx+~;_Bfcx*SBymjO9L1u<9#5X^22rwyPQfx^Ex7nkH5 zGsIqxBHRNJL{))k&HVEmwzJCGAig|yOrcymakdPWu=jB9nx;XZ_fvWZTXI1`F=*I5 zI5pE?iDiRQQozai+q9ciDx71*E$hq&r0E zlm_XL?vfOgrMpW?I;3MkK|rLtTaa#0x&(c`_y2c2yxLb>T5(Ev+;{(UZj*)&nxM`S zy1@EW%L43`QD`EJtvXi?G3Al^bHz0lk+WzTp-z$GrubC)m&2#0;itqPP^__~8%NIZ zXu~z#5li`T*ygikl)Twq*9o`NN-6;{ zdCJGiRhtutmsrXnY8|yl5iV+v70eLbRhAtjp(?!S$#1whq!;o2{O~7yDl}W}Vvz@f zsHvWdOa$Rgd+b3X@{mPt4SMdXi-VIbO;Y@>`h`*n(j_^CNDmoj)*xBMaumv0xP%|G zCG&;K@FLkl1w1g48gp_VsIKU<)_r1;gx1Hx3_>2Lv}W)bqhZQVY!MGK=hN?%ee70&j2|xIhx`#WV>KGeAqe`n4A~Q8pqS zxvBg;kk2gaxDB*}XK^Bv_*C+3ftcTp=Gpw=(wl+wvUF)z`hoEeANZ|8(u$Hj5Gqe& zTjHd7q#{=k^#VjMCd0xkevv1o-ZBBto`ic5*imq`EmpcGRDW@*_%ls`_B~0Z41%FT zui0VO{a!70n^`9@P&+_OB63;WT=?M5^l=w^^Kg1a@VX?@06yCdqnVG3;MO!j8o<50 zl!Z-^!0nQV#!xu7`H!V92L`M$uVRV}vNz=p0H6c3W1^o;+g`$BicE0D`=hNnl<8j= zil({SF(VTp#b$5YwKrs?$CZ^SJ;WS(YEPK}x4c~E#}@!eM{!NEM2kVM=REV9VWv_` zv$8qo9k+83Nx^(LCa8$5u;JD5o8*3ernzDg&9CfPd6=URDnlmy=VVH@E-K!4KZAwq zy}-5})+|)$1bPTTM$VI+HEBev#LbjNc}G5%3fBK}DO4l(`G~d}ub*YATt&B6RvO#-|DH?5m;!n&?_b!Tk8eRKKEqw#G`&nCEDFn3UodES zp(T4EInOQCG0LO{x^tcu#KH))%|)fGG+C|xGpEUF!uAE`fZ?QOUjWwLrltSd3NYDP z0~`^?Cl2f!M5#TaIfUd^m94>*&oMPA!0IY`uuBuleYs>ra3xnKrr_u#QAlXz>$^}D zzL_B{KT!R*Pdxq6;buO84(j~q{DY9uxW=iQKV#lG6n^ODnMYB>#M6M@ihv=JUC^LL z*R*o#TQmVdRygpAdCrb1vSI?&XKHE0``B5}t$3suKF%H#^k4?(I!fF%GSL(4rM%_7 zH^CiK$>VYYx9S5z4>EX9M(kInvzAQB_e2b6{Rxh8PPkDQ(dt=c$^zLk1u;hpukuUY z&~GXyRO>Fs0u#c=g^#-v6J+=4u?j}M-{1qVCe0gx9{0?@b z^kG^siezoC3=`ysq)2?w$!;_q8Xujqf+*)g=&&aVoth3!Ml=(&xj|=`Q!3|ph+K5m zM@CYcqQmy<&9?;_Cq%CnW0>|OX5!>+gGXNc01fbk_&nxNJP2bdtZ>^1PSOnJY_m^wPdI)bKV%2{I2!&>ikFGz zw7`ab(n}`<1>7k$g6IP{pJl-evd2GqrLH(J$=`<;HMhP^l_?-kyun31KEiRj2&Wl+ zfJOG-t@9X>n-)6v$L}LwX$`&cSQQJUQ)f|;HoBx1br0OtyHsZ(6_=0_>Ah+_(pa@x zvf1B|ZCL!JxLj$0G8z3vtB&z;*2#L={$ z3Tz~$59*5b>(aBOnIW-r1+0*ZiGr^uX@wgHC8Sd0(?@n$?ZA$RU=|zjGGCxle5lx( zzpzrd2`K{41+!O)ts=%mkR*aE9K5vh;*O?8q#IUbqN70sa2&JSK#zAcpxcs8iCnx~ z>^$Nn)oV;FJa-XeSgEH8C)*?ZbTD%#rxo-k0DL`6FTI!Xm2Kf9Dv|)G=+Z@XznxR2 z@7mfnvz?t+lGxZdWkLX6fQ#sKaE9pu9p%Uex9lU&_3owQtP;$wAwEIDHt!vRo$pXK z9HNOt0hLFahcUGrVV9rnO9#hmcEt+uj*gDvFUs>v=}93w@! zVM?}O@n%D$3LSdpPQAUA0%NOH44q2di6{OPUGgutN4Z_L(G1 zGUl)VMu0ZpX7e2uWk0I$NkM{#OdZZFHeRdQ&C+|*_$Wq84xJs$QRId$C(4=Pq9b(< zE6X#v4*=bDgRCb+1Q zsNP0MxXkY}5X{(>{^`3*u6>NFry;M3>sxP?#abk0e_qbctxnz)~ zsqO?8Wrz%=``Mwc$V5*!2WRO3#eW}Kx^6Z;LgZGV+RT%_-Ymtl(uplDp-AbpK(rm_ zZ<#;-GI4M;I50)JX0V?&0-KMXWZZh}rjd1L@zmt@?Bpc*FICXb%7$_>s`K{xLVFNl1VMb%c)Qq-Zu%&!ccKp4^E1#8cr$c zG#WE+r3?D;)qg(>G~P$O{|=CN1>?v)o3KHVIl~or6~|m#JGj4y$ZVz@5W!_lY4hl! zwaJ+_nih_KNJYs&Nlfd|p@V|Uli@+ZrN5j~;+RHB_8bd4bWOzM;zNc}<{skvGWkud zJoD7b>)8pM8K%gk%JJ?=UA6Ro1D9rIX>E*{E4g-@?-{KA@4=`&#CPKDxALNgJWd+) z<5Dyx+I2Zq3bLjIfHyJw9)Fs{b%}zN=9(uO24OVLsp@2xGev@jjPl%-*u2rCsMerU zBw@IenkiBiu>x{ONrvSXh7LjQq^8?#-F@j~#~^7;pH|NYN3JRe%fi1;+@H2mr9JJ)n&hQdbkw0y>3d%V#-A~I zxR}olpQ!l^Z$t6_z5e2eT0v;K$S1YHJX>}GwOLfs2!rh#Ll|u;{`h-mtp=ArPoaw~ z%p*)rRKf~$?XL%L7)G?g0ukgytSVfpA?^vQ5~f+N!7hDh670h|a~l1A(FKkS@0ZL9 z51f`J&_ptqT_I0Wj(XJ}SZlyg0p8I*RU@dgljw&OFzp|NsNUZb7}J;b5xqMeKkCe$Dt#A6{FAggk1Nee=^`$k?^V_igh}lK zz~A+rc>uYe%mSz@;0$2iYffcTiz+hw{8?cVx(P7O#*i6~5aM~b38 zS+Q3t;##x*Q6jbAJt6W5l_}VzgE}lNmpwO2Gr?WXXC@uLzW+5ZwbB+_5+e^@|Ni+9 z7y$A5fQPx}u716YB#7!Ed_}puoHF~(0I2ffwR9aa1(h$*(rT5=GJ9mMD(pk6xDU>HD>R zg(rLpsLeus8n8-;CrHZEus!VBgESYQmL|o(Una_86CE)}3K<)zMNIb5y;-DIUr)(8 zVBsh4(AV#|Ga=i*ae2~ToNMvV_@3A<%i5W4!B6$@wh17-~ z{FBOtxcBxLYUxZ)c!;baJTkpG&gabX1}P=u7u;PD;D21>+zVX$O!CS?BYu~vya}`ptt=Z8qB#CM!S*F9V z`_wRf?-=0d%owAuHjG;vvXGT0Q@|cT$NFw{u*T+FLd7SbHYr*edVt3%OfP{8o14xC z^PM!V;e!eR@-0|tlPg7bG-pLoZ)!?(ld|{RNwR%^f;9f`@fth&&DN_(=1Y_RtjAqIstB9OIt4uz&ykW;1m>+7gYm?q5M4@qasfhcu8fMW!Nes_@?^^Z9gJv$NJfW5B z{x#F_-|R!tPC23^oQsd)#4iBu^*YKL6lpS>2FwzOtVz5Kfni)MgY1o>s{Qn_Tn&P^ zgHx(BAwh3Hu@ZkXH)+dr|3^BXV7Lw1P%L#^OA>p91H;f^inE+d%e(LFjyS#b%Z1Ab z-mi0p5u|ScHhjEfvSBfntOw0S|M&+4ufPWHDMLrLr4hcXCP!C(AE2k@iqqTGzGN(J zZ^*UyBM7uZVKgi}0bmSl@njw66C#Lr6GzgkC&k&K39oXp8Z7Mo(NQmu0&M~AXEvzH z7f=T$W7KpPeXgoL6Q@YkS%?8#kZ7+###=cdRY=+Fa{o|kFW;(#w+++)5x#~Aer+7w z(;fM-ub-PxkmNwq73H+c?Ej{ct2bc`?CE!s^4`>UG0K+^>N&*x8gbsXFih?BGe<^83uTIA$ZTG&DZlEmKQpG&iY8*7V8U*YRtUn z^d_GFIaX%P^BUp$93^zZY9;w1_oZF3%}xP^g zCxZKG`?3m!T$Pm}pw-4UtPv-5&lENkNX)XTorj3daaO2*52Lt(mEY*P?e#`Eq8J#> z&D&58kXH4V2i@K-S;?BWZ+dh8iYX*}>Ma1`|DnkB|G5D8Z1d9Cv3N4KO0#@gdKVa9 zN~nE%;^GKa=zCxseRHM`W5rk)9CiTXLbEucPP_)$s+&zj@Xhdqu^pbw?z4J>kVS_=q6AMDMe++ae4uDT#H5{?}0K2Wt$?;`s!X1Y%hm z%yEi%6l}j*X45*(mngQJsfi2Ay%R!2$h#);nWW}X&q3K~)tx|gOtjO=lS?YF?6@v5 zemgZwq1$hO$u;C9O;0O>NV$A-P)sY^&%)ni1a%>84uvGkZR1I}zfbU*mH*CM4$vHo zI5TKo^a50xD5krosHtU!nvO$Iy<>qDUWm&w8fy{^MKq@f$1}FhhfJ#A1*1i^>TFhMOm_D_-LRCZ@@npr#TTJ$Qem+;yK`XzE1*o- z!6Dt;Z=WQzkgyuS#H^yo)D8YAAsijE;yU?zl*}#)#Kjt4QwLoE&MU9P-G|(!SQsYz zvZb{a@_LZ9e=r0(ml_jrbV(T|PbO%re(vp3^Zb0AojOf7crQHud$G-T4P_vd;AK^D z-KUtReyneg0x3qGN63rELsxGOKEHTt(K18mRs|a@21!&uxn7P}5GK-)aPf4!uM6Vu z3(R0r)msg`DZ4VQd*$=&q^M$aeSD|Q{~5X`_3MwdGhHuQ0rDu|(6I^}1|~kgudp!; zx{VCFEqwB>!hkd8fA0bMefxMCWTvb^mHqF0;-+nVuF);9P|al?;$_j0N)M3~)%nH2 z=|&hV4jJGzLV6b){$8+qjH=6%U;lt;`8I$X&jd?+<~}gr$~|sa9QrG`lT#I@R(trW zRb2}SMuEUx48pYG3{9o|hlS?2e7Vsq(8IEH{q&vcW>C)2)$=HLihkCn$VvOrmwYss zfv*Jh;y2dbg94z@!zK!=dyUC<3MJ+C0X@lxqSM z2Z3#=IHO&~qys14MbZlk0~SbTW>1&q^uGRs}ZvEc4i;L>5dmDIcIM zKAwwnO&E)-F@x2P-(0`oxl|QI$BtU{ea{?HPj?bD{!vzkuE+*Z5~$3SbVsm`-xD0s zYN)IIyXoQC5TVMgaqZmr2vra`pd+g4VKC#E^x1K+t-y6vVSZ8e*#3LJaYW#14%gx7 zzpPk0%Q%AId55g4lJD(2S#0gJlQyF*M^(*lT~IScXdgcY-Dfv!JZywll5%Ti6CK%B zDO%)I7Ug`|bZ!aoFm4orv`kZff6J+iD1W{OT`Vepp&=F{_Dv3S!l z5GXQP8&^H;?(=}r2NG~ZbT_nyJ-acOf<&VAcI%7WSMzKPq<#&%khDdyrJdn7z+ygf zm&4*FCM7FBYWp51x66kPa*|I%hn~yk8c({lsI)lXn6HD-VERkwYa@VPQAbihy{vaK z@?G^^1P{DE1bfTOhaPhEC5X54-LL%=2YkH@@yE*A(bpR{y+Z+A6r?~VXfX#B@-e+AG>%`3&0 zE&P~QJ8qPon&E(2oL8-kN?4!MnIGFL1xkF%s*J`9-sEbvzrbk`vX*ne|Akcr+o$_; zy|v{4u`u0n@YQ<=L0i?CQc@4VqE;tV1>j$sL6#4v{K39CNa}Qx;70yJ1*r;jiOK4Au37zm@q69 z(HL9^y67mE4DEyT8U>r?;HpEH`G;mdab@o*^c7RYzRImeHfOx=+Md1q_jOA?P*T#| zMLPo5;lY~VX=86NM6g*>fg zS{%&P-1$2#FLMwjQ6~1%;If@RM26jz=dH!6lQ`2;9Mdz+4CvIzZ(3RL5Wxg4^uqcU zd2-GXh9=W!DKX^wffEKpAT&tw%;M$er(w&n1!B*nTl zT@rudV}!(hw%75hi{HLp3t2i|OB>{}isERC4r;&*9ardGG_$lC6IbkA5tc4aWrKdp zdgWka*liaxCdL8zwXUq^@as0~p&IguI9h+Z!u6z73Gp~b(Dm)jOCC_yZKceQ3mc;n zt~X?1wY@Da>slhVP|ot7Wi?Jff0Igsi%a8v9LBi=eF&`cvzy1dMx*@&xsKeIkAhhZktxfn#v zCFLwH75iJd-AE%)isoQia4Aw+m>zm@D8s-e<;zQp3;sl<@yS*DXNm=zl-a1;_n;?< znQZ1U+;UwBq_W@$<-ZqL7;i2gey9kCKVo9pUuI2PHus!Om$*;L@B8@FXi41CW9*#w%_4H52BdO;1*@U(J*LrkYll717^l?o=+ z0v5vJnakD+mJ@h0u3WxCUxgNCFEY{Q`3EZYPDymMFkZFQVA&ImDi8O9Q8wJn1#B5! zYWu-YEYcp#G5VR?n;xR%_t6DWz2Vke1`=$2X< zJH%u}$p=LUy^bNCfk5?=>k~`8XKYd+zrCaRcgI2`K?VJaSV4hP2ijkwQQz)XamaXt z{GsT~-;N07<87SRrNBx zvr`{gAN8UR4h>KsOe2UB%KQDHzu;AOHL> zN@~gC-lR0a(|kkX>v3+jNtKz0dj4rRsrf`vWscvMi1x9(3#*mmtAZLB*>l6LxF?jV ztiB&I-`f9+lXzpWzn-)JiJL|=c@AF;WUOv6t3WH?#EFv2f;VRd)Dprnekz8DhrbC+ zsuam$?I#N(9?4};e7;0(o1?X7DXfWv`}CsT7FJr>)1yGCpVz-`r{+Iwbzu@8-$fgBTT-D{t!PhlmH6l`N3ajh$$HWk2@q#MMtceTy|?Y+Kp zxU^`FU{CTW$=xku1YT-BJX*@3(pGK~f-2{v43jYvly{DFoU|Sy#Y)Pd-07f3GvO94 z8zuTZP+!2l)8wYQWi5B#aAt+DP<;Qjz#Cc2#B0q8$0L43t6= zE2;3M-|Kqyi`901F9WxID1+|RepQkhuOdp82xjmh>sP+9YBF<4#j5XUydb~jT8*IH zQ{q(@L4oH#y#pt4#Jzex)9K7eR~@p@Gs$puSqSTDKH-@ZcV==~Wg()IJoms4p593B z3BDy>($kz$i-8;;hx-GGF}VcJe-AwZ-a^FJBRjOOacOl9So!IFhVROPEw?q1 zF2(F-`6(EVr)$^4LLR{_8iuA2q-+zh%wX~z2dJ9TkdI5Mr<*H`=N=RGLFZG{MnNkWgOlpj`p^13tSowRxGX^Ix#b0>1im;I-OB_kT&U&#$ z2`$1$U??-SpTr`3<|)M}!CR|2WQ&1-dj{((vCaMS+I}fR)+}-i)x@Wk==ow#-}ALy zn6+;EyS~nd^?{JE@~nN~uh~wM3$I8g<9Dr6S=Ju=U|9Rjk}c8B-R12{H+)3G-I9Dl z9>th}3-|=axwH}}LLCjQKmGh6R}i`91VX;4t5R+4a^6_+N|?%?_}s5*5FO>XtLz=J z&HL*6=UMMl;Rnf;BG|t2TPAm{(9R$kHvIj{?w3KUMri(kNyo1jooNOHC8CYQ0xzjq zONP|-MnK++WkdyzA5?|Vf?j8{bwPG~!=t*CRU{hjzGx!Fh%biGSck#aB@C(tr8VyB zt?Fx|5xnP>R2T>)r|oD$2V-B_`-^|ec{xJEcd$XDQ5T=+Jww0x4q%pDg2 z6?DJT3F+5iKU^VG;b-e=NDkqY9;;8_nM+;^aQ0(HfhYyaoLw1N(4%G<_Wr~2@Io3& z?y%o4E%2x7mkU5OyU-PVL{bV`v)cSYOKFD%QCBzgwmXW%VS5IVC0{?qPg=$#j`?;1gnc7CF6aY=U(V&7CWXN_Qtu znY3>`u*X@z?6=8h_#&E!kCAEr4QH&wc`ujWWGkS7c>^fj{|?-f`0u6;f4n#QI*VSF zm>J?-1VWq)wj{^Wo;fawVBl9gI#}1Th5psZpkS9a$!ez#Vf;Ze(Kp-M61jmJaWE&& zHIIR)amK1fpI*~XH%uvMZvvt-O*46}bEME1Ni{mvu{P88baz;sKkkkZvZIM?LxU;x ze6oncf;DRenv8#pAY_S&YAOj;GR)h5z4bmU$$vtw;Mbt)kl{n)UQ|E?Jgo@CrMR+W z*J?jO-s8M6d9NvLs)ba2X|+4-o!i4^@5$G3XWy&cj?|mo2n6C%ovVvm6RDXW!U*9y zBFdbLl`AN&fPGn%0@ngJb|kJ}ZCQXiM>T{7WQ^qR6k4%-bdyEQVg@!9TO%@Dlqr7V}~=K^|SqW#lv32`YpZ%Hp7>)V8v!dT2WB>Zh?opAMqk9)>#=sz0yzxveax zI`i?o@TJPcU)zYrRe@e!3y-$?h!VUCXm(0V5m>eT+J=K)(HD>SL!iAAt#EvhpYUQ_ zExAQw&M+spIh9%2F|W&B13G+x`Q|MuP)Mwk#6ms20qkyHOMqRw9NX^%&Tt9ewa;@q zj9`TO-N_aGwilQeoorK?xr}a#{awy!!F~I>XH&j7CrZjgj?=oa>+=(hUz3n$|1O2L z7{f(58mhn889~!k7&S=TrzX+bnn5RFaK%k)_BRd)^8`e(!@|dq+OH%9am^4cqo~(^ zpN|Ub_?>VRODBi>|B7WDrV9hf1}9rL-eollW$%VGXu|0bL#%<{?&lG?XF)M>X=zaMnvt- zTM}fZSJ|f5b-Wo_pV-4Mq9K3lbfiPM3YI~VGEVVt`>5qEjqGdCZj8~KR-d*%?L^KxFjoApduTZ zeFp814c0 zwRvdXR6n6Htq6&SU<=#~N63(T9ik@{G^1i>AS#$HqeXhC241Yz{KWgG94$5Hr-g)r zpE>ZZ1##O(#p0#VLtJWBpX|=2}RObKSbSmCp)RsXVQMeOd0*Zd1Wywus7?6|0!4*qgy; zvl3ay0kQ3DNrQKZuL0K>aWnf41J7s$ zqEH1O2Gzg>xNXwUfJ_%jvVO1k&R{z}=E?ByzZ+V}%v^!tN`X!eq2y=w*SU;zkmhF4 zw9TU>sSGO)A*D6YP`12}5!j-<)E+cy9cy5`I0q z8x7cF18}O3q-Se~vP-$G=Q%5^nz+hw9W=U1~Tfe02bF71d`)XP$!1@zrLW~ zKLdLtqq=8Bq39saxwsb8p=jU!EF_Jkyo~2=`Q32<_v65yO5Y+E{iUo-CG^ML}_xooF2UWQJCbH@d>$Co}_}W6bv_acIY?#sw+FqOpvDS+GD&Fw+wLsTG%D{PH2%2#kQTO%65$*tBQ18^dT$*Vn zE-2`=6)*CtYA)z5GYEfVStBCzIf)_}KHEiRrVG`#yYFZ}@+Cax?&{h%amM_bk8=oN zixF%2^K!F`i~_BOw2-ILDiW+ygUaqSyu7j$bx=Z-kbLnXd?zH<=j&4$E-9J8+&xE` zWLYpeo8$;T5;H||6!HBY|<9?+AhhehR=yG_J9%tsjFb9y)5ZfF)=MI=?TAe$n zIp>u08hgYGc9fKZ4x6&?xa-H%S76gh8;b05cpLb$b1Jj`?;?TR74@`6q~!Rm798&b$+}EB9zUhgBf|uG*Vh`%9o9(){8uRqe%fB^qb%7y z;`|DTvoYV#@gPGa{z9!oemN=?Yc~*2E^O%Jf7^8}SCG+1h#f)*8{C&#n%Z^9b^2@EdR(}m zhA78Yb^RH+%UIK9!p-*b;|AJsbXHNBp#1IPh@6m6rMkXIs+^By5h{bPOo` zbo{gV47alb<0NZJ3wQBN?~u15V$!qzs`4)i#IAZ8LVNg$J_nvww}7 zdJgT>py8nL^T8It>tPs-g$GATH3X8p28^by!7*|O_g2^J+Umr1Er!WfB+*FLK2YJSSIW`gqoJ#wCo#+8tEBIKeznY7%Qt7}mU$@~$Hn(qO&E>Q2D>^jYr zyF*PbDWk^&6upcd+z zI9rY7%y!Q2%ija*?L6#jmk+Ylq#99G^r}A#Te14FCtcaX8b%m?)@H$pvUt@({ELRs zLmZr)`Dn*}JAQmI!veWFqgwhsrG}VmF|k!yeD*Z`X;UkfL?JKpf2mQ>f!rrV={&CN zb}W*#GVlFfDP=#yHw|?|Qz%l=Jh!hzBI_>Ni)&&iZJpPbwg~iwLp7dJ8r&EkoTlWL zIjqj0X%^gPXV`UUL}GvR>rN^=^8))5b=9D@dh$`3kcsBkk8t^nBI*_kE=T9sem<}9 z`I;(qCVB9gIoi!!pr?6A|y*?4yjO$6Q=fu-!pp-V(#_#E2cvVLM>?6bx%uig}Z zO#2@_Yvc<2fui#2!I6XEQi`g}17SrdQvjN|Q4{Nr1kNUuJZ$i7*3?t{4};XZ>AbXCi~?_uNM{$kp-=G2hL6^;6$&S!Aat%V1{=|aidTOiz0MuQ|9GU z&V)*wx6~G)w*JO*4OqVmPes1~*W!*QKjHDRwov^qkn)~sTaY5CvDjPjf?Hm{8Xz6RlltQ|i&J%Usi9Ll)}APV_2vYL?xRNT9A#ZjLRSYH zY>TM*CIHY|2!d&fISZZ^QRQxV8L;K+tf`ruKh}F|p+Llj-L4qpvQ`am3HfYhIEli>YA1WZBBM2VnT(HZSsaptGYVhtk#HuYK&vuah93w_!<_b?f zl@B|n)PPbD7;tiO^eAdZZ&Dn~8?SbA<=WCSl4i9lvPLEpWO;HaD1RW(fG&@)N!bsA zUunomL6@0ks(h}xmHJ4OQCpLqO{$}6!L%)Jes(y#tK#?C=g^>Jn6%eIs`a=`PC||q z88j!DYwX{BCX7r|UoTWrC$g~Tk^+ggYlZ`YUSTd3cxM8oh`xSFtM`tf8_U!3D$tlG zMQV5{|EpYWP+=^0+g5aLxq^u3ivqPMg)x@V612cLxUMS;M9(JLCi&sx6JBo45rV&k zZ4T*9AGMI`wKBfB%&z?NZXXSQ{e)N-oT`&xG!lB`w!iruU^Q9`(wzSTY}qmH9ThAoK2lb}Aq3!s1UO1t#0j0aY7oF$MW8FfEH`i?W8&}-_g4fh6_zr0Ym2Ed z3iR$G$$BGY;GJGAf?@Kd!Bm+Gb`Z{Wk&qFR{EPPO^viZ5WZDxB8X~%171@~AFMBKs z^+o0?Rw21Kd6)cN^7@{$?KtY$7douxWL$VM1}8$9L^u?G3ypy1M&W{}-!Pd>GB4z5 z24RS~z`F+qx&e^~X_L@Wkmh*!6d+LNF0!^3DUZvOVn z6(hu8$G?`deVX;tIAO+RX%W33ygUHg$SU#4gQv3!1AqMZT4~%w#ImS>nB-MXP5RKC z{0rsN?EkaHqC9aJhYUJUjnP&Ns$nTe`J zJD1c)_-quuYwTz%e8i9MS;*zhxlkVc^fNuWmgNICG9yfLE^g32FwH z8W>RHhyeT+fgU(9LIGHPxjfKaojwgng`wDgI~IV%!0zUuWLhQR83J6o%d6!mOC|WH z2$JOf7aoBPxWQ%19;%$Lyhno=vSL3AQC7o^ka6(Yi8>C?U_X$dM4v1CfQlk6{Lgny zq_74|-dM)j+T(lN+>u=qFkY!tMVMBq`WxrTi$n)_e{uLrZAD$ zM9;wa)-@Zr1|;ycm20NX&b#lVcj9h?;g*p_u3kj% zqHHx9Ni5(*bSx!#wT5Y&J6E~=3RpnL+umz`q;9D9f6LNJS05Rf_2w26f%@S!D0AUG z#VZ7srUPJbnuKwkxBe}@j`-FFyD{2vw3bZ@ox%yi(OS%l0j#`B!o$^Nq5~hL%LBVT zQwGP|D|ypSRHVU-^64Gz@{82brc|cGaC~~aNJo$pgiF`^#t)NKtDfnLxD{6y&>qHidh&GsYzPv5 znY2C$DXI6=@P%k+7S>P?zLJQqOC-l7DzFEaIe&NiPbkbE@D9rVds+VPHu2wWyj$Sb z+P}xO7uSnc#l^*zYJWyOPf(zx!O>U&n|(uiDQs$kj!^s?F)ieoy1nq;#Puz8S-5`< z7ruS5tuCh8N?6dQfhMhnY*=5LDL6U=uA2(BC@k7~dGEeYVlf6lJ_8jtkE2#$Hmu2d zc%4d~?=T$auDXLCtI;Nhom=ONF(;0oCNgx%1zgz}_SDy_5P_9s>g(Nvm~e@u5Cc;_ zP7?N~QtLtS?SUKf#@}Tl!*37`?7ETn)1?2Bpe*G`xQPU`Ivh_6%zhHF%;kLju;z zcy*KabdeS2=C!X|~;bY@`_@l=%Xs2U^#)zge+vt=A!SK^8My3ug6?0;H_$#zH2# z7|tlma&FRJ6+nA_ZVrHQ$vioDQqtzvAdD)BG6AW-ckumMVb*NvPO{;v{(B8p} zGu5>x08bQ{W}v#Bimx4GAi_cnyiwa0e@N)m>53_rzq}_)k@xxN{5gp*Cx1}J1!qrq z_-(!;c-in}n2TxW=SaP;ERH*ELAZzQH6!-2&Z{zCYuO|pW*eazv}V}#sjJaGTLl~5 z<|HZvBv*Kc|NR?&zsEKI_dDRGbwE}Aml^dC0lqydttNZgB=9;GqHDvRvef&*QrC;y zPk6~ah0`WmtU7Vbchdi-|K8a6IHW7H^O9L+a8BR+@jvf18iPLjTm>--Hv z`S+D9TwRr~J4AKBNd4M_4aJE=YMf}dPyV&S!6j{&O1c8#W#Jt9eAQvNRA(B{>$AnB zZd%&Ws^o3-{ZV%q(~$4yY9Xge%6Tf{_ZQo?w|@tg>Hf=ID89Ii&w7}lb7m*>LT}gu zWRMn#Hgjr-ov5ZbfEtf^^pQ+Cz!6MA(p~TsFPH!rEQsb1Qq0zxH{cj^8!ij321`K zuot5G;Y4eaOzPW6Hd|xZPpSdM2!vKKXlxsppu2Bs%-w1t!{|Kb|FzkWemnx+>~Crf znuDA_SWl%z9Z5O~wtfE1r5m2l5Nxv{2Q3zOPsG){-KF( zXdOiwA)obpa5@osKBUc~B^fg$`OXjj#teYJ!d{VBj)W{j^9%0Su8ombgTYz<(LH<_ zgW7JWO+(7i+b3`m%e@O_{9gl`f|rQ;tcYb;_>ds(*^w?=0~$VCBIKF(i4>5pfV9#P zNqTnm?dQKh{tH5Oz&)t5Mf>-}kZJ^kiZZ$yRx#|U<0W0LK>=VBZgW}~NslwZva{1K zwhp(S7b{jgV_>BGdgbq9I1pV2vV>b?cE&`?JP{0PBoFH2qENv@b-ep;hy^1-W$G=sXF-;5o=g&g2hHCLtYw$!+@1sI%s z(j|ypTr2a)QbvPSaQHo*yy%2>#6fzi-r#yYH*^uuuj;4CI@<~ho3zyYG0#{F<6bJWUZCK@Vv*=o(fK#oycT{e);q zfc^EGSNSZjHuTAJwf^Ia7O2nN^QKpm+cB=2qV*#gn%2t6%rgwYGQ%xYedK3uuqd#d zp~KZ=!z5TVLPB64+LZs-3^*k6R9BN&@Rbt@wpQvK%y^Y!iHeo(&$yBJ?MK8z;`ZL! zy|2+0S+%2RbTb%#@AwuU6oIHDDLRo(b{EeXpIV`AaHSY1k_De9(NX{Jv4)vm;O^k` z7RDafg0388W;xE_Svw>9T_UNOygvN8M-jJ0a`oF{05sdE)d-KPtJSmPO07lB*0>oo z#r;F{{Xs-S|fF@%W2(IM3~Kw(}PQ3OY0yYNiP+Qcz;@zb+*hMUF89{Ud>R z6;S40+K#{S!ld7M&J2kMzFto@DX$<;s~bzUod9&wI>ai|;&+c5(O;tNK@WWbc&@CB z&A&J99B1+v!Et@EJx87LC+8N{Lo!Ie=ob`K{IYcT{{NN6O94vV&1DC}uTUeyvNL#- zKk0W!cE;WFY2e!x_}!uYH*rzX#Y-IX+iud{#_QCxf&d@#2HuS)x(1=c3VvcZRF0y%Myq zNcxr0Tu7duD}>s0|5?$X1GujBR;#SKQ}^x>f6$K z9svHMC~Ciha->cnvS>oj;H-g001F^gWHTJFupgnj_+I%T+#77eG~Qka54Dgk zg56$}pIx`VIN=l@g%`eb{f6(E3agDxA6UUn^S0$NZ^|gu<}JIcL-!PC08xxVliIzLR(V*`c2-H^2C^ zG{L0Y_IUjx=okgCZ&(2cCG>KmiRfA$J2RjSHt0Uz3J^sS`x0J!$}nD3EbNghWYEd| z>}t5t4Dx4~lwy;DF{Jl97@Z`AyD5A-K)?o{rIsmymy2G$k}i)q<99ETK+NF*t!`^r z(b?T-Db|C@Np^5xOJZQ?w3B3G^h4k+R z!Ss66kr9V@3t5&Z){g}i`e>Y7A+aw;?Q#VKi+Zi|F%u@HZ@0Ug>(+GHV{TA~)!TEr z03Gn1gfiB6c$ZtZZkOFzLqkJ|Q0l)hzxr>D%7}qR!5pjm#nj-yH!b`Q#5r!Tq3^(2<21t^pklVj*7+dAS4seUrWupX zs@e9O+o6zU#Crx{v0|#x2A|*sj4I+>Z@onDazuXj(br{@Vw$-i6F()I1KT%?5m_)2 z^tFv@k99>JeKs|k1y*(nLb(PA%?t~@7JSt}%{kx+aDdRu#<+Jp{~uXz9aYsAbq$|; z;UeALUD8OWbT>+Oh)B281rZ4a0SO7|?(S}+yHiS#l&<&qd%kCkZ@lk+3>gE@K4 z*P3h2xe6(83X1-!p=me{L{1WBNJ4D71XvDLFv?o;4oS(}zH-zLf@zyay;ykpvCr@M z9kQcSw44)cYef&dArHLPZpnA?8Cq)J%lG1&8t1nR;9y1rHgf!=7+XuMrH*~(_&S|_ zgh$;N#WJtd*v0$`CqL(J1|F-6`d=cldK5pKdH;~7q}lR`MO``@mK1gD`4(c3B#M-f zYo7hRhz%o0lO#I&i)sQxOEY?8-{&fPF*_NZ^&*RC>>yfH?7K7vyY8Ecb^_P{Dg_@C z>bNp7RURa|cl@Smb>?_?I+SD1`Q?Ro6<3}7VXx~*$4S6iW$x=TmQ%6}h+O^3*981X zMevC48$>O+Dm;y=$0eS|G@rd@AUsGCq$V6ie`1!@PjHR+9QWM#;Cq_Jd-@)6r`n!3 z-mN`-*ep12;NFD;y$B16hO}6?*zS(5*LcwgJ|$^&p48dQl2f#y+O)z{2r_y}?RwM4 zSgBsCKGoILfHSDfudRZk9!R)>3Xs5#Aw)5DL}a6Oc@M2XGgd=oRPa`cDC8pzR!+;n z!e@8Hm4SqQr}(MO0@WcxE`SlEFYIh*hV-=k!WZrd`My!1j&D}6Xc5<4-D+$(k9R+3 zQmOO0Fl8P(oDqt*g=}Cv1Zr%zMH^=QKb)$MY{&571-b5x{os1F!{y*;o(W50S$m;1 z{VSe`syf&*f?bl$id?^dkAR1k#MV(ppLP4XisCEjK@{s8h7$8iHM68{42kb>au9L> zbRM=Ui>9G18jzn}lO7eAI}X)J(ST2=w|K~Q_rEMlQDP{#a8m-dxFfGlghAbkF|CFf z3pxz<;~s5=s^BC>9L`#oiB~UD1nnSGbO8}RF95d*=)>Y&4^+AQGwRNm$u*HI5h0k#- z&gnC%QLkgm%mU_N4DvLC*?^nZ_-{{Vxi4gk_EL~G%kHMxW;9^6df%$T_AyvY>C0P; zy>Znw8e6&xJU>+`O1iyn_t(f;ZfZ^%?DHGM#V)qt0cwR4p-F0nGU z8D#qj*8+uCr#`p~vb(3w#&s@!ceWgD+ly#zk3p*SM!ubwV@CJ+MCmiOB0|T=UUY6f zkWGe5_o`5tXnuutMGC)6K!|qya~6ORw|7~xvEm!W$ff_hGLPH&ANE|P4$3_9W3V}5n!GuTsbj3_O^+W_X z%uqH_Ijm%{Q#*ZnK)e+N76y4P5lou#+Mps_vM^MeFkF(ib8**UiuG{ZV`Ej*3P{RD zbfIX+!^57%?TCQSiZFvlX*&8mY+dkP*&ygJy!3={J-H?y6lzUTwx#J%*|&qZ zL7rKrA-lQ~rTQDf&q%{m-wj z+nvZ;xfcAJK@A@eO|Xl0KE=`fYwfpAzPM-+-!h!gES)4hRWMv~|KJA`wAM+lG>y=VkA+qvG#&{n3o6K(l|ooL zCqE5EFM)*-nwv)0LQrdc2}qcazi*t@tE#C6x*SmYJskKmL764EIUSv|$7$voGqgs2 zY`=dMF8K%Axj3wR=UN#+B#ZG5$!jKTb9YT2$Y*ZF?=Oh3(vuOO0|?O~hXocGGB*eo zpuga~`x-FDJgsa^;UnQ57Q_MEUQjW%Dft1cVMPZSzozP!ebR~TP$CD=37RU~OlswsgwcBo-e8AuN%;zS7XSz-S1V4^Sn@vNJEH%Cw1gRqaCV;)M<@gaUX^rx( zFp6=D>ASb0!Do!vRC)#b09udk52n0t7H0%xGQgw#mYrF0$Cev5w|`ixp2x7X6%u}M z`;O_nUjNs5aN8zB6!MEmN9H1G$i#dI+z!VS^P{ds{%*1U)Qr8Bu!a@O_dx^mm8+CB zD#5$MYNytVSHM^6o1^AqN(u@B5C@q3j$C7^0l%CX6lW zw_KM=()ebnULs)k(Xim`=}Odn&7!3{Dd?|Btsi$K(@pjPw zPP|8`iuUO>>IA56c}rJvecyNCHKP0XX}6Uu@JYbb`g>m;g1?7#?*zx0jtTevPE4-G zd@~oL;+KiR6Pb*|jMCrzr$oIA4PUbD$p{)Eq#-sBFH=RO4B`ERONlShlA#%1w``@Q zu=PF%5S%SS=x|DJOh|Ld{qjZun^ptAhrK~CF=P=~y z)626WUt#?Cvp5TZH$M2(61!xn$kP=G_9QdTq?Pi!Lms?R@g?4y2Ib9>bzhrtf-K&B z#y0s$d%f@b{HT9vjEjX%^<@pfYgR%FPO^W!Xq%pz-1fMO|K))Si(EmLU6ebX)Ruy) zFZ)WDjL)!5&fvV{GTL9=@fJCz#gn%8zsbFmuxn?jkL+9*E~W}Y5j0fp)W}E z!!6gzlc(4(Z&X@)FHP~=Nf1QNol;1Mi%g0jT%jrxba4i(z6U$frs1f~q8_xZ-9L6X z)USBnY$w_$doDTD*FJb${^|IQ%?L3jAV%odW2RmC(GIdhwkXlq=Kq#)f9M)_ zvP)WP-q)~*RNs>LoQ$g?#X;8#KV$gQDe=r$!U4e5<)9Eh)s8N=^%+KZ|8S(~C5~;5 z74WsQrOAkQnMNO#ecIq#@9X%NdiSG5z;Aw>H{5d)j@;r(Ds9E3^V~_aib$DL_1^*% zPeJ{!2Ao#VuFWlU(j-o+E?hDj106nP<-sZ5AA=$5$kzFCOiN?CbDp}Z>t2ksUE<`& zRm<+lMmN~ZIrbUzHF$a*OF#9Z7X-1k1-(+Vw`Vo(2Bc7H8=2FLvSG}8#(LP_mg!Dr zoF7c!Y86PuKdZ{K&xKY{o74_dhZ2FY^jgkI@moSnz zV2wavVY+AGM4i+LCay+6DT3pz*Az3R!L?hq)t_RX!5K zVRNXPNS50IR~NHfkcDB&ZCP|VZj);oWGdA=s+Ol%V11d{N_;|>RucjD&Bt`{@bbWh z^Y!v8im~-~=~wVh3Q+J#tdk6iYUg={??b=sZ`(j5Rk6B=d-4m8KHz|QC@fkH6d>Sk zxYkSDC*;dU;F+MCQ) zNT&&%T8bgPtz1knz$U@|dzwr*HC~OpI(nR%WwXdP!K%zXI_d9Cc81okZc@C`;yMU2 zLX`fO3t&}RaTMKmjK%e+UYr*GXxiS#%$67y!osaR3j>8Zn<7?^%O0uN-M0*eo6W>9 zRA=UK9bXj#xJw4moPe996<{$b9_ofKyxTZBZ@8dg5e0pS1oKxKm1 zPlElnE$`WvFlJPGR2=9<{bh8PLR5Z&Vh_RSC5`@{>KMXYl`8US%b- z;V`d3-RYq5)_`7(Av`loQhymw!7+kLGrR(p6s>^VGXXse%?VfPBAxP`szD!;2fO4t zk>c=JsuT^8)i2+8?DxHpjuG3LC0~GF05F6-`w3asVcQGxHA#S&HQKCG=YlBCkU(ic z<21SrpE(@=hZ@zZU=1`b6Z{M)(4Y9e0Y*HNqqd~<=@VfFIirbd_(Kxmzn9;wC0#w# z>?dqBC`UM+%32Jyz}5HZ4Tq|ff2UVYP4x*efcHMiLU>^PhZLWFnEi`U>-)@a&OVHd z)mX%)f*l(*>h7w914c%7KiWZ4N1YcvyAOj;6G5rJ85|%I#;A;>Akp+RxXHKCF(6I0gjqiMK&zM?V7~yVFJ!ucM5= zApfaz9i}D_Zii#|k+s3qM9%#JKhN)-!7xKFA`amW=Nqg`%LMC(yY{EM=GBX`FJuCs z9;^|Z2)}*R{^TzerZ+C`UT+jK^gQYoqledCu#i>xWc{3XKFG~;3s(xlnwqLNXGPhc zL0BX#_uIToEx`|S`@{8hQkW!;KLbRCA{FZcz4kUzRi(WdQG5uWxYF>S8+bfg{xlGc zB7uDLC205!(%&9@Ew_?m1lT|=AVP(0a8C<>g*W|6C)kT5PIevIe;NC`?8T+yaid20 zmzR(drmAGYVC>K35e6m9lJP4#VvEoo#kARGT_`bD5&cHmYV~Q_4YDTOlc@g%&1ryS zR2`s7?iE=G3;Wopv;xq)AnQLfs4O1xC}(u`(FQpWq11kMb(4W@(PFhaO^+sQ_Imdx zkZv${irTdW%rf8loh)J1Nhy+pRCGKX=9iE0sjNf|m9GsY#_)X9=kUAJkY5m^YE;)s zCEEA7t{}p(+HQ0mX!MI#MyD~L-`^=;rJJh)e2mJ;xbaQSfn*~2_mnn54UQscBlU!4 zf2WMa+9fR4Td%BJ2Y3jCDZU2LK|Qbrwgy5iB0N>9zZ0=zhE;F{zVwBs(}WoLY{!Gt z*^x}?PorX2%X6(q9?vkzulK;g)T>u*0>7H|jg0QkC7#Z~S*W#oY>%@}53}7^5}!>$ z2<3K4;$cc#O(<87?T6c_kid$2oVV*B0kWXP(3a-|(&j?V|FGPNq@N`a6tKfvr0!uZ za*5~|_!*l=^cq=gR$>fP97o|FkljJ(=ui%mt!Z%D>5I=+QO7HOPO9f?A5r;$Z^0+9GuL+P6u>hBe$cFbQgwDWrmRmkcP)tM$P9&xiX=63 zeAX=#MQoKe=yF}5vig#*6UpC`h+1k?P>Kf1DV3G2Wy19SmcbM>;R<^OLo8{r{fw># zs??LQ3bLAr2G8IYYVJSoDM;keG;Ek9yL{y&US@y{2k+gSkI=(R#cyxugu7{Vv3hsG zOQ*p?N6J~;L_@{4Klu6@l(hMRlV_hm>E*+`W%PnbQv6^u=ezL z)!mX}U)H!&)_io^i4}0tgQwoIMRDBlD^?j~8X*Gdx6}EIOiWH~H#@DqR{_7Z({Fz< zN!(1OKkA6KgsiXwM%TYOMq@p@#pi8hb|Qpq9zsdI6EOp%G0fO5Q|oEdK0Fc zXj=)B@m~smyH7LC3JbK0c7Ez9?Zjv>x18aLE0J$N%0TVvhisrzKZR@nY*G^)T={X2O0TR{>HyHs8ijy;hRHAR;L zf_C%2DlU`NKOomQzK^9ux!>nX<(N|iWg)VqyuY{kO8|_U#+WI-br12iJvBpBH7*DG6OnazsB5+=+{y-7#J|I`i^=q ziXVt$eCcuV3u*VIo-49Bjzlsb;Rb#fzazJF-@B!?(ZJKqNY2ON_S@p8`>`kV`&X>- zL;rqS_TKtJWb8ii-S)>#FR0`BJEbn)v4(&pdJ+@u_shY_cgZe4?NUDQue_6YHyNeR zFPzhpSZ?tnwzo=a(>q30!A{E$Yyk)~-;9~cdjo7MU!t6FsfBqlzlDT4LPDi(cg3Q| zKKU^RX+8~qC_5WY!^KT^tOpFkB>&`6qR&Hh=3|C2T{Jjn5BzHYU9fkLk?}!of7G`W z#;mMq%+kfd-)sw)jI}_lRa#2zcMXQ6D0a|LOt}fDfEEWm5vobY z8pyD|748Kizi{n$AUc|Qbt1*ezle#VgxDnIN5%13u}T?n(XiV82=YOm8ATc*ECV4x z0o)_04K3pYTP==#q{2WT;@EYIs`ajSPkAN_$6$WMMh4RK*KvV5o6=xFJE{Ea=R5sp z@K{DhOHny|p7fft=0xnFq2j?R&Q~*F;Gq&dp>2Dd2T6NEsn1uSTYF5aeha8NA0-7s zaz@r27&#Z;F^8(lw9;cji-OO2MWPuy#zY^lw**$bEf3~6+wadn8Wma4T7)@qo*g)r zgU*Lo#uBo*nYpwneMamy*%*YKvlw|c;;;_X`6|j9sn56 zc^DIo%|~uX)f#hzCmj-}@Y8m2+BO_WA$`c*EmC@G@*L5QK_SQGi- zG_wUaAl$Pd?=6<7*WZyxUiE}Q^k2WM>Ix7M0agzR1nsF8D&Wi&0hU57xL4O(Hv}Pu z`0CmHguOb3*mQu%S;qas2npP9g{F(d0>DO?qS$L+$(1GfL%YEL1^)UI^O+VaJv`zxqDD zntmT3w)VHk9BvL&sC4suc%tOr)IHou)?K2LAyzXp(wO>E*Hvg`UwHt~-WE|z!xysbxfEqTV?zYgB#hN`ni z=C7Y8raufCdMSIN5gsnIjhO~`4&3oag>^BQCH*k;yy@I;v^J))!GZz!M=oak`D8oc zy{y1ze4R&!^&bK%_Mq%cJt3)$G8am?d)vHx@1tAxJAv(`+L=jA1(4yGH05Ruc=wu> zx#_;_5({^*BVlvl?WepR?3gSIR%mXSEeZ3FlHPcHkkL;FI{%b>9LNGrdCAPyf@?CmE0Ao_IYBgX z#WSN{{4l$p0jNJkm0GWJh`U}mZoMmOaDn$10~xaiw{;FnKi)fczguP4= z^DC77_8*BZ3{N|CtxsHyyH{$}s}*$*ecl^pmeP*xS4V2nO@B{*|9eDCb_Dp_-*)2J z0Kdd@gaP$Gz7WaTY{8#hJRTS}yICh`IFMAJ!O}@W;xrL!=yTjwVPSv0>T%Qo7P~;# zBhe54w@Y0nF3Z4rF46w2y4a<&b^4N*xLv>UUHWRZ!{wmD^v-e_X95^(mT zkg1NsN3?P*U^5Aw`gr*vgcSkKBjLuj_%l%P88Ab8a-QzA~Am+FXKXB;2AjXXz%{~hm+ zJ~I6V{F3HGQf$MmC^n^g*n|0$sij!b37z@o>)Z8SQgTMj!Z&Vw>Qyi9JtO7y`Gs^%w&S}HBqgl#bK$lZmqE;2T;H|^e)hfgXEY#{cg*@ z!?uj;?bw>X=Yi{(BoWvpGRdFgit$_+#Fy%|<^c*J9scc$m>IZJCk;u2LF^&~&<TWRYBVDdJim!xKD`J;cxE9Rcgho=P?&cmH&+Z$G!o*6?y*Z<6zh>TX`jYNB@| zpGO6re4z3>w4^d@4`|I|-c9pb)qQPT>$a-~T=xmIovwetS_R><{2%XsKU}RnF$JD6 zZEbBO8o8o8Ri{53+CFV^K0-}7+1Ogn;>-Q|MOL{*McM9i^Ofc2j++k3lsQ{S z$0+r0hqj)mfNy7w;o`@PZxQ>lz#XlPs6_Dqbc_}9l#ha#tc@+o2P z^HKjlJx=L6SN$k7PghaR!1}jJ4X5s((mwr$tK?>g*XikZ7pIm#fs?3u2XR|4M<}gz zTheY9KHGdgn}*(xxy$Eav6*&#kv?|3$m@jiv{p;}4rz165*m ze+vJ|zbU(1F(O_c$s&2I^}A7lF8BC96WjairFQ!F?kAA^`#U-KCcFUL&mu#m@seKUVq;pBcQzf8i%V)Fv$@v*V$@kag#2KO@YTnPV!)zy}-CSvVpv5B#n71pE1 zHq&;p=T8_j`u-2n{L|m!tN_1NhpWz;z~n_uWGc5-mC$wfgRdH?u|U%6 zjqUyOF)`mw_Wb&XQ70W}yT)4_)u| z^!Qk)HZ3Y&9k)NMR|8yntZFJoA*L-Z#}957MKI^b6wVN1tVGlsaMSzTIEY-14U5gs zZYj8Vc=v{)-F9ywR?pn2-T%~%hITZ)cJkg$F^wPEmVh{~#>smp6rRR(?Q#Y>v_oG! zZS0$lOtY4+TqAkEFG{kX#`2vbEWX{PY$O6kg?Bwp?zIp4`xzPe!=bXvq3%gXggGz; z(H?lapZ}UQe$4;KP2%x1I`GOX zkO(k&x}7^-tUV|;eR!*l#+5!M(8{1XC1bJwbFoaXQqq?|NcSlJqUB_G0(?M_w`l*W z!m+{GI};V~P=Eq4g%!r-~2sKp_RySbtdZ;Fx5 zIs??z;txXkw1z*fQF35ezsqsn_?``s!tS$a^K3{OMj9k?0h7dp1|@v|=o4C~VJF-ed$7QbhnF;dyq{ z&w-4KMThVd&q5ohBuhE!+;`PA{A*HtBH0A?F~z?aiD##!OU{Lw(`bjMcVkL*v8TT~ zgYS~@UH=A}niLF1kPa&9Xo@Svdc*;e-08|^jrixR05KtU_#^LPyGg|qkD_KV5(Eyh zwR+AG;rvs%74fY)k!#`2kth-DyA1eBcJ4<0emXulA}4?WlCRLEwuXl(AsA-o_B@*J zF#I&%0H!Tx9_bA}w$BUqJzlqzndNr~iRk{S=64@q4Ek7v0@!~d$Aqo~*#)t%0AIEJ z=1?PU`kcsE2(0G*e9^pB80;7R#drG{%{d1#^V2Py8q4Y-h5QahLKSjhXTtN&SRR%% zxqeAy*tDOz*-3-=23qE=+M)gpUu%FDjQ5TE%K;3DvzX}5QBhGf z^Lu-HRQH`!A%SZM2ngVQ18GTK%P#$(Yl!2wzj51rhPwE@psg8l9CzNUw3oeSTzLbN zpe7ukymxAUT<)Z%IYfnXTXpVz0SNi>~n%_gc#9H%Bs4vJE?SAt3+^G_2ww~ymllGbbC`fsw zT7S(&XD|i@2x;P*PyhrUoDP}x7Et%I@&cn$J*jIi50;8qf8y_uo*X|JV;bZMB9|%R zeyhaK?8(Sj{zH)?_|X=1IqbVRf9LVNo`9I?a?de3)GM?aj;?Yi)(7T%)BfeSBvL*I za2cI!G@PQ7G72?mAiyUwgPX~UNMB8n;Spw^&s=w?=NPYUGTeEe?ZV>O*rklI0z+0t zwq@KO*2L?;IufKVgMPMY{;&%ix^V9gKEr5ZdUr>v2b`jo4uSa{doBs~jP$yGYHV_) zzw^qgS=cT|2-j`f?pBWb{yH8tY+*_bEZC+$fM|^W?NmDGUtC?@cKcR!YV~%uJ^=g| z4#LQPd4&Jf%GJYh;FG=SU9z|LAn}3uU( zaf*o8w~lUka1gyUOC>UyHVa$9X(_d8JRljj4Jx0Ix%zb~t}+WUVAa`?y6sOt9VM;^ zsg+_ZPk&ahtqUKt#=RN@D)eS#Ig+i{z73)0Ra|G6gr=-FyT=&5+%|-FMUOM@*?Wma zmY3f=(rr;-lFrIpUsBJ?B>x@=vXtls$peVC5`vI!!D<`5`K}Ewg_@gobDYlwkzMUF zBo31+!S*R9J9dd(z&v}0QHH^o(ux0a3=w`Eb6BZ3arPOjJ(b?i^Kh?30dI(-Pu^wkD?D(Hx7Q9U{C!883sg&rGPh1ZtDC&brk zeLyLLxgzf2eU5P@6IkncfAneF{`Y&_KVX?XnVoVf}g>roSPcF z5=;}sctsBDHNfkfAFC;8vU`~!>{@_KWe9HyhiLth{Um2)kMnDW8ReS~`Zj@#UY;Po zqZI*8y2Qv`shPB%y4B)Y#b^rz6%!bX70S>km{+*gT!*)k zL$Cf$q3%Qc<7Z^UYN%o?zCI6oRjQfRh#-cb7EbSqVg><%E_!!j%_dpIadOekZPI-I z489QV*DSA3w!R`lMYR^_#!wjXF!b}?wywH;lzJ*QbqIB|(b)EwDC*ZjHPoNUPPnuE z`sw~NJt-HJgc&DvtJxWP_Oub3W^u}Buz7qN8Sn57v`{EpIKU{?@4)G#uigk7aH9dS z`;7*~yQM2`d^7ehbetv9=xhtNN{+W#cA&>Zj3=`se;rwdMX`@0By^DKv|45CH9(y| zM3=VBgFenRPJys0(qB7#lh8M^5K#QEH22S@r-DaN%U-s^VEv>iia_oY>K$p zUDGi#HF4kN=@KN9`jI_kF<3X*jnuFsN1o@c%kGCle;tjRF?Rq>Z(2Nx(jfo1n89|a za*p7pN^xqi-HmhuxWr7qC^hz5GKLFfvMOtq64;}F^q3C$;qqa0kq^?8VUiH|bt3J+ zu$a0%37E-*cSt5x{QA7Y8;dW7XBo%+*=f18?=a~I7JB$e4g>amIcmc`hZFuBA z0e#%-|KCpNbA7j$dvtkkbkHiIdTkp`#ql?3lV@T=a#O{_7_fIHR>}$psZI10vjCD; zi#1Hr#*bx;=gb|{PMlVX&#j(uL%KT^A5|IiY)S^eUPjS?W~uH6BjDLyl<$kvK zc79Mm&M>io@8k8Pwfj!pg4bDd7fppi(sUCdZpXFKjJ%4YuQu(t9@5$5Md>$ERRVK! z8~zkMsQD42;(xvywOPSZl&~a~+|Rn}WO12kPmbRBW&^RW`of`;y1XErfg3kI%i#HC z1}w;s_?&?^?pzL$b)kQPR;Jz$l%6vk$>3$-cZD$6y&GqRM9GxAz(8TzWI{!ir2VsX zWX&we`-L!r6+v>P0zFbv6wj#&-7FY%A^mqpq?PV5vg8{#gBlzd>i9v7I>PnyVKJng zY%lkb{=@_ChU6oT%e3u`t*#qK131mOd|TT7(XltJ294VHujeyeuUucb)(od>D-EK- z%|El|sdvfZOHpz6_C8BNt{LaFOvdz}2Wgw1!9$sI?V|XFn4DFBbrG0+DmV z4LXa522El!vMC-6ArWS7>=VA5Y|F|3=qJJHINkJ3iqtUn4)1WuPL7%HgoVgBLwbJo z=pcn8;#;f=5eD$vMxB+Gss2@gk?bVo5!IgR53f6pSNfK{p9&pAX}Cfh0j~qC##(-~ z*saQZ3@`HTTb+Q|w|&#k4K6BwGY6hZMCtuVvQ=+PMauhLxWA;R!z~mk_OnVr)_Z z5_CW`3qY7V=>Aq?K@oxFv>%Lr6J5@trDNZ#0k;SfZ$uvv|8SH+!cX!J$07+aRcc$z zT+K&QGYedD=TyGCIYQ(RnD5quHirP_sIEAu`vt87)S;UVB%E&E(ZLo);q%NKQ=Y=% zChdD$Z$nAwP&G1{J6uN)AzopAJ~xCJ$uzVYpk(m}ou100_HeK5AX+gT$D77A& zA_`JBMS#uIl%jo?5Y~i$ESp2#ev3!OL$mwS4iYh_EOCkp46yG`(*}PKwvb@>i-YGS z4Z1!)WdPO{E;zJ{gX6}m|89f-9Me^abQh*L zJRpRCF4>mYf4-BcgC7D#neX63k|rFyRKOCB=@<`d?6ri;`6z+f@z!(Hu4IK@K~&D{ z9U=bDKzdOHZxkW51LlGO907WS-TnBIwM)kk4geuQB|(fV#q2{2$t$mkXXYq24_fwI z!)twXy+%{f3b8o@pjEw6HyI*KA+R0onRn8CjKqf(4R|VHhF~L#km*ZAQc;7Q=j`8* z@jI}|r@P)u@avUjqUx??01)796UfwH+rd$$E-5w-sDf(3ttke@aGO3_D?+LBwq?;O zPE9{L2U#Y?zDmNhSdQkD<+EG}hkgc+{M|vdJmDA#6(O&_%Mw`e5Cz=QgCs-WA9ows z&qS{@`$W8|6T=4PXuVbZD93tR!o(b8&UFq<(sdnq{Fi-iP#p03ti)u zb(TYotoXW%_FYt43hU-+W)opUqEXwuCOgIJA zX$iU5m-6IM#{Zg??2?bjGi>mWKK;m~zJ8$oaOL=Nov@z9VrS3di$4s9*C8=YOl6AJ z#%Z+u{45I=1jT1$8=SK3CzfR|t84*lXD)Pz6QbGsw%hSXl2d#w^sJ7u)*U=Aa^kgF zjABwURBVZL3)TL>2%NaE#Kh-bdEwAs4cLfeDT#RIdMh4l9~q4HfL$P61czDqiWPM3 z0#){Fu3N3ww-S_s>px~;KdC5~J2w30>~pfvP}g$O%AF(IN`htyWHP#LoqXL4>!UT` z1u*7R<-Y&9+WLgGj-=oEf6vUMwHN26)hOg1K6v!v1KIwalTenkK!#ZJ7cbWn?sIq1 zxVxRn2q7y~8P8@0Zq(^rHO;$XYY=NdTGcCrr}7H#sS2HNayL~2_**0Pj@%*$5R3ma zU2oy;Q!zEkTjrG`i?bw~03S~}#V3=h0YGvA@CQtzu z96hNhk+V>0o0CjDDV1s_ABF30id>V(cnL%Mk?LsUX^6uQfgc&Lxe&W!LIgfL6*uXA z`SQ=H_8;cJCre1aQwd8IV&GdFd9$DrxhM5?P`d0jFPjvI*hhpl@T`B_<}ZakUMOfD zq}FA-$IW4+>lyU(#DH#5M?~erctH_yDLU)@18lO3+X4ojHDKBYB2?y^=wlp6Qi9_X`P1`cU-W8LQ6eS zp!L7l0nqfhS}`n23$ZmJ=;RQOL3JDfTvRF_NC7P5B6eUMh@(!k z0?$k}_@^S@7Jj?eBPC{44|rhH*>gWjEyN9)Bx1~5=bun;4zyyM!^w0c-i{j_BY znhs1ZExA1xsH};);9Jp`B=gn!SGB6d(*JFbVB79V_FbL?Gc-N1>JY+=ihzaHadmdd zJ8vkQQ4Rnvqitk+r|0CpIRiWZ+uSg{llgbFPPYg)MJ-#V7y@=l^ECeGG~LivOE8~0 zBLukVD$#ptl4IjmnFCL$bJn+JgV-jMS0W{VHBRaN*? zT=Fp)@;5!5uPpfyhP@7@LroyDa{^5ymmD>BZ)kh76s<4$>wtg*>3@n1_5y@nPlfJ*ljedr|9r@$M6|ivmkHH*%-m9yeU5NqaI;&=_AI$|F;n7{8YB!EgXYm zoFM)oDq4SBMz)11`SQphL2j*oMv`cSB)+>;~>S&~^_DRdLIoUD<%K8%jbkGP0S?)ZOeC{NV};a60bdfe!qPQ?`!1^tS5|58Yaf^VNbWlP3qmsh*F;LrUjZwVVCh zdlC;Uo8ymFJdE$fY$3wF=?jGs?jHrwu=)2#eOCCFVG5u6MH_JUOkjdxFV4EfQV6tF`+DXG6kb0_B|DWadIlQDHCtBuzxo zA{V};&WVU0gIWo(VylDytF_a+8Iz~L=XIPuPD~!YS}x=@k~wOG;KHi9kj4^Z9 zUaTxm)jNF+m$amqg-O5lu{JKBAk&q>VJR<3i9J3b%Ov-M!>+7S->{3D&zbiWJxhZX zl#1h^RNf-iHMI81H3JmyxCM4cj6qUJax{{US_dR-){C0+O#B=)-b z++T)c?79@!6AIpEFbh1t{q$OQCWBAgtg;9QlW-_(b16_WEE>b{A0#T9R0T_k@R2AVTife&*v%f8}_m(e~0fazy_k8SBuHFT0BqG-bXEz$8x($ zq1Q({)zQV=((2hd(2L}J9Tl2@9Dgk<-V&DK3xl78fUTK@AQJL&@*91n?otT+Xe)o9Md;0yMA z$`Pap7wdoBJpO0H82ievw4D<5 zr;Gq_=>M!{BmRNv$e5Cla(jDTy<5o4cU)D_()*n7;@b&};LAuRs5KEaHr1y}9jePC zE_$m&T~p_saMkVd-g{q>8WzdLM7+7wlF$1Ad!j%lYZf@b5i8wD&yv-r!6?vYs8NBhoAt^&thhl~uwq>yQ^f>CgO3fvoQ51)&VHA)*eKWS?B* zMvi?!WGq9UQ)K)~6>;(5BS{u)bBinCclRnqXb9Wg3=>UDSrQ}E8kMW=O1*3Dvwbmf zZ8d<`#xSuA$)lycLwH#^p%mzAguib~ltD||kM4%0=bK`CZe*^OC(*q$Ke_t6A5OdZ z^Mr86O78mnqcOZv9_c#MS>)U3hhx1z+&a1_hzl@ekr&dq)!mJFKs*Pa5pqucob-LH&8`VH< zoM1zc`GW7#ct(Q*c#i0@Mm`we?gCuiKRReU7TCIWI-mQa9l#?b*%G&RpX*GU+ z3EVe+;b{k)X0p#58)`GtK1#FAd}uHLT(L zLc~$H8R|IOMMd=$M@P|OXgJ#IKMPdYG4&ERo||2||6(Rb?wkr;9Rut!LVwGjL<}w5 zk7N}&Wf;>jG|bTQO$Yi3zNVFd-=E)c$T|eF%H7=^Xz#Ew=NYBpr#|$G<>6&$vcO-w zA;v61PZHc9IZQNP%p;{t9zGB6F^ig(p=`}Bk9#S zawz4H#2|3DMAg4kw~WaEzpk;CO-r2icj#x;b!tXIUA4Q1MGi@%_gQ|lq8vYv-Tnr3 zdzHMRk^f#aVZEuWueF{YdkjXB<>}cUX*=x0gP+F>ow?X4IIZARu5r8AIQix#orNJ@ z5Tt*bBm{vn(O;{OOyJP5Pbb zI4W&XdElt0+tEc$t%lV6?=(6v3gQ$z-_eG5+nHLtYGGV}&9COBSxe3d6fp(ka92-v z-*QOih)5$>i{$_SB}>^-ta*^!aGN6IF9^SnRw{r;Zw{LcTJ z=bYy}*Ex0W`*z=-YrV(oJ+AjvUf<%0_0KI;QfLW|#zJYy*vj{R>e*()?d=I)Jc&$< zB92FtzP=^C=`Er0v4QWBZXw6dJMFMrKRzbUVuZ0lt6CbLxap`J>A!4_;3DD?T{53A z>hEGLRfF<9T$fM2nmN1r$n@`e!yX%HfB>&TyRP>G93 zv$k~4K;|qV-J8#%r(1<6dn5WwN#Al+OhgjLYd6}eec1e}FSndTf5Ndah%cb6hU)k* zg|E;63q{OID?-S-pAU2?%1j{f4hcAJ$4BXn8-oywhuUDk_rSbbKQH>$7X^TKrGyQ zot;Kfs_7PO^`n*rX5&vA)XL4>0}3?$5=rz&jz3FvJMp@iTU7mL=Q1EbB?hO*YL+xh z9{9=o0ItSa-sE5SrZxFOCKu_KHT*j2hA%pcX`u{&@~0tH=2gF6pn$HiV5w7PF{!XJk7g`pSMKg@9Y)tX(n8LumS0dE*Az-F zLg#u}5wB)$cj2Ov4Gm~8B0kO+TvAI{cY0Ixf|BT0O!=!9)p0etxT-XP5CeJMjMV8o z5sfXAN5&DWD&k1O%9D;_J4X>xRei#V`24%c5)`tCOyUdmQ4zw675)OAQ}|q{uvcGn zOFbo|!NxWAQJ&s~Rn>wt;>8tH3ymjPw_0xt5WxK5D7B9agN>*Ph?i@HL(zfKQSL7wn*&adMZsu=KRpg@fICLbV?8we&VUz9KP%>*2b=dPwK2b2hk^2T7z|A zTi;X%BMm$x^yKf5Dgc>d`O^cFH?wgyv6aUoA6{2j{^R2q(^m|}fxsIv!gr?9m-H*m z!V>1?HBO0@2*k_?TRm54E19!K(pQV#<8gOX!s>^#xqD#4SruR0XY#sfSnWV!9j)Q) zza`}_DZ6d1;Tfy1KwrW}B|)0$N*k@gN(sVM>T93hy3<8h_atpeQi0FKh-V<7a4_JP zwUcK0apD!&VHTzhEbY>$w{VprolCdn3J|7i08g1f_}34L9xwB)bke-mg-ST?A35r; zs=}&jX>dEB%%WoI$hGp9?$qx4SEu&O7)=G8$0Sq@mDy>Vc-B-d@{I9R z+%vnj0)m58#&>4-9xMl&@bCN$KB-bs;a8v{OFV9TILxPKvUUd-XT%^-!A6yMhfMJ3 z)nIB=@*WdQMCpp^r9{7;eh!L+%FXY|t;uGXlhhG*AIR&~OrkQQJWKlq>YIXWJ z)wyGQhbXxc{l;S-c3t-U67g&n|I#Isj^{_1Xir~SX2Z-%_*Bq$MSx&6cscl#%^db9 zq{bAht*<7>+7db_c{ob($1OoeQxm+RiOs7kbwY%px1}4O8;0WYoB5>T5yLD0q6%(x zx8s8VFs_qqYqcFERsq3*y_Mlv>ex?MN7WjCPKj%Afo5i*x(ZJ` zu9aCyyVp_ts3c79acjErQlna*f5hiT*&pBwM~=;!Papoh9aFD_rAZNpi+NSCQ^D?`$dgj=IcawR>N!*;((Zrq(iFtYo@B$A1hI_ZHnDupxZg zIO=C|Nn1MXXjpiC-;2b?Z=ScXuz=*awTae`>gwwJ1;bC_ypjH%DI^|i>N;p#y?Rwk zt9N5OsvJ^d`IwAOe5)zcX5Nv1+es95er`RspXc|U;=pk0QKf+Rn`$y_bT^&__rj4Y zu0I)D-#_sWx$MrTGpsG9jiYZH_waB@BJNqL8hzID+a{x`0R3LNZXUMgFf}jyIk)-F4ZC|LcqmGT7i4O_Kr#Yi5P)S~v)Gn@f@ zVG7TMY7UY2&1RFTMg=R|h+tn(BDZ2+N1B1TMUWXSYLZ-Yx_@M(N4U#Duvznx^>788 z&tKe}&QJ*xR*-=V{``kM**-o#M9h!>>~76Ri8xHf%KGL;iEWGp7TS8*@P5FRcGtY^ zk-lvT7tC^1+$$XQ@sc;uT*F2OPLm^a0%Ss|wBF-Y3IcJ#nw=}xJQ933|0)+bb6&4O zx@=Mb_BEA)$44cm<9|`lOt4a!-X!dB>+o7p9L{X+vhIPBs%FVl1}#n*(rk}uSd=JI z8wP~dA6DidkIsKTCK@`PV(;KU`0Vn})w1^Xc8BTC7gu7?n-O<(A5{^Vq33NcEhN#yivIfB)5j!X3BRpfo%>L=~!_3fSb*b?Q`*(#TlB;VM? zeGYTP`^Ndob9NtN!l(PA<)~?C>6w?3t(v(NX@BXMrTp!*t49=^X`{m#=xFA?znC_x zzABy=DPcaUUC-t%8oPn7Bup3@9DM8MO<|AS?X0`CesqGPze4o&%H4O85+Zxs+jF5D zsvI2b`a;C4Q($eVq0s^5b#q)+rhNH|>ei$9Z)ZlAl=QDReS634d4%EW3+mFTDRYv` zOCwG`Ug|OuJ7XVzx#m}ohjh-{PZUB)=*{qu4+_B@t#ep4tXfL)U~I7bp&{W*GK_oO zS_vHt+?weI%q$bi2px;at>U|aA&FL{$I8ho(ZDP~IFbX6L* z>tOO0%0KUrAE2avfk(g0cTR?JW~khwB1*7}t#Y*5*Q7bpZF`|sG@@zYXKnL`OF8lJ z>{t@-x?Hn1xco}rtFFN2=OCohK~`OI7j_t4IW>!~**h6)Y0JH)*U-`V5E-fbg8H=- zi>j`!xbZh^exH(=m)H2m`0>wHH2yiwJfSXgiR;@xWfCi7ucE~E|f}}-m}nO z)2(&SZ@Ak&U3Xd*cbLi5)*lW{D67&--Ahj19W6DdT5z#h zHF^C{Ekq-h+w4|(?(1)UXXJI6MA&S$FDZ{rEvKwV4e!2A$?H<*D;`___#Qvk z{LSdJQ@Qhw?;BY*$@!q9kVvC}D}y=ZOHY&@$go+gXC|rhkEK6*m+VEspx2)z8;)U= z;BlC0R|q=HV^ZCju{X5%Mn*(t>^px1gSOb-d56Yd32!nthdK%$tzD1m^r@Rr<4}yy zl5%2YifHWY#Pg`pQO6Y)7Cz`oAIP`TfAAn>Xg*5tE}YhH%Bp3Wwk=#-T3TUd5Oth^ z<47($`AlzWe=g7s*%S{D1V6jtz0$ADHSh~GBz68-n_`z+_bArl1zs5F@+C;i^pjV+ zQ(*ICo^vzJNcc!8C@91zN;y5XMGjd?FkaJ?UnyW*czn-Cxqj8e88tO67(urkABK(%ONctCf6{c&=ag?Q^b6mIobd`@;Qsj7C)syTms zr=48ed!dAbF*~j*|2W3)CbRT)f^SF2xWRN--}piCx^y8!ThzU5x$*#5oOc$>`~8Eh zIezx1pXsiMkfjj4#N&dY`Jo(>W}jo+@k-&r0Rgsih2!o(rkfNGhsxZRCtBNSy$m_S zy-t;_;E&zVA^*L{qf{Kkr(C8)PcBR4-<1BA&QIbHVt^xmCQaoZwC+gvf&5ddu)fTz z@9$QNQib=3KO4C?xfIma=lOkcm?^WkK|L@cJSb%8Qm!UOrBxvJCnqPL;pXm2y;E5&&3J|1vE8(+|h9yO8Pc zGL@7-!*kmj4)Of{^{aI88~0HT<+0I|!N-D6?T)<9F(G-I_k*U~U2>x0Tejw+ubZU({58$uX<(OH3;JzC78Mpb|AWF9$>uDeiin zmhAjoXK^>7Y51>R&=*9iRwuz&eRjQw&jZ0?6wlmog_l~kUvKiej25l2eKlp zgdGct1jzz~rYT#Vk*13R?3iDi7(}X_DqDIc{D~5?4pZE= zmRV4JYu~z<71_paSX>!n`i5VHkEi?D)T8eTjF}$}jFI^|f7a1v)PdT|QbE;O8=lsh zK#U`fd3c5T2{nyYnURC_8Ha!lIv-ZnCkFD}JBJakuuhH4X_7nQLQs?RO##3r54~&! zSGQ^A3rac#$;qEj8t&*dVHocf$fcTm%)%rn%_#(@e>H!lM1glP_4ZouyWhTE3xge~ zCoprHw-#l9aFGH~Fv#r@JBZ3Us*~rde3ib9`%M%gj#3Zf@%wVrm z4w6ns2cE&$czM}7&SSC1Kq z2j!^@$9e^6b}H4cReSupNObnds{dL6*J)85xvc7Mx*?S(sYmNyI5107DHskDcHaCi zAEkY-(dEKj%}mmko2HXb1_4D|uFtRZP8affQ0BLbxYYI?Ixai$hNSpQfcIBEDWqb! z@SzA{qJ{c{L6cw$bI0tMvO=)<=eLsOrLS+j-26>I#`%`m{;eR!ca&G(L39@Uw4^!( z9EM-CyD~}NF4Y+P^1J+R1n$!8*`T<+ld1fI`x|n#H?;bKw|v^isL*TRV)lH&hEe+L z9)6yX?&gaZ$_VcA)jB3u2RiaRB_)|}+|zZ$A~Im%d+wMuTK);A1V%``TyNM8CUsN7W?LR^7opn-J{XSZ^L1$!`6o>lpv_M}GQC20DT9p9=Xc zI;E;UNXu!*#w+^Db$n8;!p@3>rzzlu3^`3zFqIIxd!AqJOKYJLa^Hcb#$V>v9Ec2VY(q>jFl_>y-hoQdEEtLv!A-oeL{WR{GmT#_7qY z+T~yDh>MZH4Bw-~FTJD?q&4SPcgo@Xq@L6UwSABO;7e2wNS;inv!)ql;fo5Kq}f{D zuBIWqm^&WAK}%EWQ0%I%D1@+EoHo;Gy!p?1C|662`*2*Mg=h0&s6aR%1_Dn{I(V3b zcs*|GG)y?Us92!%{rRtBVtm z!Z`%@1o#bz+H7My#A2|ttgH|wq^5pRPHcw%ud6;Pk(bCyos_U}S6bu0X`0;}U(4JP>s>>?r{FYEjaC&J38|H;9zICPe^)~#_6yw8dWc3tQ`;zaK z_%K0yr;RO5w8fcQvNCa5pLX^ncAAu@H*F?}s{{z^SY;3?83=4*I8YjE(5SG{j*WkJKvWo?;;_}=)Jp*Jpq%htMig!0Fy8?NE(rX57$ z!6o@iR()Z_T82qeLGeTaT;f7BZA-t4Ac)y=J+_ADB5BK^+;=fGb*kFOzkPFZod)Ly z8%hlb#6@3k?b-js=U}zFZhz`Me=faXb|rPi@l4I6)UxI+R-U!ERd!QCKUE~%@Cctl z`k>#BHla9SMU>K{%3~hFS-XjHFPUf>hs1X=tT*)T$k`raP$&11n)rnvQ-?%M2FJ z;IlGWF~aNPuv6a`MBjNLo0JlvynGPu%TH33**-o9ddr8HhScz@lh9-&D@fg)6PKwr z;`1V?1oww!idSHBgfET4fCh*{o!LXqb!S?0SMb1z?Ng22ALnUza!J2bvOLbt6%H%) zDHaSKBGWUZ4(=k^s%|aQ4Dc&Oq@H?W?0R_y^C~*|vmpe-nB4~0Su@--!w)(dmM0v} zmB2l65e3S7JkT3c{_%wH^{Co|4%ibX+?mArI6fK5rcSF2#s{_4;UQ|=Tz@nh>E|0J zj^AG~cILkS8XWWL7c(vSy)Ji4w_dG!l|*}->La>cFTXld6S=nF2@OZz3A9rq!1ag- zvSIS3j@fg9>kfM49C1{>-4(^SFV%tqFnd9dhd|oLe_jPYC-@6@2yW-&rY}yjsxnhvRAAt+P(MK z`G_xN#48UxBzD-IQ?~FYzbNH2-3>0viZCkTBislgAE`%af_L?+7adX+ zYu=%6M@?iv%_#ifJ{yKmF(&!*$dj&o^9+xL1Pa=;^@3F4C@t#D=g$`33IxH>171py zH<&4U#=iD?r`dTf*B(yTHTRd%Ml0#;a)?eKhtkiZKMCvYrPxwO?hgwq;$>UVA_yA=kqI7r z?Yf%Ft&wbm5IHoLrA{DaWSsB_{bIc7wIdc>zLa=~)M5+ml|s7b5ZowVv7yA_S0IU; zPYAdh>z7TOx2`t&cma?K4OF1QyKi+39V8M^Oj~t^6Or21VkRP0MOdap00vVxOsXF6 zs6{J^AB7^2+tFMa7hf~NSd95O#bP16iAXWtwbo)ryo#FQh;h&V<+=Ke$%a3-8tL_K z3@2D4+|QZC+uX-a;vq2rQugBY1pokJ;c@jb{h?UF5Cs zawr6cV0cE5n1qpPN9h+U3FeI&Iqnx{4U~e#5Fm(xH1l(Z;{9o-tf&!J;2lf@G2ndV z>ey3G3e)tAB#&qdMUVw6w|@8y4sTk~2SIQ#FPOzMyrCzl#bF-k2cs2bP1!`RgV0e9 z*dxfx&Y&{~J@k;0yx|mp74xzqn**V*ehEQ#y59c}KH%~$3bZU(PAume@l`raa>O7w zzFlCpb{#fTo@sNGgZd~cKj6N2_fl;!_A|XL2GdgQyW-)P-c(^C;6Vt^G z9HH5!t+5J$>=Cx#xR!o@Z>XFK=36qUrAT1{m8X1dXa1_{&S&cQ&EGnuZJw zpU#AB;atg56Y<{0Q$o^j4Gpj7Q*{b$yE6^@=UP+J)8i=-)$3%Pew~r4%d>e8vP-as z6FCu_4=dN>zQF;~UY(qzk9wb^q-60}$a~jBWrNb2{J`O+PLBi>ie`E2?Sj|FIN7QM z_Mj)ngxO&0dwoI3q$xEisRx{B^X_ZKVPW*L-nr#ls8@D8(lxg$EiLWi)z@eE z_>@&t#;?A)%0ii#o*sGDnB>tdJajxY{HtPFD{iwZLG>Y`HtIc3vHfm1?VSOZJTx!$}7 zYqNb_y}eUwTPBU6{(*r@P@G2i+_?znQSaVnf@fd!cNar|^18>PJS?}Z#8Ju6%Uat{k0 zFo`IBe*QPUM2LXwx?w1$o#-n9k4vB(yU$32P?mSf$*{fX;6NyqBFvJl+J5}7tv%uN z>bTJF8V0Km7i~tt1>Dne1QBpsH-yO6KG%u#(Q7?B`OX$Ws-6Vu;t7wtDA%6+dn0f^Fa!N9m{nbky12ku-26sLi+|y zhzMY7%p{*uf~+C~Bl0&-(ne99v`0eLC%2}6Fo@@q5FwQ6THUj7Xa|u|H@N{!M#j56 zK`y34E~`ciIpDbOf71#}qW1kyb;Kly7nj9xzFKQUN;r`l524diPiDk=!U}Zv0rmhz zQZ}FRH)W5D6_Mh(Yb`6&PcZ!NkmBNn8J#nUVRUTI0I5{&VnNc?3=eq2oql*MKB$OC z3`|Gl*02Y&JzJ-|#I%|KBRh9!UYXz;LXN1lzsG{imNvguX+uN>ibDR-UqjCQ&0js|HdaTN&Xw3#F8T{HG&0RUcSO&2qht{EP_eH!7CLLn41%2NPqkJ6_1<}SHX-O<}xIS93J(jZ>AFW2@p!%Nx|+1s%3 zu!XmQT+lpNaO3^mdiwi#cr2KBpe1zo_EQPbZz6J9`=O*HqVlAjoRVxl070zC1nskT zu=r_Q4%Vl{9&OT_0&-PcOKg_%si9lCwzX=fTZ;9=LZz#OjZ}-3M_iL#H?pY3$9`~ENK_)fO zPky`>t13#<`%Qr8@2{s?9HG)Ia0S{buz*SsgSs>`NCwDFKKKw(e6mj_{b3MdKllju z9>ot8Z?)AeXrluU_5pT+OW-!J4txrs@&E2A8FHfkyQd`7C3Vo){~7)zV8i_e{rr8R zrJD1tll=vOC^O`mvMyFTZ9P5t4h*vW_SPC*BI|V!VUUot;_$%JYukM#0T=+h z{LxUYZ@;n8p!?1ke*mJv)x6^L7e>?k?OV#|{R5KBw6t0DmI84Xdq50?v^r?))mNT{ zavko)w1bK=WXuwe$Ljo{mf%mQ##v~K;HpSaw_cInBgs4uh_w1c0?dAs!oc(X1Z!I+ zrKjtGRt6yCAymNl0A0 zw98|#6>Tx4mKGMr{83;aH)%~6qG`s7+>IXmGn5rrn`esH@&Urh)) zJUSKujDyp{Ajf29b{p%k8XDi1UQ6yQw*jmvhpXETU`;}Vqm~kkTsLBOZF{{|a`2zQbLWoR zUW#5Z0>Q_X+5Dla>kWojVuIw9lmx~1qmIQ~N04^vR_&~nX`&F1_U_&RWJ5@7O<(Z$ zVw;@mS(qjQv%QH$5>F$lYE|+N9!x`Qjo}eVi}BZa@yGk1Wgezn?Q_hRhBx5P_7F$Z z<7|i-yN~b5RQ+6V7GwG;YMCD%Y@o_12t7SpskGtHvH86KUZ3#Z-ki1)(0a7G8S2Vz{8Z zR}c4r0(h_1k^H;x2og_V9@cuq>!agF=!LZhb zTD{oN^CuiRS3h7LK6r4{U+v>nn+&k`4_bwLZ*T9}vuDXylBgfOY>B-R(*nW-upm}; zgxu>YP(q^G$Fl9khUI1ZYxw({c0ei6!*yT~0bUJ_zTV!eevFgWjEi-Wu5%dsi;Nr} ztT7ih4L&6#v^iq-hq1rqfY$fN$4+aw7gh7c?VmvaBs+}C#J>%fc5(cBxEz<1%m?N1 zYFhmn+d_c6?bKj}?@tT3k{6!$^#|}{A;UkvLXbX|zls$7$bkD_bp`J}@5}eUU;Xbt zjY08gNjqEH6219L;~!8vK$S(x)&;Hrx_>RWr&(s^q-B2Hl z6#ubf$4nw0-FMkhmCW2w70W{7O)j+77HxEm(mA=*G0M;^bkm#|u0paxn{ABmsH6z7{-J0Sk@)!qkCh6pzBRWP5fmb!Y5!57RZIkF=%U$V3dnht8x zjY8omi-!+OhM$sx)D=Y+D#~pY1p$z6RAf}`(`Qw_0}KV_iT32*#Om`|(sKI5mfzCo zSXV*3%7UXYcmY-5N!f#$q-y8;!IJ1ddh`eiAnyX+(TCFU=$-R`Q$7VF(OY08qs1-X zacjDi>Y*bk8uj7Mr8W6rb5%`E4Xk?R-9Mg7&5}`C7#ts#L@88YWW)O8j8|{KQvpC$yP;n6@-GKdT&oFK;UmrSg^A)TM)3A}S*%#}0z#H(8`^Kp`fN zU9gE$^-4FNA5})zN%PvZZ(Io<&KiDwPDo0FmcK2BVq8GX6Xz`;$*SGH>C$+C4qr$^ zp5tt9Ewe}eFIzJT3Ghnjy#x^f;0=m8bJ%krbQ?Rn+uM(KqQFlxP-w@2kKHjM5$O53 z1hwuHii)&6;J?kMq5}uJ{a@+(mdK*T2!^QuM=Xr zLz9yMYN6ssGfnGVV4$=t9!r=Dc$J>Pddy`v@b!Th`<;3CD7y~S@P##&fE2zYPGq^G zwKdD4?|k`?3Xpv(RB(R=qU!eEIAB4!H%#9V+42v7?tc0y+@GABglgdx3$@JiD=y6L z>m#5@CHJBQ=s0)&yad1`$cNAa-ECqr-YUm@g6t42&+WG%A+%(N zppun7cwnZX4mqF)y$q+dxd9az49acbhXC43`1FZar=VrTz~-=l3R=9*7X)rd`L;1Y zURU^bu~SCdq*2-X*Vf^+fu6Qtg3WvZi;-V3GH`0=Cl|bl1LPDTDJk~3jq0>Mkf`_SA7ZxGCwM!y47Kwf@ z?)sVL4kJuBMAxwgJTOV85gF@NSz5SMR2P-9_Zve;*0u&L*FXzp6#fna6$CS!NXgF5 zj*hPQxq$j_U{za(64EDR)wUQ~{)18s)E;^r`l|yGzH63mc7S#o{o@LX|AJ+I zLFLxI=|U;WcYwJbM#sgC!6H!*U_kUVfsZ#EP_d5>iO>Fn1CFBpCNLt&#hBhSk29Pz zZ*P1r1nHlf#tp&VbpfZZvnz(a4G#Xjv~j=bLr;5q+}?I)nl@y)ep_B%&dtpwY*!mt zScT>t$)G$$=S$S162#i)#X(b{cdw*mlobIE0QC$B&6^<}8zG~kM(LvHoF@L#m3B|2 zVI^2W_C3ZS-gPrQIe8aQeh1N5l9_1@7(?!aLpxez?bWMSptg$!EU7Nd=C-}s^X$_1 z*a5$&Gw`OzVqlb4-Bd>kBqaZ6Zy#H5mKg)Vq6?+PQD1GJW$|p{M?c#_9dLYx@jEsO z)}krOV5Gsw(EDMAc31NOYB_AJ&cZ!_ooMFS;G=QxIzSs9Z%&Bb+S(v4cbaNXLNB;j zfqo&q&ZQL1mVFLs%+RhLKuX++l8xWtFyNb-nvnP#3L+n@+moy)`~uW=-fFPFzn_uh zh0MM2rU=lVAZN?|d?n4>DA()E(BFfsw_Q}Dw7zkVE6p)$iwBW;-`IFk(r&ooNtw4a zkv&XRG(vec57PazjeWfy_I>{T%NBImWmgZF2}oLd;qo<@I4>vXI^3a=YxDDJMpwfT zbcp{MqmFI;Y0!6;`K}-_d;150zrg5+7Q%DK7Ubz{f8i3UPG@GY{-Cj>cRXzE>~gZR z(G7+C@3W^*!!g>Jw?p&#Irm>L)Gm7$O&m92JSN*3&jv}uyFF{;r}hR>`xAt5jOql4 z=Zi~?LWTR{ro!t$wq!m7cXt#-PHLPafI$EWtO8a$e$G6|>tTO^+TKK?Q1f;r^DbEA zo0bG(fS~n3dBLNcAtTTO3Rm`9u7QMQU|`VY>r&u|XrJ~}zi|T)lWN&&ch+5S9Gti8 zzkT~QCo39cfMWw0ZrG7E;8(OnJxajv4=thyks!c9Pyce+UpwyMBwSOXsG#r&q&-?P z6TOrHA|{)1phDqDLMfmvc=~!hM--1<$vWtiPRZ|0O?r9e9k2t-fl=FWDJc&Y$LeKe zWi?^gkd-L`dJsLyFtj^6lzX^3P+26Ytjrx0=aBoBg`8Zi;p2Mn(FX(sphO7X3iMjp zU%}eTCw!>f=K-<~{rIs69YGD?awbS&KT|hULPVm4@wrUR>R|>S`vAYztw6w(h zXv`l5b90XqOat%(fMP72i1h_v@WCX??Q@r-R8(_5FfGgCYfy1FrL30;bjjC0e-^*$j#u%s+s!vFPnCpZhEunwmNXHL;(D zhKk|nLM@Z)!-dgmfCS{8ci{yftdzvWVIS1G#3{En>7rvlXa*F2W!wJS|9b_q>#;HA V;c()a_x|1~$STXEUom+4zX1N`pFIEo literal 0 HcmV?d00001 From d423a2250c6235a297143879de35e987ee4df3f1 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 2 Aug 2024 13:53:00 +0900 Subject: [PATCH 07/90] chore: add the link to the tool for analyzing timestamp Signed-off-by: vividf --- .../docs/concatenate-data.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 00192d55a2fff..34a0903c00951 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -51,7 +51,7 @@ Three parameters, `timeout_sec`, `lidar_timestamp_offsets`, and `lidar_timestamp #### timeout_sec -When network issues occur or when point clouds experience delays in the previous processing pipeline, some point clouds may be delayed or dropped. To address this, the `timeout_sec` parameter is used. If the timer reaches zero, the collector will not wait for delayed or dropped point clouds but will concatenate the remaining point clouds in the collector directly. The figure below demonstrates how `timeout_sec` works with `concatenate_and_time_sync_node`. +When network issues occur or when point clouds experience delays in the previous processing pipeline, some point clouds may be delayed or dropped. To address this, the `timeout_sec` parameter is used. Once the timer is created, it will start counting down from `timeout_sec`. If the timer reaches zero, the collector will not wait for delayed or dropped point clouds but will concatenate the remaining point clouds in the collector directly. The figure below demonstrates how `timeout_sec` works with `concatenate_and_time_sync_node`. ![concatenate_edge_case](./image/concatenate_edge_case.drawio.svg) @@ -65,13 +65,15 @@ The figure below demonstrates how `lidar_timestamp_offsets` works with `concaten #### lidar_timestamp_noise_window -Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan like the image shown below. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. +Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan, as shown in the image below. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. + +User can use [this tool](https://github.com/tier4/timestamp_analyzer) to visualize the noise betweeen each scan. ![jitter](./image/jitter.png) -From the example above, the noise is from 0 to 8 ms, the user should set 0.008 in the `lidar_timestamp_noise_window` parameter. +From the example above, the noise ranges from 0 to 8 ms, so the user should set `lidar_timestamp_noise_window` to `0.008`. -The figure below demonstrates how `lidar_timestamp_noise_window` works with `concatenate_and_time_sync_node`. If the green `X` is in the range of the red triangles, it means that the point cloud matches the reference timestamp of the collector. +The figure below demonstrates how `lidar_timestamp_noise_window` works with the `concatenate_and_time_sync_node`. If the green `X` is within the range of the red triangles, it indicates that the point cloud matches the reference timestamp of the collector. ![noise_timestamp_offset](./image/noise_timestamp_offset.drawio.svg) From 3d21b6c0cc6cdb2f0241c08c70ecf316ae9608a8 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 4 Sep 2024 10:56:47 +0900 Subject: [PATCH 08/90] fix: fix bug that timer didn't cancel Signed-off-by: vividf --- .../src/concatenate_data/cloud_collector.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 315d53e304c4c..3f1339c47e22c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -109,6 +109,7 @@ void CloudCollector::processCloud( void CloudCollector::concatenateCallback() { + timer_->cancel(); // lock for protecting collector list and concatenated pointcloud std::lock_guard lock(mutex_); auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = From 542ce9737e17d9ea94668931f0e952f4fa049559 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 5 Sep 2024 21:59:30 +0900 Subject: [PATCH 09/90] chore: fix logic for logging Signed-off-by: vividf --- .../concatenate_and_time_sync_node.hpp | 4 +- .../concatenate_and_time_sync_node.cpp | 39 +++++++++++-------- 2 files changed, 24 insertions(+), 19 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 1f653b19fdb6a..93d324bd5c7c8 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -122,8 +122,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::vector lidar_timestamp_noise_window; } params_; - double current_concat_cloud_timestamp_{0.0}; - double lastest_concat_cloud_timestamp_{0.0}; + double current_concatenate_cloud_timestamp_{0.0}; + double lastest_concatenate_cloud_timestamp_{0.0}; bool drop_previous_but_late_pointcloud_{false}; bool publish_pointcloud_{false}; double diagnostic_reference_timestamp_min_{0.0}; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index e0f71fee8eb0c..0061b715e228e 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -314,32 +314,37 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( double reference_timestamp_min, double reference_timestamp_max) { // should never come to this state. - if (concatenate_cloud_ptr == nullptr) return; - - current_concat_cloud_timestamp_ = rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds(); + if (concatenate_cloud_ptr == nullptr) { + RCLCPP_ERROR(this->get_logger(), "Concatenate cloud is a nullptr."); + return; + } + current_concatenate_cloud_timestamp_ = + rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds(); if ( - current_concat_cloud_timestamp_ < lastest_concat_cloud_timestamp_ && + current_concatenate_cloud_timestamp_ < lastest_concatenate_cloud_timestamp_ && !params_.publish_previous_but_late_pointcloud) { drop_previous_but_late_pointcloud_ = true; } else { publish_pointcloud_ = true; - lastest_concat_cloud_timestamp_ = current_concat_cloud_timestamp_; - auto concat_output = std::make_unique(*concatenate_cloud_ptr); - concatenate_cloud_publisher_->publish(std::move(concat_output)); + lastest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; + auto concatenate_pointcloud_output = + std::make_unique(*concatenate_cloud_ptr); + concatenate_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); + // publish transformed raw pointclouds - for (const auto & pair : topic_to_transformed_cloud_map) { - if (pair.second) { - if (params_.publish_synchronized_pointcloud) { + if (params_.publish_synchronized_pointcloud) { + for (auto topic : params_.input_topics) { + if (topic_to_transformed_cloud_map.find(topic) != topic_to_transformed_cloud_map.end()) { auto transformed_cloud_output = - std::make_unique(*pair.second); - topic_to_transformed_cloud_publisher_map_[pair.first]->publish( + std::make_unique(*topic_to_transformed_cloud_map[topic]); + topic_to_transformed_cloud_publisher_map_[topic]->publish( std::move(transformed_cloud_output)); + } else { + RCLCPP_WARN( + this->get_logger(), + "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.", topic.c_str()); } - } else { - RCLCPP_WARN( - this->get_logger(), "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.", - pair.first.c_str()); } } } @@ -438,7 +443,7 @@ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( diagnostic_updater::DiagnosticStatusWrapper & stat) { if (publish_pointcloud_ || drop_previous_but_late_pointcloud_) { - stat.add("concatenated cloud timestamp", formatTimestamp(current_concat_cloud_timestamp_)); + stat.add("concatenated cloud timestamp", formatTimestamp(current_concatenate_cloud_timestamp_)); stat.add("reference timestamp min", formatTimestamp(diagnostic_reference_timestamp_min_)); stat.add("reference timestamp max", formatTimestamp(diagnostic_reference_timestamp_max_)); From 77a3a794a710ca1ff96d0bd61cc915bb30700192 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 17:21:29 +0900 Subject: [PATCH 10/90] Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../autoware_pointcloud_preprocessor/docs/concatenate-data.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 34a0903c00951..dc2d60f0e2d20 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -14,7 +14,7 @@ When a point cloud arrives, its timestamp is checked, and an offset is subtracte ### Step 2: Trigger the Timer -Once a collector is created, a timer for that collector starts counting down (this value is defined by `timeout_sec`). The collector begins to concatenate the point clouds either when the required number of point clouds has been collected or when the timer counts down to zero. +Once a collector is created, a timer for that collector starts counting down (this value is defined by `timeout_sec`). The collector begins to concatenate the point clouds either when all point clouds defined in `input_topics` have been collected or when the timer counts down to zero. ### Step 3: Concatenate the Point Clouds From 52030a7282cc1eb60e2fb616c1246bea82376048 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 17:22:35 +0900 Subject: [PATCH 11/90] Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../src/concatenate_data/combine_cloud_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 11985a4c8720d..da91605d46e70 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -160,7 +160,7 @@ CombineCloudHandler::combinePointClouds( output_frame_, *cloud, *transformed_cloud_ptr, tf_buffer_)) { RCLCPP_ERROR( node_->get_logger(), - "Transform pointcloud from %s to %s failed, Please check the defined output frame.", + "Transforming pointcloud from %s to %s failed, please check the defined output frame.", cloud->header.frame_id.c_str(), output_frame_.c_str()); transformed_cloud_ptr = cloud; } From 3ddf249863ea5fd137bf4241129cd836b772c3c0 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 17:23:26 +0900 Subject: [PATCH 12/90] Update sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../schema/cocatenate_and_time_sync_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json index 183b807ec83b2..798f778feda04 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json @@ -73,7 +73,7 @@ "type": "number" }, "default": [], - "description": "List of LiDAR timestamp noise window." + "description": "List of LiDAR timestamp noise windows." } }, "required": [ From d6797360a27e3861b82e3860ec374c752a5eb6fd Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 17:23:55 +0900 Subject: [PATCH 13/90] Update sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../schema/cocatenate_and_time_sync_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json index 798f778feda04..3444c1419310f 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json @@ -52,7 +52,7 @@ "type": "string" }, "default": [], - "description": "List of input topics." + "description": "List of input point cloud topics." }, "output_frame": { "type": "string", From 1f9d24c972f46102249b6db129da7a201f5301b6 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 17:24:28 +0900 Subject: [PATCH 14/90] Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../src/concatenate_data/combine_cloud_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index da91605d46e70..1b8c33037e108 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -81,7 +81,7 @@ CombineCloudHandler::CombineCloudHandler( void CombineCloudHandler::processTwist( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input) { - // if rosbag restart, clear buffer + // If time jumps backwards (e.g. when a rosbag restarts), 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(); From 09452e7560c7fce14308b377b4cd4c008556009f Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 17:24:44 +0900 Subject: [PATCH 15/90] Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../src/concatenate_data/combine_cloud_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 1b8c33037e108..27e55133f16c6 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -237,7 +237,7 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( if (twist_ptr_queue_.empty()) { RCLCPP_WARN_STREAM_THROTTLE( node_->get_logger(), *node_->get_clock(), std::chrono::milliseconds(10000).count(), - "No twist is available. Please confirm twist topic and timestamp"); + "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud untransformed."); return Eigen::Matrix4f::Identity(); } From d900d3f8be1407274b5fc6987022b06bca5b6d73 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 19 Sep 2024 11:32:57 +0900 Subject: [PATCH 16/90] chore: remove distortion corrector related changes Signed-off-by: vividf --- .../docs/distortion-corrector.md | 8 ------- .../distortion_corrector.hpp | 16 +++++++------- .../distortion_corrector.cpp | 8 +++---- .../test/test_distortion_corrector_node.cpp | 22 +++++++++---------- 4 files changed, 23 insertions(+), 31 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md index 44a064e89ad1a..ab5a07b5279bc 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md @@ -44,14 +44,6 @@ Please note that the processing time difference between the two distortion metho ros2 launch autoware_pointcloud_preprocessor distortion_corrector.launch.xml ``` -## Test - -```bash -colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-up-to autoware_pointcloud_preprocessor - -colcon test --packages-select autoware_pointcloud_preprocessor --event-handlers console_cohesion+ -``` - ## Assumptions / Known limits - The node requires time synchronization between the topics from lidars, twist, and IMU. diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 7e26d4c1cf2c8..e786bff04b3cd 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -50,10 +50,10 @@ namespace autoware::pointcloud_preprocessor class DistortionCorrectorBase { public: - virtual bool pointcloudTransformExists() = 0; - virtual bool pointcloudTransformNeeded() = 0; - virtual std::deque getTwistQueue() = 0; - virtual std::deque getAngularVelocityQueue() = 0; + virtual bool pointcloud_transform_exists() = 0; + virtual bool pointcloud_transform_needed() = 0; + virtual std::deque get_twist_queue() = 0; + virtual std::deque get_angular_velocity_queue() = 0; virtual void processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) = 0; @@ -104,10 +104,10 @@ class DistortionCorrector : public DistortionCorrectorBase managed_tf_buffer_ = std::make_unique(node, has_static_tf_only); } - bool pointcloudTransformExists(); - bool pointcloudTransformNeeded(); - std::deque getTwistQueue(); - std::deque getAngularVelocityQueue(); + bool pointcloud_transform_exists(); + bool pointcloud_transform_needed(); + std::deque get_twist_queue(); + std::deque get_angular_velocity_queue(); void processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) override; diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index eff4e726352b6..d0119fbc44f24 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -25,25 +25,25 @@ namespace autoware::pointcloud_preprocessor { template -bool DistortionCorrector::pointcloudTransformExists() +bool DistortionCorrector::pointcloud_transform_exists() { return pointcloud_transform_exists_; } template -bool DistortionCorrector::pointcloudTransformNeeded() +bool DistortionCorrector::pointcloud_transform_needed() { return pointcloud_transform_needed_; } template -std::deque DistortionCorrector::getTwistQueue() +std::deque DistortionCorrector::get_twist_queue() { return twist_queue_; } template -std::deque DistortionCorrector::getAngularVelocityQueue() +std::deque DistortionCorrector::get_angular_velocity_queue() { return angular_velocity_queue_; } diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index 2e0306c6217c2..047d021a4c6da 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -286,9 +286,9 @@ TEST_F(DistortionCorrectorTest, TestProcessTwistMessage) auto twist_msg = generateTwistMsg(twist_linear_x_, twist_angular_z_, timestamp); distortion_corrector_2d_->processTwistMessage(twist_msg); - ASSERT_FALSE(distortion_corrector_2d_->getTwistQueue().empty()); - EXPECT_EQ(distortion_corrector_2d_->getTwistQueue().front().twist.linear.x, twist_linear_x_); - EXPECT_EQ(distortion_corrector_2d_->getTwistQueue().front().twist.angular.z, twist_angular_z_); + ASSERT_FALSE(distortion_corrector_2d_->get_twist_queue().empty()); + EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.linear.x, twist_linear_x_); + EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.angular.z, twist_angular_z_); } TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) @@ -297,9 +297,9 @@ TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) auto imu_msg = generateImuMsg(imu_angular_x_, imu_angular_y_, imu_angular_z_, timestamp); distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); - ASSERT_FALSE(distortion_corrector_2d_->getAngularVelocityQueue().empty()); + ASSERT_FALSE(distortion_corrector_2d_->get_angular_velocity_queue().empty()); EXPECT_NEAR( - distortion_corrector_2d_->getAngularVelocityQueue().front().vector.z, -0.03159, + distortion_corrector_2d_->get_angular_velocity_queue().front().vector.z, -0.03159, standard_tolerance_); } @@ -329,22 +329,22 @@ TEST_F(DistortionCorrectorTest, TestIsInputValid) TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithBaseLink) { distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); - EXPECT_TRUE(distortion_corrector_2d_->pointcloudTransformExists()); - EXPECT_FALSE(distortion_corrector_2d_->pointcloudTransformNeeded()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed()); } TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithLidarFrame) { distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); - EXPECT_TRUE(distortion_corrector_2d_->pointcloudTransformExists()); - EXPECT_TRUE(distortion_corrector_2d_->pointcloudTransformNeeded()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_needed()); } TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithMissingFrame) { distortion_corrector_2d_->setPointCloudTransform("base_link", "missing_lidar_frame"); - EXPECT_FALSE(distortion_corrector_2d_->pointcloudTransformExists()); - EXPECT_FALSE(distortion_corrector_2d_->pointcloudTransformNeeded()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_exists()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed()); } TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyTwist) From bcbe94a27b8e5721d07fc96ecb9c172c2a340db1 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 19 Sep 2024 12:32:40 +0900 Subject: [PATCH 17/90] feat: add managed tf buffer Signed-off-by: vividf --- .../concatenate_and_time_sync_node.param.yaml | 1 + .../combine_cloud_handler.hpp | 9 +++--- .../concatenate_and_time_sync_node.hpp | 2 +- .../cocatenate_and_time_sync_node.schema.json | 8 ++++- .../combine_cloud_handler.cpp | 31 +++++++------------ .../concatenate_and_time_sync_node.cpp | 3 +- .../test/test_concatenate_node_component.py | 1 + .../test/test_concatenate_node_unit.cpp | 5 +-- 8 files changed, 30 insertions(+), 30 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml index d023479acf6e3..d99849b532f3e 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + has_static_tf_only: false maximum_queue_size: 5 timeout_sec: 0.2 is_motion_compensated: true diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 1e51e072928e3..e2a7b4c69da70 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -64,6 +64,7 @@ // ROS includes #include "autoware_point_types/types.hpp" +#include #include #include @@ -81,8 +82,6 @@ #include #include #include -#include -#include namespace autoware::pointcloud_preprocessor { @@ -91,13 +90,12 @@ class CombineCloudHandler { private: rclcpp::Node * node_; - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; std::vector input_topics_; std::string output_frame_; bool is_motion_compensated_; bool keep_input_frame_in_synchronized_pointcloud_; + std::unique_ptr managed_tf_buffer_{nullptr}; struct RclcppTimeHash_ { @@ -112,7 +110,8 @@ class CombineCloudHandler CombineCloudHandler( rclcpp::Node * node, std::vector 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); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 93d324bd5c7c8..993a07ee98568 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -67,7 +67,6 @@ #include "combine_cloud_handler.hpp" #include -#include #include #include #include @@ -108,6 +107,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node private: struct Parameters { + bool has_static_tf_only; int maximum_queue_size; double timeout_sec; bool is_motion_compensated; diff --git a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json index 3444c1419310f..21abc823381dd 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json @@ -74,6 +74,11 @@ }, "default": [], "description": "List of LiDAR timestamp noise windows." + }, + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." } }, "required": [ @@ -88,7 +93,8 @@ "input_topics", "output_frame", "lidar_timestamp_offsets", - "lidar_timestamp_noise_window" + "lidar_timestamp_noise_window", + "has_static_tf_only" ] } }, diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 27e55133f16c6..2f0dc20813b9b 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -67,14 +67,15 @@ namespace autoware::pointcloud_preprocessor CombineCloudHandler::CombineCloudHandler( rclcpp::Node * node, std::vector 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) : node_(node), - tf_buffer_(node_->get_clock()), - tf_listener_(tf_buffer_), input_topics_(input_topics), output_frame_(output_frame), is_motion_compensated_(is_motion_compensated), - keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud) + keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud), + managed_tf_buffer_( + std::make_unique(node_, has_static_tf_only)) { } @@ -155,18 +156,7 @@ CombineCloudHandler::combinePointClouds( sensor_msgs::msg::PointCloud2::SharedPtr cloud = pair.second; auto transformed_cloud_ptr = std::make_shared(); - if (output_frame_ != cloud->header.frame_id) { - if (!pcl_ros::transformPointCloud( - output_frame_, *cloud, *transformed_cloud_ptr, tf_buffer_)) { - RCLCPP_ERROR( - node_->get_logger(), - "Transforming pointcloud from %s to %s failed, please check the defined output frame.", - cloud->header.frame_id.c_str(), output_frame_.c_str()); - transformed_cloud_ptr = cloud; - } - } else { - transformed_cloud_ptr = cloud; - } + managed_tf_buffer_->transformPointcloud(output_frame_, *cloud, *transformed_cloud_ptr); topic_to_original_stamp_map[topic] = rclcpp::Time(cloud->header.stamp).seconds(); @@ -212,9 +202,9 @@ CombineCloudHandler::combinePointClouds( if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame( new sensor_msgs::msg::PointCloud2()); - pcl_ros::transformPointCloud( - (std::string)cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, - *transformed_cloud_ptr_in_sensor_frame, tf_buffer_); + managed_tf_buffer_->transformPointcloud( + cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, + *transformed_cloud_ptr_in_sensor_frame); transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id; topic_to_transformed_cloud_map[topic] = transformed_cloud_ptr_in_sensor_frame; @@ -237,7 +227,8 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( if (twist_ptr_queue_.empty()) { RCLCPP_WARN_STREAM_THROTTLE( node_->get_logger(), *node_->get_clock(), std::chrono::milliseconds(10000).count(), - "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud untransformed."); + "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud " + "untransformed."); return Eigen::Matrix4f::Identity(); } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 0061b715e228e..390cc422f736e 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -84,6 +84,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro stop_watch_ptr_->tic("processing_time"); // initialize parameters + params_.has_static_tf_only = declare_parameter("has_static_tf_only"); params_.maximum_queue_size = declare_parameter("maximum_queue_size"); params_.timeout_sec = declare_parameter("timeout_sec"); params_.is_motion_compensated = declare_parameter("is_motion_compensated"); @@ -189,7 +190,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Combine cloud handler combine_cloud_handler_ = std::make_shared( this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, - params_.keep_input_frame_in_synchronized_pointcloud); + params_.keep_input_frame_in_synchronized_pointcloud, params_.has_static_tf_only); // Diagnostic Updater updater_.setHardwareID("concatenate_data_checker"); diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index ce0c2653022d1..84f08a2b8725e 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -84,6 +84,7 @@ def generate_test_description(): ], parameters=[ { + "has_static_tf_only": False, "maximum_queue_size": 5, "timeout_sec": TIMEOUT_SEC, "is_motion_compensated": True, diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 397310f5b4335..4cc513b01b62b 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -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}, @@ -60,7 +61,7 @@ class ConcatenateCloudTest : public ::testing::Test combine_cloud_handler_ = std::make_shared( concatenate_node_.get(), std::vector{"lidar_top", "lidar_left", "lidar_right"}, - "base_link", true, true); + "base_link", true, true, false); collector_ = std::make_shared( std::dynamic_pointer_cast< From 22b654a82fb41cb8d26cca2728ebc0b0829da59b Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 15:25:31 +0900 Subject: [PATCH 18/90] chore: fix filename Signed-off-by: vividf --- ...ode.schema.json => concatenate_and_time_sync_node.schema.json} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename sensing/autoware_pointcloud_preprocessor/schema/{cocatenate_and_time_sync_node.schema.json => concatenate_and_time_sync_node.schema.json} (100%) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json similarity index 100% rename from sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json rename to sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json From 076bfaa87f54e1342a688d1931b183d88dc8e501 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 15:48:58 +0900 Subject: [PATCH 19/90] chore: add explanataion for maximum queue size Signed-off-by: vividf --- .../schema/concatenate_and_time_sync_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 21abc823381dd..67f31b6003b5a 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -9,7 +9,7 @@ "maximum_queue_size": { "type": "integer", "default": 5, - "description": "Maximum size of the queue." + "description": "Maximum size of the queue for the Keep Last policy in QoS history." }, "timeout_sec": { "type": "number", From 0e59f48aa25c3b399c2f1fb3a56d9474b5a0b4d7 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 16:06:11 +0900 Subject: [PATCH 20/90] chore: add explanation for timeout_sec Signed-off-by: vividf --- .../autoware_pointcloud_preprocessor/docs/concatenate-data.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index dc2d60f0e2d20..c86b8a5aa9dee 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -51,7 +51,7 @@ Three parameters, `timeout_sec`, `lidar_timestamp_offsets`, and `lidar_timestamp #### timeout_sec -When network issues occur or when point clouds experience delays in the previous processing pipeline, some point clouds may be delayed or dropped. To address this, the `timeout_sec` parameter is used. Once the timer is created, it will start counting down from `timeout_sec`. If the timer reaches zero, the collector will not wait for delayed or dropped point clouds but will concatenate the remaining point clouds in the collector directly. The figure below demonstrates how `timeout_sec` works with `concatenate_and_time_sync_node`. +When network issues occur or when point clouds experience delays in the previous processing pipeline, some point clouds may be delayed or dropped. To address this, the `timeout_sec` parameter is used. Once the timer is created, it will start counting down from `timeout_sec`. If the timer reaches zero, the collector will not wait for delayed or dropped point clouds but will concatenate the remaining point clouds in the collector directly. The figure below demonstrates how `timeout_sec` works with `concatenate_and_time_sync_node` when `timeout_sec` is set to `0.12` (120 ms). ![concatenate_edge_case](./image/concatenate_edge_case.drawio.svg) From 8e7997687f6ac8d1d01b3aa0d2f2aa9a8dd84773 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 16:49:54 +0900 Subject: [PATCH 21/90] chore: fix schema's explanation Signed-off-by: vividf --- .../schema/concatenate_and_time_sync_node.schema.json | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 67f31b6003b5a..254fb06e3ffa0 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -13,8 +13,8 @@ }, "timeout_sec": { "type": "number", - "default": 0.0, - "description": "Timeout in seconds." + "default": 0.1, + "description": "Timer's timeout duration in seconds when collectors are created. Collectors will concatenate the point clouds when timeout_sec reaches zero." }, "is_motion_compensated": { "type": "boolean", @@ -39,7 +39,7 @@ "synchronized_pointcloud_postfix": { "type": "string", "default": "pointcloud", - "description": "Postfix for the synchronized point cloud." + "description": "Postfix for the topic name of the synchronized point cloud." }, "input_twist_topic_type": { "type": "string", @@ -65,7 +65,7 @@ "type": "number" }, "default": [], - "description": "List of LiDAR timestamp offsets." + "description": "List of LiDAR timestamp offsets in seconds. The offset values should be specified in the same order as the input_topics." }, "lidar_timestamp_noise_window": { "type": "array", @@ -73,7 +73,7 @@ "type": "number" }, "default": [], - "description": "List of LiDAR timestamp noise windows." + "description": "List of LiDAR timestamp noise windows in seconds. The noise values should be specified in the same order as the input_topics." }, "has_static_tf_only": { "type": "boolean", From 66b4092d6044f7d83f2178c7092a005ce3d5725d Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 17:11:31 +0900 Subject: [PATCH 22/90] chore: fix description for twist and odom Signed-off-by: vividf --- .../docs/concatenate-data.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index c86b8a5aa9dee..2303e65129fda 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -28,10 +28,10 @@ After concatenation, the concatenated point cloud is published, and the collecto ### Input -| Name | Type | Description | -| --------------- | ------------------------------------------------ | --------------------------------------------------------------------------------- | -| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The twist information used to interpolate the timestamp of each LiDAR point cloud | -| `~/input/odom` | `nav_msgs::msg::Odometry` | The vehicle odometry used to interpolate the timestamp of each LiDAR point cloud | +| Name | Type | Description | +| --------------- | ------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Twist information adjusts the point cloud scans based on vehicle motion, allowing LiDARs with different timestamp to be synchronized for concatenation. | +| `~/input/odom` | `nav_msgs::msg::Odometry` | Vehicle odometry adjusts the point cloud scans based on vehicle motion, allowing LiDARs with different timestamp to be synchronized for concatenation. | By setting the `input_twist_topic_type` parameter to `twist` or `odom`, the subscriber will subscribe to either `~/input/twist` or `~/input/odom`. If the user doesn't want to use the twist information or vehicle odometry to compensate for motion, set `is_motion_compensated` to `false`. From 10d83ee10c6a8f5cd62efa1cb6f2d1e57b7d75fd Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 17:13:57 +0900 Subject: [PATCH 23/90] chore: remove license that are not used Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 37 ------------------- .../combine_cloud_handler.hpp | 37 ------------------- .../concatenate_and_time_sync_node.hpp | 37 ------------------- .../src/concatenate_data/cloud_collector.cpp | 37 ------------------- .../combine_cloud_handler.cpp | 37 ------------------- .../concatenate_and_time_sync_node.cpp | 37 ------------------- 6 files changed, 222 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index f71bb1df968b5..d589e07a2caa1 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -12,43 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - #ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ #define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index e2a7b4c69da70..61209c9395cba 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -12,43 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - #ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ #define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 993a07ee98568..3ddc76dacc8f2 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -12,43 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - #ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ #define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 3f1339c47e22c..ccad72777f83e 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -12,43 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - #include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" #include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 2f0dc20813b9b..fbf1a6570b17b 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -12,43 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - #include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" #include diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 390cc422f736e..26a986f4041ad 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -12,43 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - #include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" #include "autoware/pointcloud_preprocessor/utility/memory.hpp" From fbb5fe9ab325538a936bd23a33aa0f4f63cf8110 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 18:19:28 +0900 Subject: [PATCH 24/90] chore: change guard to prama once Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 7 +------ .../concatenate_data/combine_cloud_handler.hpp | 7 +------ .../concatenate_data/concatenate_and_time_sync_node.hpp | 7 +------ 3 files changed, 3 insertions(+), 18 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index d589e07a2caa1..c7d3956c1b268 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -12,8 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ +#pragma once #include "combine_cloud_handler.hpp" @@ -73,7 +72,3 @@ class CloudCollector }; } // namespace autoware::pointcloud_preprocessor - -// clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CLOUD_COLLECTOR_HPP_ // NOLINT -// clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 61209c9395cba..bcbd40bc6a2a3 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -12,8 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ +#pragma once #include #include @@ -90,7 +89,3 @@ class CombineCloudHandler }; } // namespace autoware::pointcloud_preprocessor - -// clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_HPP_ // NOLINT -// clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 3ddc76dacc8f2..91342abea386d 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -12,8 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ +#pragma once #include #include @@ -129,7 +128,3 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node }; } // namespace autoware::pointcloud_preprocessor - -// clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODE_HPP_ // NOLINT -// clang-format on From 3f0732e46d8e81869e0aecf11477356cf85e250c Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 18:26:29 +0900 Subject: [PATCH 25/90] chore: default value change to string Signed-off-by: vividf --- .../schema/concatenate_and_time_sync_node.schema.json | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 254fb06e3ffa0..37608d2900fe3 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -8,12 +8,12 @@ "properties": { "maximum_queue_size": { "type": "integer", - "default": 5, + "default": "5", "description": "Maximum size of the queue for the Keep Last policy in QoS history." }, "timeout_sec": { "type": "number", - "default": 0.1, + "default": "0.1", "description": "Timer's timeout duration in seconds when collectors are created. Collectors will concatenate the point clouds when timeout_sec reaches zero." }, "is_motion_compensated": { From c19250b0630815f422be4e8cf2917dbbf622ffe3 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Fri, 20 Sep 2024 18:32:36 +0900 Subject: [PATCH 26/90] Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../test/test_concatenate_node_unit.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 4cc513b01b62b..c2b82841ecddb 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -172,7 +172,7 @@ class ConcatenateCloudTest : public ::testing::Test std::shared_ptr tf_broadcaster_; static constexpr int32_t timestamp_seconds_{10}; - static constexpr uint32_t timestamp_nanoseconds_{100000000}; + static constexpr uint32_t timestamp_nanoseconds_{100'000'000}; static constexpr size_t number_of_points_{3}; static constexpr float standard_tolerance_{1e-4}; static constexpr int number_of_pointcloud_{3}; From 5ec228c303c0858d661033a25987810b25da135c Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Fri, 20 Sep 2024 18:41:04 +0900 Subject: [PATCH 27/90] Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../test/test_concatenate_node_unit.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index c2b82841ecddb..a3cc6a1d15e7e 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -436,8 +436,8 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) { rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40000000, RCL_ROS_TIME); - rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80000000, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = From f4c869e2863372480224a30175dbf3606c4fbe8f Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Fri, 20 Sep 2024 18:42:03 +0900 Subject: [PATCH 28/90] Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../test/test_concatenate_node_unit.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index a3cc6a1d15e7e..4569aab45c2ec 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -263,8 +263,8 @@ TEST_F(ConcatenateCloudTest, TestSetAndGetReferenceTimeStampBoundary) TEST_F(ConcatenateCloudTest, TestConcatenateClouds) { rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40000000, RCL_ROS_TIME); - rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80000000, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = From 4cca6c118c03ee620ea86d774056ff7092ca6828 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Fri, 20 Sep 2024 18:43:23 +0900 Subject: [PATCH 29/90] Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> --- .../test/test_concatenate_node_unit.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 4569aab45c2ec..491954f4399aa 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -211,18 +211,18 @@ TEST_F(ConcatenateCloudTest, TestProcessOdometry) TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) { - rclcpp::Time old_stamp(10, 100000000, RCL_ROS_TIME); - rclcpp::Time new_stamp(10, 150000000, RCL_ROS_TIME); + rclcpp::Time old_stamp(10, 100'000'000, RCL_ROS_TIME); + rclcpp::Time new_stamp(10, 150'000'000, RCL_ROS_TIME); // Time difference between twist msg is more than 100 miliseconds, won't calculate the difference auto twist_msg1 = std::make_shared(); - twist_msg1->header.stamp = rclcpp::Time(10, 130000000, RCL_ROS_TIME); + twist_msg1->header.stamp = rclcpp::Time(10, 130'000'000, RCL_ROS_TIME); twist_msg1->twist.linear.x = 1.0; twist_msg1->twist.angular.z = 0.1; combine_cloud_handler_->twist_ptr_queue_.push_back(twist_msg1); auto twist_msg2 = std::make_shared(); - twist_msg2->header.stamp = rclcpp::Time(10, 160000000, RCL_ROS_TIME); + twist_msg2->header.stamp = rclcpp::Time(10, 160'000'000, RCL_ROS_TIME); twist_msg2->twist.linear.x = 1.0; twist_msg2->twist.angular.z = 0.1; combine_cloud_handler_->twist_ptr_queue_.push_back(twist_msg2); From 53279b59ae5660d3dfd4c6f68c3b236703ecca14 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 20 Sep 2024 09:45:37 +0000 Subject: [PATCH 30/90] style(pre-commit): autofix --- .../test/test_concatenate_node_unit.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 491954f4399aa..6aa45446c7a6c 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -263,8 +263,10 @@ TEST_F(ConcatenateCloudTest, TestSetAndGetReferenceTimeStampBoundary) TEST_F(ConcatenateCloudTest, TestConcatenateClouds) { rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); - rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); + rclcpp::Time left_timestamp( + timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp( + timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = @@ -436,8 +438,10 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) { rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); - rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); + rclcpp::Time left_timestamp( + timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp( + timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = From 853b8fe3927a10a69d632381f24a785b31374673 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 18:58:11 +0900 Subject: [PATCH 31/90] chore: clang-tidy style for static constexpr Signed-off-by: vividf --- .../test/test_concatenate_node_unit.cpp | 48 +++++++++---------- 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 491954f4399aa..95643ab9c720d 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -67,7 +67,7 @@ class ConcatenateCloudTest : public ::testing::Test std::dynamic_pointer_cast< autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( concatenate_node_->shared_from_this()), - collectors_, combine_cloud_handler_, number_of_pointcloud_, timeout_sec_); + collectors_, combine_cloud_handler_, number_of_pointcloud, timeout_sec); collectors_.push_back(collector_); @@ -88,7 +88,7 @@ class ConcatenateCloudTest : public ::testing::Test const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, double qx, double qy, double qz, double qw) { - rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + rclcpp::Time timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); geometry_msgs::msg::TransformStamped tf_msg; tf_msg.header.stamp = timestamp; tf_msg.header.frame_id = parent_frame; @@ -114,7 +114,7 @@ class ConcatenateCloudTest : public ::testing::Test pointcloud_msg.is_bigendian = false; if (generate_points) { - std::array points = {{ + std::array points = {{ Eigen::Vector3f(10.0f, 0.0f, 0.0f), // point 1 Eigen::Vector3f(0.0f, 10.0f, 0.0f), // point 2 Eigen::Vector3f(0.0f, 0.0f, 10.0f), // point 3 @@ -130,14 +130,14 @@ class ConcatenateCloudTest : public ::testing::Test sensor_msgs::msg::PointField::FLOAT32, "distance", 1, sensor_msgs::msg::PointField::FLOAT32, "time_stamp", 1, sensor_msgs::msg::PointField::UINT32); - modifier.resize(number_of_points_); + modifier.resize(number_of_points); sensor_msgs::PointCloud2Iterator iter_x(pointcloud_msg, "x"); sensor_msgs::PointCloud2Iterator iter_y(pointcloud_msg, "y"); sensor_msgs::PointCloud2Iterator iter_z(pointcloud_msg, "z"); sensor_msgs::PointCloud2Iterator iter_t(pointcloud_msg, "time_stamp"); - for (size_t i = 0; i < number_of_points_; ++i) { + for (size_t i = 0; i < number_of_points; ++i) { *iter_x = points[i].x(); *iter_y = points[i].y(); *iter_z = points[i].z(); @@ -171,12 +171,12 @@ class ConcatenateCloudTest : public ::testing::Test std::shared_ptr collector_; std::shared_ptr tf_broadcaster_; - static constexpr int32_t timestamp_seconds_{10}; - static constexpr uint32_t timestamp_nanoseconds_{100'000'000}; - static constexpr size_t number_of_points_{3}; - static constexpr float standard_tolerance_{1e-4}; - static constexpr int number_of_pointcloud_{3}; - static constexpr float timeout_sec_{0.2}; + static constexpr int32_t timestamp_seconds{10}; + static constexpr uint32_t timestamp_nanoseconds{100'000'000}; + static constexpr size_t number_of_points{3}; + static constexpr float standard_tolerance{1e-4}; + static constexpr int number_of_pointcloud{3}; + static constexpr float timeout_sec{0.2}; bool debug_{false}; }; @@ -231,14 +231,14 @@ TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) combine_cloud_handler_->computeTransformToAdjustForOldTimestamp(old_stamp, new_stamp); // translation - EXPECT_NEAR(transform(0, 3), 0.0499996, standard_tolerance_); - EXPECT_NEAR(transform(1, 3), 0.000189999, standard_tolerance_); + EXPECT_NEAR(transform(0, 3), 0.0499996, standard_tolerance); + EXPECT_NEAR(transform(1, 3), 0.000189999, standard_tolerance); // rotation, yaw = 0.005 - EXPECT_NEAR(transform(0, 0), 0.999987, standard_tolerance_); - EXPECT_NEAR(transform(0, 1), -0.00499998, standard_tolerance_); - EXPECT_NEAR(transform(1, 0), 0.00499998, standard_tolerance_); - EXPECT_NEAR(transform(1, 1), 0.999987, standard_tolerance_); + EXPECT_NEAR(transform(0, 0), 0.999987, standard_tolerance); + EXPECT_NEAR(transform(0, 1), -0.00499998, standard_tolerance); + EXPECT_NEAR(transform(1, 0), 0.00499998, standard_tolerance); + EXPECT_NEAR(transform(1, 1), 0.999987, standard_tolerance); std::ostringstream oss; oss << "Transformation matrix:\n" << transform; @@ -262,9 +262,9 @@ TEST_F(ConcatenateCloudTest, TestSetAndGetReferenceTimeStampBoundary) TEST_F(ConcatenateCloudTest, TestConcatenateClouds) { - rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); - rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = @@ -414,7 +414,7 @@ TEST_F(ConcatenateCloudTest, TestDeleteCollector) TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) { - rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + rclcpp::Time timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", timestamp); sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = @@ -435,9 +435,9 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) { - rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); - rclcpp::Time right_timestamp(timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = From d32dfbce5105d31682f5db4cce9cc30d95c76d8b Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 18:59:31 +0900 Subject: [PATCH 32/90] chore: remove unused vector header Signed-off-by: vividf --- .../pointcloud_preprocessor/concatenate_data/cloud_collector.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index c7d3956c1b268..ed1767e983414 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -21,7 +21,6 @@ #include #include #include -#include namespace autoware::pointcloud_preprocessor { From 07cb7534ea90d6d3e32948c32eb57d87c7bf8722 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 19:04:16 +0900 Subject: [PATCH 33/90] chore: fix naming concatenated_cloud_publisher Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.hpp | 2 +- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 91342abea386d..37545a247780b 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -105,7 +105,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node rclcpp::Subscription::SharedPtr odom_sub_; // publishers - rclcpp::Publisher::SharedPtr concatenate_cloud_publisher_; + rclcpp::Publisher::SharedPtr concatenated_cloud_publisher_; std::unordered_map::SharedPtr> topic_to_transformed_cloud_publisher_map_; std::unique_ptr debug_publisher_; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 26a986f4041ad..940abf541e025 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -96,7 +96,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } // Publishers - concatenate_cloud_publisher_ = this->create_publisher( + concatenated_cloud_publisher_ = this->create_publisher( "output", rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud @@ -294,7 +294,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( lastest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; auto concatenate_pointcloud_output = std::make_unique(*concatenate_cloud_ptr); - concatenate_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); + concatenated_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); // publish transformed raw pointclouds if (params_.publish_synchronized_pointcloud) { From 490b15cec2efa8ee8155746cc14100efcca40034 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 19:06:15 +0900 Subject: [PATCH 34/90] chore: fix namimg diagnostic_updater_ Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.hpp | 2 +- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 37545a247780b..88cd68873bdbb 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -111,7 +111,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unique_ptr debug_publisher_; std::unique_ptr> stop_watch_ptr_; - diagnostic_updater::Updater updater_{this}; + diagnostic_updater::Updater diagnostic_updater_{this}; void cloud_callback( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 940abf541e025..777f5cbf2e22d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -156,8 +156,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro params_.keep_input_frame_in_synchronized_pointcloud, params_.has_static_tf_only); // Diagnostic Updater - updater_.setHardwareID("concatenate_data_checker"); - updater_.add( + diagnostic_updater_.setHardwareID("concatenate_data_checker"); + diagnostic_updater_.add( "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus); } @@ -316,7 +316,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( diagnostic_reference_timestamp_min_ = reference_timestamp_min; diagnostic_reference_timestamp_max_ = reference_timestamp_max; diagnostic_topic_to_original_stamp_map_ = topic_to_original_stamp_map; - updater_.force_update(); + diagnostic_updater_.force_update(); // add processing time for debug if (debug_publisher_) { From 8f168964fe8a96ed91c97ee705d6b4edc1a20cb5 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 19:40:36 +0900 Subject: [PATCH 35/90] chore: specify parameter in comment Signed-off-by: vividf --- .../src/concatenate_data/cloud_collector.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index ccad72777f83e..da56fa1334a1d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -56,8 +56,8 @@ std::tuple CloudCollector::getReferenceTimeStampBoundary() void CloudCollector::processCloud( std::string topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) { - // Check if the map already contains an entry for the same topic, shouldn't happened if the - // parameter set correctly. + // Check if the map already contains an entry for the same topic. This shouldn't happen if the + // parameter 'lidar_timestamp_noise_window' is set correctly. if (topic_to_cloud_map_.find(topic_name) != topic_to_cloud_map_.end()) { RCLCPP_WARN( concatenate_node_->get_logger(), From 1d89cdd8c3be3387f472b2b231b601d4eef16eda Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 19:47:40 +0900 Subject: [PATCH 36/90] chore: change RCLCPP_WARN to RCLCPP_WARN_STREAM_THROTTLE Signed-off-by: vividf --- .../src/concatenate_data/cloud_collector.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index da56fa1334a1d..6dfc433d617a7 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -59,10 +59,11 @@ void CloudCollector::processCloud( // Check if the map already contains an entry for the same topic. This shouldn't happen if the // parameter 'lidar_timestamp_noise_window' is set correctly. if (topic_to_cloud_map_.find(topic_name) != topic_to_cloud_map_.end()) { - RCLCPP_WARN( - concatenate_node_->get_logger(), - "Topic '%s' already exists in the collector. Check the timestamp of the pointcloud.", - topic_name.c_str()); + RCLCPP_WARN_STREAM_THROTTLE( + concatenate_node_->get_logger(), *concatenate_node_->get_clock(), + std::chrono::milliseconds(10000).count(), + "Topic '" << topic_name + << "' already exists in the collector. Check the timestamp of the pointcloud."); } topic_to_cloud_map_[topic_name] = cloud; if (topic_to_cloud_map_.size() == num_of_clouds_) { From 651c666f3eaabe7be12944d08509f11959412d2c Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 20 Sep 2024 19:59:18 +0900 Subject: [PATCH 37/90] chore: add comment for cancelling timer Signed-off-by: vividf --- .../src/concatenate_data/cloud_collector.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 6dfc433d617a7..1887f3e07b4ad 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -73,7 +73,10 @@ void CloudCollector::processCloud( void CloudCollector::concatenateCallback() { + // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the + // pointclouds in the collector. timer_->cancel(); + // lock for protecting collector list and concatenated pointcloud std::lock_guard lock(mutex_); auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = From 370483c9a22c05c4c8bc2f6563c484e10d9d51b0 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 23 Sep 2024 23:19:30 +0900 Subject: [PATCH 38/90] chore: Simplify loop structure for topic-to-cloud mapping Signed-off-by: vividf --- .../concatenate_data/combine_cloud_handler.cpp | 9 +++------ .../concatenate_and_time_sync_node.cpp | 8 ++++---- .../test/test_concatenate_node_unit.cpp | 16 ++++++---------- 3 files changed, 13 insertions(+), 20 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index fbf1a6570b17b..6db3dc12d3295 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -106,18 +106,15 @@ CombineCloudHandler::combinePointClouds( std::unordered_map topic_to_original_stamp_map; std::vector pc_stamps; - for (const auto & pair : topic_to_cloud_map) { - pc_stamps.push_back(rclcpp::Time(pair.second->header.stamp)); + for (const auto & [topic, cloud] : topic_to_cloud_map) { + pc_stamps.push_back(rclcpp::Time(cloud->header.stamp)); } std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); const auto oldest_stamp = pc_stamps.back(); std::unordered_map transform_memo; - for (const auto & pair : topic_to_cloud_map) { - std::string topic = pair.first; - sensor_msgs::msg::PointCloud2::SharedPtr cloud = pair.second; - + for (const auto & [topic, cloud] : topic_to_cloud_map) { auto transformed_cloud_ptr = std::make_shared(); managed_tf_buffer_->transformPointcloud(output_frame_, *cloud, *transformed_cloud_ptr); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 777f5cbf2e22d..975ebd68fee69 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -327,15 +327,15 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - for (const auto & pair : topic_to_transformed_cloud_map) { - if (pair.second != nullptr) { + for (const auto & [topic, transformed_cloud] : topic_to_transformed_cloud_map) { + if (transformed_cloud != nullptr) { const auto pipeline_latency_ms = std::chrono::duration( std::chrono::nanoseconds( - (this->get_clock()->now() - pair.second->header.stamp).nanoseconds())) + (this->get_clock()->now() - transformed_cloud->header.stamp).nanoseconds())) .count(); debug_publisher_->publish( - "debug" + pair.first + "/pipeline_latency_ms", pipeline_latency_ms); + "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); } } } diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index f1ae44d770a63..95643ab9c720d 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -262,11 +262,9 @@ TEST_F(ConcatenateCloudTest, TestSetAndGetReferenceTimeStampBoundary) TEST_F(ConcatenateCloudTest, TestConcatenateClouds) { - rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp( - timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); - rclcpp::Time right_timestamp( - timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = @@ -437,11 +435,9 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) { - rclcpp::Time top_timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); - rclcpp::Time left_timestamp( - timestamp_seconds_, timestamp_nanoseconds_ + 40'000'000, RCL_ROS_TIME); - rclcpp::Time right_timestamp( - timestamp_seconds_, timestamp_nanoseconds_ + 80'000'000, RCL_ROS_TIME); + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generatePointCloudMsg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = From 4c0b585cddea1aed99a4b6bb6101a25c22ebc59c Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 23 Sep 2024 23:28:54 +0900 Subject: [PATCH 39/90] chore: fix spell errors Signed-off-by: vividf --- .../docs/concatenate-data.md | 2 +- .../concatenate_and_time_sync_node.hpp | 2 +- .../concatenate_and_time_sync_node.cpp | 6 +-- .../test/test_concatenate_node_component.py | 44 +++++++++---------- .../test/test_concatenate_node_unit.cpp | 2 +- 5 files changed, 28 insertions(+), 28 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 2303e65129fda..a81dd3f91c6ef 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -67,7 +67,7 @@ The figure below demonstrates how `lidar_timestamp_offsets` works with `concaten Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan, as shown in the image below. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. -User can use [this tool](https://github.com/tier4/timestamp_analyzer) to visualize the noise betweeen each scan. +User can use [this tool](https://github.com/tier4/timestamp_analyzer) to visualize the noise between each scan. ![jitter](./image/jitter.png) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 88cd68873bdbb..055718f45829e 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -85,7 +85,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node } params_; double current_concatenate_cloud_timestamp_{0.0}; - double lastest_concatenate_cloud_timestamp_{0.0}; + double latest_concatenate_cloud_timestamp_{0.0}; bool drop_previous_but_late_pointcloud_{false}; bool publish_pointcloud_{false}; double diagnostic_reference_timestamp_min_{0.0}; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 975ebd68fee69..75bb32781c694 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -86,7 +86,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } if (params_.lidar_timestamp_noise_window.size() != params_.input_topics.size()) { RCLCPP_ERROR( - get_logger(), "The number of topics does not match the number of timestamp noise windwo"); + get_logger(), "The number of topics does not match the number of timestamp noise window"); return; } @@ -286,12 +286,12 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds(); if ( - current_concatenate_cloud_timestamp_ < lastest_concatenate_cloud_timestamp_ && + current_concatenate_cloud_timestamp_ < latest_concatenate_cloud_timestamp_ && !params_.publish_previous_but_late_pointcloud) { drop_previous_but_late_pointcloud_ = true; } else { publish_pointcloud_ = true; - lastest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; + latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; auto concatenate_pointcloud_output = std::make_unique(*concatenate_cloud_ptr); concatenated_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index 84f08a2b8725e..b0ecc7e961b7d 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -66,7 +66,7 @@ COARSE_TOLERANCE = TIMESTAMP_NOISE * 2 global_seconds = 10 -global_nanosceonds = 100000000 +global_nanoseconds = 100000000 @pytest.mark.launch_test @@ -216,7 +216,7 @@ def generate_transform_msg( qw: float, ) -> TransformStamped: tf_msg = TransformStamped() - tf_msg.header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() + tf_msg.header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanoseconds).to_msg() tf_msg.header.frame_id = parent_frame tf_msg.child_frame_id = child_frame tf_msg.transform.translation.x = x @@ -271,7 +271,7 @@ def generate_static_transform_msgs() -> List[TransformStamped]: def generate_twist_msg() -> TwistWithCovarianceStamped: twist_header = Header() - twist_header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanosceonds).to_msg() + twist_header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanoseconds).to_msg() twist_header.frame_id = "base_link" twist_msg = TwistWithCovarianceStamped() twist_msg.header = twist_header @@ -362,7 +362,7 @@ def test_1_normal_inputs(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -405,7 +405,7 @@ def test_1_normal_inputs(self): self.assertTrue( np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) self.assertEqual( @@ -432,7 +432,7 @@ def test_2_normal_inputs_with_noise(self): noise = random.uniform(-10, 10) * MILLISECONDS pointcloud_seconds = global_seconds pointcloud_nanoseconds = ( - global_nanosceonds + frame_idx * MILLISECONDS * 40 + noise + global_nanoseconds + frame_idx * MILLISECONDS * 40 + noise ) # add 40 ms and noise (-10 to 10 ms) pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -475,7 +475,7 @@ def test_2_normal_inputs_with_noise(self): self.assertTrue( np.allclose(concatenate_cloud, expected_pointcloud, atol=2e-2), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) def test_3_abnormal_null_pointcloud(self): @@ -492,7 +492,7 @@ def test_3_abnormal_null_pointcloud(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -542,7 +542,7 @@ def test_3_abnormal_null_pointcloud(self): self.assertTrue( np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) global_seconds += 1 @@ -560,7 +560,7 @@ def test_4_abnormal_null_pointcloud_and_drop(self): self.twist_publisher.publish(twist_msg) pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + pointcloud_nanoseconds = global_nanoseconds pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -599,7 +599,7 @@ def test_5_abnormal_multiple_pointcloud_drop(self): self.twist_publisher.publish(twist_msg) pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + pointcloud_nanoseconds = global_nanoseconds pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -638,7 +638,7 @@ def test_5_abnormal_multiple_pointcloud_drop(self): self.assertTrue( np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) def test_6_abnormal_single_pointcloud_drop(self): @@ -655,7 +655,7 @@ def test_6_abnormal_single_pointcloud_drop(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -696,7 +696,7 @@ def test_6_abnormal_single_pointcloud_drop(self): self.assertTrue( np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) global_seconds += 1 @@ -716,7 +716,7 @@ def test_7_abnormal_pointcloud_delay(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -734,7 +734,7 @@ def test_7_abnormal_pointcloud_delay(self): pointcloud_seconds = global_seconds pointcloud_nanoseconds = ( - global_nanosceonds + (len(INPUT_LIDAR_TOPICS) - 1) * MILLISECONDS * 40 + global_nanoseconds + (len(INPUT_LIDAR_TOPICS) - 1) * MILLISECONDS * 40 ) # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -776,7 +776,7 @@ def test_7_abnormal_pointcloud_delay(self): self.assertTrue( np.allclose(concatenate_cloud1, expected_pointcloud1, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) expected_pointcloud2 = np.array( @@ -794,7 +794,7 @@ def test_7_abnormal_pointcloud_delay(self): self.assertTrue( np.allclose(concatenate_cloud2, expected_pointcloud2, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) global_seconds += 1 @@ -814,7 +814,7 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanosceonds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -830,7 +830,7 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): time.sleep(TIMEOUT_SEC) rclpy.spin_once(self.node) - next_global_nanosecond = global_nanosceonds + 100 * MILLISECONDS + next_global_nanosecond = global_nanoseconds + 100 * MILLISECONDS for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): pointcloud_seconds = global_seconds pointcloud_nanoseconds = ( @@ -874,7 +874,7 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): self.assertTrue( np.allclose(concatenate_cloud1, expected_pointcloud1, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) expected_pointcloud2 = np.array( @@ -898,7 +898,7 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): self.assertTrue( np.allclose(concatenate_cloud2, expected_pointcloud2, atol=1e-3), - "The concatenation node have wierd output", + "The concatenation node have weird output", ) global_seconds += 1 diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 95643ab9c720d..8124dd2bff3ee 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -320,7 +320,7 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) EXPECT_FLOAT_EQ( top_timestamp.seconds(), rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds()); - // test seperated transformed cloud + // test separated transformed cloud std::array expected_top_pointcloud = { {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; From 2decb6503b9bd29b14978878a4c178a3e894bec2 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 23 Sep 2024 23:36:13 +0900 Subject: [PATCH 40/90] chore: fix more spell error Signed-off-by: vividf --- .../docs/concatenate-data.md | 2 +- .../test/test_concatenate_node_component.py | 6 +++--- .../test/test_concatenate_node_unit.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index a81dd3f91c6ef..d558fa4ba98d1 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -2,7 +2,7 @@ ## Purpose -The `concatenate_and_time_synchronize_node` is a ROS2 node that combines and synchronizes multiple point clouds into a single concatenated point cloud. This enhances the sensing range for autonomous driving vehicles by integrating data from multiple LiDARs. +The `concatenate_and_time_synchronize_node` is a ros2 node that combines and synchronizes multiple point clouds into a single concatenated point cloud. This enhances the sensing range for autonomous driving vehicles by integrating data from multiple LiDARs. ## Inner Workings / Algorithms diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index b0ecc7e961b7d..86b138d553af8 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -108,7 +108,7 @@ def generate_test_description(): ) container = ComposableNodeContainer( - name="test_concateante_data_container", + name="test_concatenate_data_container", namespace="pointcloud_preprocessor", package="rclcpp_components", executable="component_container", @@ -282,7 +282,7 @@ def generate_twist_msg() -> TwistWithCovarianceStamped: def get_output_points(cloud_msg) -> np.ndarray: points_list = [] - for point in point_cloud2.read_points(cloud_msg, field_names=("x", "y", "z"), skip_nans=True): + for point in point_cloud2.read_points(cloud_msg, field_names=("x", "y", "z")): points_list.append([point[0], point[1], point[2]]) points = np.array(points_list, dtype=np.float32) return points @@ -587,7 +587,7 @@ def test_4_abnormal_null_pointcloud_and_drop(self): global_seconds += 1 def test_5_abnormal_multiple_pointcloud_drop(self): - """Test the abnormal situation when multiple pointclouds were dropped (only one poincloud arrive). + """Test the abnormal situation when multiple pointclouds were dropped (only one pointcloud arrive). This can test that 1. The concatenate node concatenates the single pointcloud after the timeout. diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 8124dd2bff3ee..44e96e9b04295 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -38,7 +38,7 @@ class ConcatenateCloudTest : public ::testing::Test void SetUp() override { rclcpp::NodeOptions node_options; - // Instead of "input_topics", other parameters are not unsed. + // Instead of "input_topics", other parameters are not used. // They just helps to setup the concatenate node node_options.parameter_overrides( {{"has_static_tf_only", false}, From eeb310dcef5c7bfc8332e8f25af23e9bc5a5c003 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 25 Sep 2024 09:25:50 +0900 Subject: [PATCH 41/90] chore: rename mutex and lock Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.hpp | 2 +- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 055718f45829e..b7f9796cbbf1d 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -95,7 +95,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::shared_ptr combine_cloud_handler_; std::shared_ptr cloud_collector_; std::list> cloud_collectors_; - std::mutex mutex_; + std::mutex cloud_collectors_mutex_; std::unordered_map topic_to_offset_map_; std::unordered_map topic_to_noise_window_map_; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 75bb32781c694..32a5f7188416b 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -220,7 +220,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( } // protect cloud collectors list - std::unique_lock lock(mutex_); + std::unique_lock cloud_collectors_lock(cloud_collectors_mutex_); // For each callback, check whether there is a exist collector that matches this cloud bool collector_found = false; @@ -235,7 +235,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( reference_timestamp_max + topic_to_noise_window_map_[topic_name] && rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] > reference_timestamp_min - topic_to_noise_window_map_[topic_name]) { - lock.unlock(); + cloud_collectors_lock.unlock(); cloud_collector->processCloud(topic_name, input_ptr); collector_found = true; break; @@ -250,7 +250,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( cloud_collectors_, combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec); cloud_collectors_.push_back(new_cloud_collector); - lock.unlock(); + cloud_collectors_lock.unlock(); new_cloud_collector->setReferenceTimeStamp( rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name], topic_to_noise_window_map_[topic_name]); From 9a85a521956db4b6309bf25a5791c958bbb03639 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 25 Sep 2024 09:33:32 +0900 Subject: [PATCH 42/90] chore: const reference for string parameter Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 2 +- .../src/concatenate_data/cloud_collector.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index ed1767e983414..1210f43048c5e 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -38,7 +38,7 @@ class CloudCollector void setReferenceTimeStamp(double timestamp, double noise_window); std::tuple getReferenceTimeStampBoundary(); - void processCloud(std::string topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); + void processCloud(const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); void concatenateCallback(); std::tuple< sensor_msgs::msg::PointCloud2::SharedPtr, diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 1887f3e07b4ad..d1dc88ad80a93 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -54,7 +54,7 @@ std::tuple CloudCollector::getReferenceTimeStampBoundary() } void CloudCollector::processCloud( - std::string topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) + const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) { // Check if the map already contains an entry for the same topic. This shouldn't happen if the // parameter 'lidar_timestamp_noise_window' is set correctly. From 111489858eef6d518a9ff78d3b75e47c34da8e4f Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 25 Sep 2024 17:41:28 +0900 Subject: [PATCH 43/90] chore: add explaination for RclcppTimeHash_ Signed-off-by: vividf --- .../concatenate_data/combine_cloud_handler.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index bcbd40bc6a2a3..68d3d97b26d25 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -59,6 +59,8 @@ class CombineCloudHandler bool keep_input_frame_in_synchronized_pointcloud_; std::unique_ptr managed_tf_buffer_{nullptr}; + /// @brief RclcppTimeHash_ structure defines a custom hash function for the rclcpp::Time type by + /// using its nanoseconds representation as the hash value. struct RclcppTimeHash_ { std::size_t operator()(const rclcpp::Time & t) const From 84b547c93c5dd9821352f1b28c5cbbaaae89d344 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 25 Sep 2024 17:57:18 +0900 Subject: [PATCH 44/90] chore: change the concatenate node to parent node Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 4 ++-- .../src/concatenate_data/cloud_collector.cpp | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 1210f43048c5e..be18aa7052f45 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -32,7 +32,7 @@ class CloudCollector { public: CloudCollector( - std::shared_ptr concatenate_node, + std::shared_ptr ros2_parent_node, std::list> & collectors, std::shared_ptr combine_cloud_handler, int num_of_clouds, double time); @@ -58,7 +58,7 @@ class CloudCollector std::unordered_map getTopicToCloudMap(); private: - std::shared_ptr concatenate_node_; + std::shared_ptr ros2_parent_node_; std::list> & collectors_; std::shared_ptr combine_cloud_handler_; rclcpp::TimerBase::SharedPtr timer_; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index d1dc88ad80a93..53112842350ea 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -25,10 +25,10 @@ namespace autoware::pointcloud_preprocessor { CloudCollector::CloudCollector( - std::shared_ptr concatenate_node, + std::shared_ptr ros2_parent_node, std::list> & collectors, std::shared_ptr combine_cloud_handler, int num_of_clouds, double timeout_sec) -: concatenate_node_(concatenate_node), +: ros2_parent_node_(ros2_parent_node), collectors_(collectors), combine_cloud_handler_(combine_cloud_handler), num_of_clouds_(num_of_clouds), @@ -38,7 +38,7 @@ CloudCollector::CloudCollector( std::chrono::duration(timeout_sec_)); timer_ = rclcpp::create_timer( - concatenate_node_, concatenate_node_->get_clock(), period_ns, + ros2_parent_node_, ros2_parent_node_->get_clock(), period_ns, std::bind(&CloudCollector::concatenateCallback, this)); } @@ -60,7 +60,7 @@ void CloudCollector::processCloud( // parameter 'lidar_timestamp_noise_window' is set correctly. if (topic_to_cloud_map_.find(topic_name) != topic_to_cloud_map_.end()) { RCLCPP_WARN_STREAM_THROTTLE( - concatenate_node_->get_logger(), *concatenate_node_->get_clock(), + ros2_parent_node_->get_logger(), *ros2_parent_node_->get_clock(), std::chrono::milliseconds(10000).count(), "Topic '" << topic_name << "' already exists in the collector. Check the timestamp of the pointcloud."); @@ -101,7 +101,7 @@ void CloudCollector::publishClouds( topic_to_transformed_cloud_map, std::unordered_map topic_to_original_stamp_map) { - concatenate_node_->publishClouds( + ros2_parent_node_->publishClouds( concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map, reference_timestamp_min_, reference_timestamp_max_); } From e49d521da8ca0096b6243319fa16cd37f4f73012 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 25 Sep 2024 18:51:59 +0900 Subject: [PATCH 45/90] chore: clean processOdometry and processTwist Signed-off-by: vividf --- .../concatenate_data/combine_cloud_handler.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 6db3dc12d3295..cf240a0660988 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -52,11 +52,11 @@ void CombineCloudHandler::processTwist( } } - // pop old data + // twist data that older than 1s will be cleared + auto cutoff_time = rclcpp::Time(input->header.stamp) - rclcpp::Duration::from_seconds(1.0); + 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)) { + if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > cutoff_time) { break; } twist_ptr_queue_.pop_front(); @@ -77,11 +77,11 @@ void CombineCloudHandler::processOdometry(const nav_msgs::msg::Odometry::ConstSh } } - // pop old data + // odometry data that older than 1s will be cleared + auto cutoff_time = rclcpp::Time(input->header.stamp) - rclcpp::Duration::from_seconds(1.0); + 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)) { + if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > cutoff_time) { break; } twist_ptr_queue_.pop_front(); From 5ae681c37aab4bcd12a74b4012c747280e95853c Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 10:56:08 +0900 Subject: [PATCH 46/90] chore: change twist shared pointer queue to twist queue Signed-off-by: vividf --- .../combine_cloud_handler.hpp | 6 +- .../combine_cloud_handler.cpp | 100 ++++++++++-------- .../test/test_concatenate_node_unit.cpp | 81 ++++++++++---- 3 files changed, 116 insertions(+), 71 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 68d3d97b26d25..133f063f7370f 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -59,6 +59,8 @@ class CombineCloudHandler bool keep_input_frame_in_synchronized_pointcloud_; std::unique_ptr managed_tf_buffer_{nullptr}; + std::deque twist_queue_; + /// @brief RclcppTimeHash_ structure defines a custom hash function for the rclcpp::Time type by /// using its nanoseconds representation as the hash value. struct RclcppTimeHash_ @@ -70,8 +72,6 @@ class CombineCloudHandler }; public: - std::deque twist_ptr_queue_; - CombineCloudHandler( rclcpp::Node * node, std::vector input_topics, std::string output_frame, bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud, @@ -88,6 +88,8 @@ class CombineCloudHandler Eigen::Matrix4f computeTransformToAdjustForOldTimestamp( const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); + + std::deque getTwistQueue(); }; } // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index cf240a0660988..6f9ba805e5779 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -42,55 +42,65 @@ CombineCloudHandler::CombineCloudHandler( { } +// TODO(vivid): change this to process_twist_message void CombineCloudHandler::processTwist( - const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input) + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg) { + geometry_msgs::msg::TwistStamped msg; + msg.header = twist_msg->header; + msg.twist = twist_msg->twist.twist; + // If time jumps backwards (e.g. when a rosbag restarts), 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(); + if (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > rclcpp::Time(msg.header.stamp)) { + twist_queue_.clear(); } } - // twist data that older than 1s will be cleared - auto cutoff_time = rclcpp::Time(input->header.stamp) - rclcpp::Duration::from_seconds(1.0); + // Twist data in the queue that is older than the current twist by 1 second will be cleared. + auto cutoff_time = rclcpp::Time(msg.header.stamp) - rclcpp::Duration::from_seconds(1.0); - while (!twist_ptr_queue_.empty()) { - if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > cutoff_time) { + while (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > cutoff_time) { break; } - twist_ptr_queue_.pop_front(); + twist_queue_.pop_front(); } - auto twist_ptr = std::make_shared(); - twist_ptr->header = input->header; - twist_ptr->twist = input->twist.twist; - twist_ptr_queue_.push_back(twist_ptr); + twist_queue_.push_back(msg); } -void CombineCloudHandler::processOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input) +// TODO(vivid): change this to process_odometry_message +void CombineCloudHandler::processOdometry( + const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_msg) { - // 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(); + geometry_msgs::msg::TwistStamped msg; + msg.header = odometry_msg->header; + msg.twist = odometry_msg->twist.twist; + + // If time jumps backwards (e.g. when a rosbag restarts), clear buffer + if (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > rclcpp::Time(msg.header.stamp)) { + twist_queue_.clear(); } } - // odometry data that older than 1s will be cleared - auto cutoff_time = rclcpp::Time(input->header.stamp) - rclcpp::Duration::from_seconds(1.0); + // Twist data in the queue that is older than the current twist by 1 second will be cleared. + auto cutoff_time = rclcpp::Time(msg.header.stamp) - rclcpp::Duration::from_seconds(1.0); - while (!twist_ptr_queue_.empty()) { - if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > cutoff_time) { + while (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > cutoff_time) { break; } - twist_ptr_queue_.pop_front(); + twist_queue_.pop_front(); } - auto twist_ptr = std::make_shared(); - twist_ptr->header = input->header; - twist_ptr->twist = input->twist.twist; - twist_ptr_queue_.push_back(twist_ptr); + twist_queue_.push_back(msg); +} + +std::deque CombineCloudHandler::getTwistQueue() +{ + return twist_queue_; } std::tuple< @@ -184,7 +194,7 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) { // return identity if no twist is available - if (twist_ptr_queue_.empty()) { + if (twist_queue_.empty()) { RCLCPP_WARN_STREAM_THROTTLE( node_->get_logger(), *node_->get_clock(), std::chrono::milliseconds(10000).count(), "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud " @@ -192,31 +202,29 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( 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; + auto old_twist_it = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), old_stamp, + [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { + return rclcpp::Time(x.header.stamp) < t; }); - old_twist_ptr_it = - old_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : old_twist_ptr_it; + old_twist_it = old_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : old_twist_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; + auto new_twist_it = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), new_stamp, + [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { + return rclcpp::Time(x.header.stamp) < t; }); - new_twist_ptr_it = - new_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : new_twist_ptr_it; + new_twist_it = new_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : new_twist_it; auto prev_time = old_stamp; double x = 0.0; double y = 0.0; double yaw = 0.0; tf2::Quaternion baselink_quat{}; - for (auto twist_ptr_it = old_twist_ptr_it; twist_ptr_it != new_twist_ptr_it + 1; ++twist_ptr_it) { + for (auto twist_it = old_twist_it; twist_it != new_twist_it + 1; ++twist_it) { const double dt = - (twist_ptr_it != new_twist_ptr_it) - ? (rclcpp::Time((*twist_ptr_it)->header.stamp) - rclcpp::Time(prev_time)).seconds() + (twist_it != new_twist_it) + ? (rclcpp::Time((*twist_it).header.stamp) - rclcpp::Time(prev_time)).seconds() : (rclcpp::Time(new_stamp) - rclcpp::Time(prev_time)).seconds(); if (std::fabs(dt) > 0.1) { @@ -227,11 +235,11 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( break; } - const double dis = (*twist_ptr_it)->twist.linear.x * dt; - yaw += (*twist_ptr_it)->twist.angular.z * dt; + const double dis = (*twist_it).twist.linear.x * dt; + yaw += (*twist_it).twist.angular.z * dt; x += dis * std::cos(yaw); y += dis * std::sin(yaw); - prev_time = (*twist_ptr_it)->header.stamp; + prev_time = (*twist_it).header.stamp; } Eigen::Matrix4f transformation_matrix = Eigen::Matrix4f::Identity(); diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 44e96e9b04295..95ec3133cbc25 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -190,9 +190,9 @@ TEST_F(ConcatenateCloudTest, TestProcessTwist) combine_cloud_handler_->processTwist(twist_msg); - ASSERT_FALSE(combine_cloud_handler_->twist_ptr_queue_.empty()); - EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.linear.x, 1.0); - EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.angular.z, 0.1); + ASSERT_FALSE(combine_cloud_handler_->getTwistQueue().empty()); + EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.angular.z, 0.1); } TEST_F(ConcatenateCloudTest, TestProcessOdometry) @@ -204,31 +204,65 @@ TEST_F(ConcatenateCloudTest, TestProcessOdometry) combine_cloud_handler_->processOdometry(odom_msg); - ASSERT_FALSE(combine_cloud_handler_->twist_ptr_queue_.empty()); - EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.linear.x, 1.0); - EXPECT_EQ(combine_cloud_handler_->twist_ptr_queue_.front()->twist.angular.z, 0.1); + ASSERT_FALSE(combine_cloud_handler_->getTwistQueue().empty()); + EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.angular.z, 0.1); } TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) { - rclcpp::Time old_stamp(10, 100'000'000, RCL_ROS_TIME); - rclcpp::Time new_stamp(10, 150'000'000, RCL_ROS_TIME); + // If time difference between twist msg and pointcloud stamp is more than 100 miliseconds, return + // Identity transformation. case 1: time differecne larger than 100 miliseconds + rclcpp::Time pointcloud_stamp1(10, 100'000'000, RCL_ROS_TIME); + rclcpp::Time pointcloud_stamp2(10, 210'000'000, RCL_ROS_TIME); + auto twist_msg1 = std::make_shared(); + twist_msg1->header.stamp = rclcpp::Time(9, 130'000'000, RCL_ROS_TIME); + twist_msg1->twist.twist.linear.x = 1.0; + twist_msg1->twist.twist.angular.z = 0.1; + combine_cloud_handler_->processTwist(twist_msg1); + + auto twist_msg2 = std::make_shared(); + twist_msg2->header.stamp = rclcpp::Time(9, 160'000'000, RCL_ROS_TIME); + twist_msg2->twist.twist.linear.x = 1.0; + twist_msg2->twist.twist.angular.z = 0.1; + combine_cloud_handler_->processTwist(twist_msg2); + + Eigen::Matrix4f transform = combine_cloud_handler_->computeTransformToAdjustForOldTimestamp( + pointcloud_stamp1, pointcloud_stamp2); - // Time difference between twist msg is more than 100 miliseconds, won't calculate the difference - auto twist_msg1 = std::make_shared(); - twist_msg1->header.stamp = rclcpp::Time(10, 130'000'000, RCL_ROS_TIME); - twist_msg1->twist.linear.x = 1.0; - twist_msg1->twist.angular.z = 0.1; - combine_cloud_handler_->twist_ptr_queue_.push_back(twist_msg1); + // translation + EXPECT_NEAR(transform(0, 3), 0.0, standard_tolerance); + EXPECT_NEAR(transform(1, 3), 0.0, standard_tolerance); + + EXPECT_NEAR(transform(0, 0), 1.0, standard_tolerance); + EXPECT_NEAR(transform(0, 1), 0.0, standard_tolerance); + EXPECT_NEAR(transform(1, 0), 0.0, standard_tolerance); + EXPECT_NEAR(transform(1, 1), 1.0, standard_tolerance); + + std::ostringstream oss; + oss << "Transformation matrix from cloud 2 to cloud 1:\n" << transform; + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + // case 2: time difference smaller than 100 miliseconds + rclcpp::Time pointcloud_stamp3(11, 100'000'000, RCL_ROS_TIME); + rclcpp::Time pointcloud_stamp4(11, 150'000'000, RCL_ROS_TIME); + auto twist_msg3 = std::make_shared(); + twist_msg3->header.stamp = rclcpp::Time(11, 130'000'000, RCL_ROS_TIME); + twist_msg3->twist.twist.linear.x = 1.0; + twist_msg3->twist.twist.angular.z = 0.1; + combine_cloud_handler_->processTwist(twist_msg3); - auto twist_msg2 = std::make_shared(); - twist_msg2->header.stamp = rclcpp::Time(10, 160'000'000, RCL_ROS_TIME); - twist_msg2->twist.linear.x = 1.0; - twist_msg2->twist.angular.z = 0.1; - combine_cloud_handler_->twist_ptr_queue_.push_back(twist_msg2); + auto twist_msg4 = std::make_shared(); + twist_msg4->header.stamp = rclcpp::Time(11, 160'000'000, RCL_ROS_TIME); + twist_msg4->twist.twist.linear.x = 1.0; + twist_msg4->twist.twist.angular.z = 0.1; + combine_cloud_handler_->processTwist(twist_msg4); - Eigen::Matrix4f transform = - combine_cloud_handler_->computeTransformToAdjustForOldTimestamp(old_stamp, new_stamp); + transform = combine_cloud_handler_->computeTransformToAdjustForOldTimestamp( + pointcloud_stamp3, pointcloud_stamp4); // translation EXPECT_NEAR(transform(0, 3), 0.0499996, standard_tolerance); @@ -240,8 +274,9 @@ TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) EXPECT_NEAR(transform(1, 0), 0.00499998, standard_tolerance); EXPECT_NEAR(transform(1, 1), 0.999987, standard_tolerance); - std::ostringstream oss; - oss << "Transformation matrix:\n" << transform; + oss.str(""); + oss.clear(); + oss << "Transformation matrix from cloud 4 to cloud 3:\n" << transform; if (debug_) { RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); From 3a8ff07acff3a6d5b747830b518569f409c10686 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 13:33:36 +0900 Subject: [PATCH 47/90] chore: refactor compensate pointcloud to function Signed-off-by: vividf --- .../combine_cloud_handler.hpp | 6 +++ .../combine_cloud_handler.cpp | 53 +++++++++++-------- 2 files changed, 36 insertions(+), 23 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 133f063f7370f..d8af18a27b6b5 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -71,6 +71,12 @@ class CombineCloudHandler } }; + void correctPointCloudMotion( + const std::shared_ptr & transformed_cloud_ptr, + const std::vector & pc_stamps, + std::unordered_map & transform_memo, + std::shared_ptr transformed_delay_compensated_cloud_ptr); + public: CombineCloudHandler( rclcpp::Node * node, std::vector input_topics, std::string output_frame, diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 6f9ba805e5779..dd5f8f00bc459 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -103,6 +103,31 @@ std::deque CombineCloudHandler::getTwistQueue( return twist_queue_; } +void CombineCloudHandler::correctPointCloudMotion( + const std::shared_ptr & transformed_cloud_ptr, + const std::vector & pc_stamps, + std::unordered_map & transform_memo, + std::shared_ptr transformed_delay_compensated_cloud_ptr) +{ + Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); + rclcpp::Time current_cloud_stamp = rclcpp::Time(transformed_cloud_ptr->header.stamp); + for (const auto & stamp : pc_stamps) { + if (stamp >= current_cloud_stamp) continue; + + Eigen::Matrix4f new_to_old_transform; + if (transform_memo.find(stamp) != transform_memo.end()) { + new_to_old_transform = transform_memo[stamp]; + } else { + new_to_old_transform = computeTransformToAdjustForOldTimestamp(stamp, current_cloud_stamp); + transform_memo[stamp] = new_to_old_transform; + } + adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform; + current_cloud_stamp = stamp; + } + pcl_ros::transformPointCloud( + adjust_to_old_data_transform, *transformed_cloud_ptr, *transformed_delay_compensated_cloud_ptr); +} + std::tuple< sensor_msgs::msg::PointCloud2::SharedPtr, std::unordered_map, @@ -130,30 +155,12 @@ CombineCloudHandler::combinePointClouds( topic_to_original_stamp_map[topic] = rclcpp::Time(cloud->header.stamp).seconds(); - auto transformed_delay_compensated_cloud_ptr = - std::make_shared(); - + // compensate pointcloud + std::shared_ptr transformed_delay_compensated_cloud_ptr; if (is_motion_compensated_) { - Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); - rclcpp::Time current_cloud_stamp = rclcpp::Time(cloud->header.stamp); - for (const auto & stamp : pc_stamps) { - if (stamp >= current_cloud_stamp) continue; - - Eigen::Matrix4f new_to_old_transform; - if (transform_memo.find(stamp) != transform_memo.end()) { - new_to_old_transform = transform_memo[stamp]; - } else { - new_to_old_transform = - computeTransformToAdjustForOldTimestamp(stamp, current_cloud_stamp); - transform_memo[stamp] = new_to_old_transform; - } - adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform; - current_cloud_stamp = stamp; - } - pcl_ros::transformPointCloud( - adjust_to_old_data_transform, *transformed_cloud_ptr, - *transformed_delay_compensated_cloud_ptr); - + transformed_delay_compensated_cloud_ptr = std::make_shared(); + correctPointCloudMotion( + transformed_cloud_ptr, pc_stamps, transform_memo, transformed_delay_compensated_cloud_ptr); } else { transformed_delay_compensated_cloud_ptr = transformed_cloud_ptr; } From 49b54d4d49865b7745791d4204f2a1593c1122a2 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 13:49:28 +0900 Subject: [PATCH 48/90] chore: reallocate memory for concatenate_cloud_ptr Signed-off-by: vividf --- .../combine_cloud_handler.cpp | 33 +++++++++++++++---- 1 file changed, 27 insertions(+), 6 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index dd5f8f00bc459..1d49d6c9cc781 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -165,15 +165,36 @@ CombineCloudHandler::combinePointClouds( transformed_delay_compensated_cloud_ptr = transformed_cloud_ptr; } - // concatenate + // Check if concatenate_cloud_ptr is nullptr, if so initialize it if (concatenate_cloud_ptr == nullptr) { - concatenate_cloud_ptr = - std::make_shared(*transformed_delay_compensated_cloud_ptr); - } else { - pcl::concatenatePointCloud( - *concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concatenate_cloud_ptr); + // Initialize concatenate_cloud_ptr without copying the data + concatenate_cloud_ptr = std::make_shared(); + concatenate_cloud_ptr->header = transformed_delay_compensated_cloud_ptr->header; + concatenate_cloud_ptr->height = transformed_delay_compensated_cloud_ptr->height; + concatenate_cloud_ptr->width = 0; // Will be updated with total points + concatenate_cloud_ptr->is_dense = transformed_delay_compensated_cloud_ptr->is_dense; + concatenate_cloud_ptr->is_bigendian = transformed_delay_compensated_cloud_ptr->is_bigendian; + concatenate_cloud_ptr->fields = transformed_delay_compensated_cloud_ptr->fields; + concatenate_cloud_ptr->point_step = transformed_delay_compensated_cloud_ptr->point_step; + concatenate_cloud_ptr->row_step = 0; // Will be updated after concatenation + concatenate_cloud_ptr->data.clear(); + + // Reserve space for the data (assume max points you expect to concatenate) + auto num_of_points = transformed_delay_compensated_cloud_ptr->width * + transformed_delay_compensated_cloud_ptr->height; + concatenate_cloud_ptr->data.reserve(num_of_points * concatenate_cloud_ptr->point_step); } + // Concatenate the current pointcloud to the concatenated cloud + pcl::concatenatePointCloud( + *concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concatenate_cloud_ptr); + + // Update width and row_step to reflect the new size + concatenate_cloud_ptr->width = + concatenate_cloud_ptr->data.size() / concatenate_cloud_ptr->point_step; + concatenate_cloud_ptr->row_step = + concatenate_cloud_ptr->width * concatenate_cloud_ptr->point_step; + // convert to original sensor frame if necessary bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { From de94fa6cf2ff7ae9b2a00bf705271fba7c7bc30a Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 13:51:45 +0900 Subject: [PATCH 49/90] chore: remove new to make shared Signed-off-by: vividf --- .../src/concatenate_data/combine_cloud_handler.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 1d49d6c9cc781..dd0184ef2188d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -198,8 +198,8 @@ CombineCloudHandler::combinePointClouds( // convert to original sensor frame if necessary bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { - sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame( - new sensor_msgs::msg::PointCloud2()); + auto transformed_cloud_ptr_in_sensor_frame = + std::make_shared(); managed_tf_buffer_->transformPointcloud( cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, *transformed_cloud_ptr_in_sensor_frame); From 79791530af64f437b89324fb5ce40377c96f1f1b Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 14:08:24 +0900 Subject: [PATCH 50/90] chore: dis to distance Signed-off-by: vividf --- .../src/concatenate_data/combine_cloud_handler.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index dd0184ef2188d..7f6d01cc9da8b 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -263,10 +263,10 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( break; } - const double dis = (*twist_it).twist.linear.x * dt; + const double distance = (*twist_it).twist.linear.x * dt; yaw += (*twist_it).twist.angular.z * dt; - x += dis * std::cos(yaw); - y += dis * std::sin(yaw); + x += distance * std::cos(yaw); + y += distance * std::sin(yaw); prev_time = (*twist_it).header.stamp; } From b344427281484082c80fd8c5b3993754652dd91d Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 14:23:42 +0900 Subject: [PATCH 51/90] chore: refacotr poitncloud_sub Signed-off-by: vividf --- .../concatenate_and_time_sync_node.hpp | 2 +- .../concatenate_and_time_sync_node.cpp | 12 +++++------- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index b7f9796cbbf1d..f93266d4153a9 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -100,7 +100,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unordered_map topic_to_noise_window_map_; // subscribers - std::vector::SharedPtr> pointcloud_subs; + std::vector::SharedPtr> pointcloud_subs_; rclcpp::Subscription::SharedPtr twist_sub_; rclcpp::Subscription::SharedPtr odom_sub_; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 32a5f7188416b..cf5c248f1c4e4 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -132,16 +132,14 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } } - pointcloud_subs.resize(params_.input_topics.size()); - for (size_t topic_id = 0; topic_id < params_.input_topics.size(); ++topic_id) { + for (const std::string & topic : params_.input_topics) { std::function callback = std::bind( &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1, - params_.input_topics[topic_id]); + topic); - pointcloud_subs[topic_id].reset(); - pointcloud_subs[topic_id] = this->create_subscription( - params_.input_topics[topic_id], rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size), - callback); + auto pointcloud_sub = this->create_subscription( + topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size), callback); + pointcloud_subs_.push_back(pointcloud_sub); } RCLCPP_DEBUG_STREAM( get_logger(), From b0c8a7c479b189cd3ab0772598bb0bac9f75ec06 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 14:34:08 +0900 Subject: [PATCH 52/90] chore: return early return but throw runtime error Signed-off-by: vividf --- .../concatenate_and_time_sync_node.cpp | 20 ++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index cf5c248f1c4e4..215d5e4d163b5 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -46,6 +46,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); + bool parameters_valid = true; // initialize parameters params_.has_static_tf_only = declare_parameter("has_static_tf_only"); params_.maximum_queue_size = declare_parameter("maximum_queue_size"); @@ -69,25 +70,25 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro if (params_.input_topics.empty()) { RCLCPP_ERROR(get_logger(), "Need a 'input_topics' parameter to be set before continuing!"); - return; + parameters_valid = false; } else if (params_.input_topics.size() == 1) { RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue."); - return; + parameters_valid = false; } if (params_.output_frame.empty()) { RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); - return; + parameters_valid = false; } if (params_.lidar_timestamp_offsets.size() != params_.input_topics.size()) { RCLCPP_ERROR( get_logger(), "The number of topics does not match the number of timestamp offsets"); - return; + parameters_valid = false; } if (params_.lidar_timestamp_noise_window.size() != params_.input_topics.size()) { RCLCPP_ERROR( get_logger(), "The number of topics does not match the number of timestamp noise window"); - return; + parameters_valid = false; } for (size_t i = 0; i < params_.input_topics.size(); i++) { @@ -127,11 +128,16 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } else { RCLCPP_ERROR_STREAM( get_logger(), "input_twist_topic_type is invalid: " << params_.input_twist_topic_type); - throw std::runtime_error( - "input_twist_topic_type is invalid: " + params_.input_twist_topic_type); + parameters_valid = false; } } + if (!parameters_valid) { + throw std::runtime_error( + "Invalid parameter setting detected. Please review the provided parameter values and refer " + "to the error logs for detailed information."); + } + for (const std::string & topic : params_.input_topics) { std::function callback = std::bind( &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1, From fa0c4dc5534cde4c586aa8fe5996113919821501 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 15:11:23 +0900 Subject: [PATCH 53/90] chore: replace #define DEFAULT_SYNC_TOPIC_POSTFIX with member variable Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.hpp | 3 +++ .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 5 +---- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index f93266d4153a9..bd835504591f9 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -99,6 +99,9 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unordered_map topic_to_offset_map_; std::unordered_map topic_to_noise_window_map_; + // default postfix name for synchronized pointcloud + static constexpr const char * default_sync_topic_postfix_ = "_synchronized"; + // subscribers std::vector::SharedPtr> pointcloud_subs_; rclcpp::Subscription::SharedPtr twist_sub_; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 215d5e4d163b5..8f141cfe16b36 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -28,9 +28,6 @@ #include #include -#define DEFAULT_SYNC_TOPIC_POSTFIX \ - "_synchronized" // default postfix name for synchronized pointcloud - namespace autoware::pointcloud_preprocessor { @@ -190,7 +187,7 @@ std::string PointCloudConcatenateDataSynchronizerComponent::replaceSyncTopicName << " 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; + replaced_topic_name = original_topic_name + default_sync_topic_postfix_; } return replaced_topic_name; } From 66a62d183e0586d2c2350bd9316f92dda6c9eb03 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 15:14:24 +0900 Subject: [PATCH 54/90] chore: fix spell error Signed-off-by: vividf --- .../test/test_concatenate_node_unit.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 95ec3133cbc25..aca5156689236 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -212,7 +212,7 @@ TEST_F(ConcatenateCloudTest, TestProcessOdometry) TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) { // If time difference between twist msg and pointcloud stamp is more than 100 miliseconds, return - // Identity transformation. case 1: time differecne larger than 100 miliseconds + // Identity transformation. case 1: time difference larger than 100 miliseconds rclcpp::Time pointcloud_stamp1(10, 100'000'000, RCL_ROS_TIME); rclcpp::Time pointcloud_stamp2(10, 210'000'000, RCL_ROS_TIME); auto twist_msg1 = std::make_shared(); From 67bfa264801ad357304985cf49a87c0e974e9289 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 15:20:03 +0900 Subject: [PATCH 55/90] chore: remove redundant function call Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 7 ------- .../src/concatenate_data/cloud_collector.cpp | 15 +++------------ 2 files changed, 3 insertions(+), 19 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index be18aa7052f45..82f71ccb0e9cf 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -46,13 +46,6 @@ class CloudCollector std::unordered_map> concatenateClouds( std::unordered_map topic_to_cloud_map); - - void publishClouds( - sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, - std::unordered_map - topic_to_transformed_cloud_map, - std::unordered_map topic_to_original_stamp_map); - void deleteCollector(); std::unordered_map getTopicToCloudMap(); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 53112842350ea..7eacc0bcebc36 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -81,7 +81,9 @@ void CloudCollector::concatenateCallback() std::lock_guard lock(mutex_); auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = concatenateClouds(topic_to_cloud_map_); - publishClouds(concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map); + ros2_parent_node_->publishClouds( + concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map, + reference_timestamp_min_, reference_timestamp_max_); deleteCollector(); } @@ -95,17 +97,6 @@ CloudCollector::concatenateClouds( return combine_cloud_handler_->combinePointClouds(topic_to_cloud_map); } -void CloudCollector::publishClouds( - sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, - std::unordered_map - topic_to_transformed_cloud_map, - std::unordered_map topic_to_original_stamp_map) -{ - ros2_parent_node_->publishClouds( - concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map, - reference_timestamp_min_, reference_timestamp_max_); -} - void CloudCollector::deleteCollector() { auto it = std::find_if( From bafaea1f1154747960e4751678a3c9b4c1f0a903 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 16:23:47 +0900 Subject: [PATCH 56/90] chore: replace conplex tuple to structure Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 7 +- .../combine_cloud_handler.hpp | 22 +++--- .../concatenate_and_time_sync_node.hpp | 7 +- .../src/concatenate_data/cloud_collector.cpp | 12 +-- .../combine_cloud_handler.cpp | 76 ++++++++++--------- .../concatenate_and_time_sync_node.cpp | 28 +++---- 6 files changed, 76 insertions(+), 76 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 82f71ccb0e9cf..759318f0a8fcb 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -40,11 +40,8 @@ class CloudCollector std::tuple getReferenceTimeStampBoundary(); void processCloud(const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); void concatenateCallback(); - std::tuple< - sensor_msgs::msg::PointCloud2::SharedPtr, - std::unordered_map, - std::unordered_map> - concatenateClouds( + + ConcatenatedCloudResult concatenateClouds( std::unordered_map topic_to_cloud_map); void deleteCollector(); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index d8af18a27b6b5..60fbeb4ba6c83 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -48,6 +48,14 @@ namespace autoware::pointcloud_preprocessor { +struct ConcatenatedCloudResult +{ + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr{nullptr}; + std::unordered_map + topic_to_transformed_cloud_map; + std::unordered_map topic_to_original_stamp_map; +}; + class CombineCloudHandler { private: @@ -61,9 +69,9 @@ class CombineCloudHandler std::deque twist_queue_; - /// @brief RclcppTimeHash_ structure defines a custom hash function for the rclcpp::Time type by + /// @brief RclcppTimeHash structure defines a custom hash function for the rclcpp::Time type by /// using its nanoseconds representation as the hash value. - struct RclcppTimeHash_ + struct RclcppTimeHash { std::size_t operator()(const rclcpp::Time & t) const { @@ -74,7 +82,7 @@ class CombineCloudHandler void correctPointCloudMotion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, - std::unordered_map & transform_memo, + std::unordered_map & transform_memo, std::shared_ptr transformed_delay_compensated_cloud_ptr); public: @@ -85,12 +93,8 @@ class CombineCloudHandler void processTwist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input); void processOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input); - std::tuple< - sensor_msgs::msg::PointCloud2::SharedPtr, - std::unordered_map, - std::unordered_map> - combinePointClouds(std::unordered_map & - topic_to_cloud_map_); + ConcatenatedCloudResult combinePointClouds( + std::unordered_map & topic_to_cloud_map); Eigen::Matrix4f computeTransformToAdjustForOldTimestamp( const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index bd835504591f9..2954315eebdf6 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -60,11 +60,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); virtual ~PointCloudConcatenateDataSynchronizerComponent() {} void publishClouds( - sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, - std::unordered_map & - topic_to_transformed_cloud_map, - std::unordered_map & topic_to_original_stamp_map, - double reference_timestamp_min, double reference_timestamp_max); + ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, + double reference_timestamp_max); private: struct Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 7eacc0bcebc36..ef3311c6f118a 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -79,19 +79,13 @@ void CloudCollector::concatenateCallback() // lock for protecting collector list and concatenated pointcloud std::lock_guard lock(mutex_); - auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = - concatenateClouds(topic_to_cloud_map_); + auto concatenated_cloud_result = concatenateClouds(topic_to_cloud_map_); ros2_parent_node_->publishClouds( - concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map, - reference_timestamp_min_, reference_timestamp_max_); + concatenated_cloud_result, reference_timestamp_min_, reference_timestamp_max_); deleteCollector(); } -std::tuple< - sensor_msgs::msg::PointCloud2::SharedPtr, - std::unordered_map, - std::unordered_map> -CloudCollector::concatenateClouds( +ConcatenatedCloudResult CloudCollector::concatenateClouds( std::unordered_map topic_to_cloud_map) { return combine_cloud_handler_->combinePointClouds(topic_to_cloud_map); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 7f6d01cc9da8b..3bf4668051858 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -106,7 +106,7 @@ std::deque CombineCloudHandler::getTwistQueue( void CombineCloudHandler::correctPointCloudMotion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, - std::unordered_map & transform_memo, + std::unordered_map & transform_memo, std::shared_ptr transformed_delay_compensated_cloud_ptr) { Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); @@ -128,17 +128,10 @@ void CombineCloudHandler::correctPointCloudMotion( adjust_to_old_data_transform, *transformed_cloud_ptr, *transformed_delay_compensated_cloud_ptr); } -std::tuple< - sensor_msgs::msg::PointCloud2::SharedPtr, - std::unordered_map, - std::unordered_map> -CombineCloudHandler::combinePointClouds( +ConcatenatedCloudResult CombineCloudHandler::combinePointClouds( std::unordered_map & topic_to_cloud_map) { - sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr = nullptr; - std::unordered_map - topic_to_transformed_cloud_map; - std::unordered_map topic_to_original_stamp_map; + ConcatenatedCloudResult concatenate_cloud_result; std::vector pc_stamps; for (const auto & [topic, cloud] : topic_to_cloud_map) { @@ -147,13 +140,14 @@ CombineCloudHandler::combinePointClouds( std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); const auto oldest_stamp = pc_stamps.back(); - std::unordered_map transform_memo; + std::unordered_map transform_memo; for (const auto & [topic, cloud] : topic_to_cloud_map) { auto transformed_cloud_ptr = std::make_shared(); managed_tf_buffer_->transformPointcloud(output_frame_, *cloud, *transformed_cloud_ptr); - topic_to_original_stamp_map[topic] = rclcpp::Time(cloud->header.stamp).seconds(); + concatenate_cloud_result.topic_to_original_stamp_map[topic] = + rclcpp::Time(cloud->header.stamp).seconds(); // compensate pointcloud std::shared_ptr transformed_delay_compensated_cloud_ptr; @@ -166,34 +160,47 @@ CombineCloudHandler::combinePointClouds( } // Check if concatenate_cloud_ptr is nullptr, if so initialize it - if (concatenate_cloud_ptr == nullptr) { + if (concatenate_cloud_result.concatenate_cloud_ptr == nullptr) { // Initialize concatenate_cloud_ptr without copying the data - concatenate_cloud_ptr = std::make_shared(); - concatenate_cloud_ptr->header = transformed_delay_compensated_cloud_ptr->header; - concatenate_cloud_ptr->height = transformed_delay_compensated_cloud_ptr->height; - concatenate_cloud_ptr->width = 0; // Will be updated with total points - concatenate_cloud_ptr->is_dense = transformed_delay_compensated_cloud_ptr->is_dense; - concatenate_cloud_ptr->is_bigendian = transformed_delay_compensated_cloud_ptr->is_bigendian; - concatenate_cloud_ptr->fields = transformed_delay_compensated_cloud_ptr->fields; - concatenate_cloud_ptr->point_step = transformed_delay_compensated_cloud_ptr->point_step; - concatenate_cloud_ptr->row_step = 0; // Will be updated after concatenation - concatenate_cloud_ptr->data.clear(); + concatenate_cloud_result.concatenate_cloud_ptr = + std::make_shared(); + concatenate_cloud_result.concatenate_cloud_ptr->header = + transformed_delay_compensated_cloud_ptr->header; + concatenate_cloud_result.concatenate_cloud_ptr->height = + transformed_delay_compensated_cloud_ptr->height; + concatenate_cloud_result.concatenate_cloud_ptr->width = + 0; // Will be updated with total points + concatenate_cloud_result.concatenate_cloud_ptr->is_dense = + transformed_delay_compensated_cloud_ptr->is_dense; + concatenate_cloud_result.concatenate_cloud_ptr->is_bigendian = + transformed_delay_compensated_cloud_ptr->is_bigendian; + concatenate_cloud_result.concatenate_cloud_ptr->fields = + transformed_delay_compensated_cloud_ptr->fields; + concatenate_cloud_result.concatenate_cloud_ptr->point_step = + transformed_delay_compensated_cloud_ptr->point_step; + concatenate_cloud_result.concatenate_cloud_ptr->row_step = + 0; // Will be updated after concatenation + concatenate_cloud_result.concatenate_cloud_ptr->data.clear(); // Reserve space for the data (assume max points you expect to concatenate) auto num_of_points = transformed_delay_compensated_cloud_ptr->width * transformed_delay_compensated_cloud_ptr->height; - concatenate_cloud_ptr->data.reserve(num_of_points * concatenate_cloud_ptr->point_step); + concatenate_cloud_result.concatenate_cloud_ptr->data.reserve( + num_of_points * concatenate_cloud_result.concatenate_cloud_ptr->point_step); } // Concatenate the current pointcloud to the concatenated cloud pcl::concatenatePointCloud( - *concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concatenate_cloud_ptr); + *concatenate_cloud_result.concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, + *concatenate_cloud_result.concatenate_cloud_ptr); // Update width and row_step to reflect the new size - concatenate_cloud_ptr->width = - concatenate_cloud_ptr->data.size() / concatenate_cloud_ptr->point_step; - concatenate_cloud_ptr->row_step = - concatenate_cloud_ptr->width * concatenate_cloud_ptr->point_step; + concatenate_cloud_result.concatenate_cloud_ptr->width = + concatenate_cloud_result.concatenate_cloud_ptr->data.size() / + concatenate_cloud_result.concatenate_cloud_ptr->point_step; + concatenate_cloud_result.concatenate_cloud_ptr->row_step = + concatenate_cloud_result.concatenate_cloud_ptr->width * + concatenate_cloud_result.concatenate_cloud_ptr->point_step; // convert to original sensor frame if necessary bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); @@ -205,17 +212,18 @@ CombineCloudHandler::combinePointClouds( *transformed_cloud_ptr_in_sensor_frame); transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id; - topic_to_transformed_cloud_map[topic] = transformed_cloud_ptr_in_sensor_frame; + concatenate_cloud_result.topic_to_transformed_cloud_map[topic] = + transformed_cloud_ptr_in_sensor_frame; } else { transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp; transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_; - topic_to_transformed_cloud_map[topic] = transformed_delay_compensated_cloud_ptr; + concatenate_cloud_result.topic_to_transformed_cloud_map[topic] = + transformed_delay_compensated_cloud_ptr; } } - concatenate_cloud_ptr->header.stamp = oldest_stamp; + concatenate_cloud_result.concatenate_cloud_ptr->header.stamp = oldest_stamp; - return std::make_tuple( - concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map); + return concatenate_cloud_result; } Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 8f141cfe16b36..9f4e74217c124 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -272,19 +272,16 @@ void PointCloudConcatenateDataSynchronizerComponent::odom_callback( } void PointCloudConcatenateDataSynchronizerComponent::publishClouds( - sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr, - std::unordered_map & - topic_to_transformed_cloud_map, - std::unordered_map & topic_to_original_stamp_map, - double reference_timestamp_min, double reference_timestamp_max) + ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, + double reference_timestamp_max) { // should never come to this state. - if (concatenate_cloud_ptr == nullptr) { + if (concatenated_cloud_result.concatenate_cloud_ptr == nullptr) { RCLCPP_ERROR(this->get_logger(), "Concatenate cloud is a nullptr."); return; } current_concatenate_cloud_timestamp_ = - rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds(); + rclcpp::Time(concatenated_cloud_result.concatenate_cloud_ptr->header.stamp).seconds(); if ( current_concatenate_cloud_timestamp_ < latest_concatenate_cloud_timestamp_ && @@ -293,16 +290,18 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( } else { publish_pointcloud_ = true; latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; - auto concatenate_pointcloud_output = - std::make_unique(*concatenate_cloud_ptr); + auto concatenate_pointcloud_output = std::make_unique( + *concatenated_cloud_result.concatenate_cloud_ptr); concatenated_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); // publish transformed raw pointclouds if (params_.publish_synchronized_pointcloud) { for (auto topic : params_.input_topics) { - if (topic_to_transformed_cloud_map.find(topic) != topic_to_transformed_cloud_map.end()) { - auto transformed_cloud_output = - std::make_unique(*topic_to_transformed_cloud_map[topic]); + if ( + concatenated_cloud_result.topic_to_transformed_cloud_map.find(topic) != + concatenated_cloud_result.topic_to_transformed_cloud_map.end()) { + auto transformed_cloud_output = std::make_unique( + *concatenated_cloud_result.topic_to_transformed_cloud_map[topic]); topic_to_transformed_cloud_publisher_map_[topic]->publish( std::move(transformed_cloud_output)); } else { @@ -316,7 +315,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( diagnostic_reference_timestamp_min_ = reference_timestamp_min; diagnostic_reference_timestamp_max_ = reference_timestamp_max; - diagnostic_topic_to_original_stamp_map_ = topic_to_original_stamp_map; + diagnostic_topic_to_original_stamp_map_ = concatenated_cloud_result.topic_to_original_stamp_map; diagnostic_updater_.force_update(); // add processing time for debug @@ -328,7 +327,8 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - for (const auto & [topic, transformed_cloud] : topic_to_transformed_cloud_map) { + for (const auto & [topic, transformed_cloud] : + concatenated_cloud_result.topic_to_transformed_cloud_map) { if (transformed_cloud != nullptr) { const auto pipeline_latency_ms = std::chrono::duration( From c1a4001b74a9165b7e2fc9a3f54d3d4bfc8f3974 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 16:56:48 +0900 Subject: [PATCH 57/90] chore: use reference instead of a pointer to conveys node Signed-off-by: vividf --- .../concatenate_data/combine_cloud_handler.hpp | 4 ++-- .../src/concatenate_data/combine_cloud_handler.cpp | 8 ++++---- .../concatenate_data/concatenate_and_time_sync_node.cpp | 2 +- .../test/test_concatenate_node_unit.cpp | 5 +++-- 4 files changed, 10 insertions(+), 9 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 60fbeb4ba6c83..ba00981d0423b 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -59,7 +59,7 @@ struct ConcatenatedCloudResult class CombineCloudHandler { private: - rclcpp::Node * node_; + rclcpp::Node & node_; std::vector input_topics_; std::string output_frame_; @@ -87,7 +87,7 @@ class CombineCloudHandler public: CombineCloudHandler( - rclcpp::Node * node, std::vector input_topics, std::string output_frame, + rclcpp::Node & node, std::vector input_topics, std::string output_frame, 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); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 3bf4668051858..9d1ea74e3b3e8 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -29,7 +29,7 @@ namespace autoware::pointcloud_preprocessor { CombineCloudHandler::CombineCloudHandler( - rclcpp::Node * node, std::vector input_topics, std::string output_frame, + rclcpp::Node & node, std::vector input_topics, std::string output_frame, bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only) : node_(node), @@ -38,7 +38,7 @@ CombineCloudHandler::CombineCloudHandler( is_motion_compensated_(is_motion_compensated), keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud), managed_tf_buffer_( - std::make_unique(node_, has_static_tf_only)) + std::make_unique(&node_, has_static_tf_only)) { } @@ -232,7 +232,7 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( // return identity if no twist is available if (twist_queue_.empty()) { RCLCPP_WARN_STREAM_THROTTLE( - node_->get_logger(), *node_->get_clock(), std::chrono::milliseconds(10000).count(), + node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud " "untransformed."); return Eigen::Matrix4f::Identity(); @@ -265,7 +265,7 @@ Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( if (std::fabs(dt) > 0.1) { RCLCPP_WARN_STREAM_THROTTLE( - node_->get_logger(), *node_->get_clock(), std::chrono::milliseconds(10000).count(), + node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), "Time difference is too large. Cloud not interpolate. Please confirm twist topic and " "timestamp"); break; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 9f4e74217c124..c9f4ee0cf2347 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -153,7 +153,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Combine cloud handler combine_cloud_handler_ = std::make_shared( - this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, + *this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, params_.keep_input_frame_in_synchronized_pointcloud, params_.has_static_tf_only); // Diagnostic Updater diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index aca5156689236..b36ea771123ae 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -60,8 +60,9 @@ class ConcatenateCloudTest : public ::testing::Test node_options); combine_cloud_handler_ = std::make_shared( - concatenate_node_.get(), std::vector{"lidar_top", "lidar_left", "lidar_right"}, - "base_link", true, true, false); + *concatenate_node_.get(), + std::vector{"lidar_top", "lidar_left", "lidar_right"}, "base_link", true, true, + false); collector_ = std::make_shared( std::dynamic_pointer_cast< From 7ebd33277b51d4fca6fb7117d568f04f6bc628bb Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 26 Sep 2024 17:13:30 +0900 Subject: [PATCH 58/90] chore: fix camel to snake case Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 16 ++++--- .../combine_cloud_handler.hpp | 12 ++--- .../concatenate_and_time_sync_node.hpp | 8 ++-- .../src/concatenate_data/cloud_collector.cpp | 24 +++++----- .../combine_cloud_handler.cpp | 19 ++++---- .../concatenate_and_time_sync_node.cpp | 35 +++++++------- .../test/test_concatenate_node_unit.cpp | 46 +++++++++---------- 7 files changed, 81 insertions(+), 79 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 759318f0a8fcb..16d85d645259a 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -36,16 +36,18 @@ class CloudCollector std::list> & collectors, std::shared_ptr combine_cloud_handler, int num_of_clouds, double time); - void setReferenceTimeStamp(double timestamp, double noise_window); - std::tuple getReferenceTimeStampBoundary(); - void processCloud(const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); - void concatenateCallback(); + void set_reference_timestamp(double timestamp, double noise_window); + std::tuple get_reference_timestamp_boundary(); + void process_pointcloud( + const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); + void concatenate_callback(); - ConcatenatedCloudResult concatenateClouds( + ConcatenatedCloudResult concatenate_pointclouds( std::unordered_map topic_to_cloud_map); - void deleteCollector(); + void delete_collector(); - std::unordered_map getTopicToCloudMap(); + std::unordered_map + get_topic_to_cloud_map(); private: std::shared_ptr ros2_parent_node_; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index ba00981d0423b..7de66d42026a0 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -79,7 +79,7 @@ class CombineCloudHandler } }; - void correctPointCloudMotion( + void correct_pointcloud_motion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, std::unordered_map & transform_memo, @@ -90,16 +90,16 @@ class CombineCloudHandler rclcpp::Node & node, std::vector input_topics, std::string output_frame, 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); + void process_twist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input); + void process_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input); - ConcatenatedCloudResult combinePointClouds( + ConcatenatedCloudResult combine_pointclouds( std::unordered_map & topic_to_cloud_map); - Eigen::Matrix4f computeTransformToAdjustForOldTimestamp( + Eigen::Matrix4f compute_transform_to_adjust_for_old_timestamp( const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); - std::deque getTwistQueue(); + std::deque get_twist_queue(); }; } // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 2954315eebdf6..4bbfa0885f005 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -118,11 +118,11 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input); void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input); - std::string formatTimestamp(double timestamp); - void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); - std::string replaceSyncTopicNamePostfix( + std::string format_timestamp(double timestamp); + void check_concat_status(diagnostic_updater::DiagnosticStatusWrapper & stat); + std::string replace_sync_topic_name_postfix( const std::string & original_topic_name, const std::string & postfix); - void convertToXYZIRCCloud( + void convert_to_xyzirc_cloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); }; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index ef3311c6f118a..e3160018e81c0 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -39,21 +39,21 @@ CloudCollector::CloudCollector( timer_ = rclcpp::create_timer( ros2_parent_node_, ros2_parent_node_->get_clock(), period_ns, - std::bind(&CloudCollector::concatenateCallback, this)); + std::bind(&CloudCollector::concatenate_callback, this)); } -void CloudCollector::setReferenceTimeStamp(double timestamp, double noise_window) +void CloudCollector::set_reference_timestamp(double timestamp, double noise_window) { reference_timestamp_max_ = timestamp + noise_window; reference_timestamp_min_ = timestamp - noise_window; } -std::tuple CloudCollector::getReferenceTimeStampBoundary() +std::tuple CloudCollector::get_reference_timestamp_boundary() { return std::make_tuple(reference_timestamp_min_, reference_timestamp_max_); } -void CloudCollector::processCloud( +void CloudCollector::process_pointcloud( const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) { // Check if the map already contains an entry for the same topic. This shouldn't happen if the @@ -67,11 +67,11 @@ void CloudCollector::processCloud( } topic_to_cloud_map_[topic_name] = cloud; if (topic_to_cloud_map_.size() == num_of_clouds_) { - concatenateCallback(); + concatenate_callback(); } } -void CloudCollector::concatenateCallback() +void CloudCollector::concatenate_callback() { // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the // pointclouds in the collector. @@ -79,19 +79,19 @@ void CloudCollector::concatenateCallback() // lock for protecting collector list and concatenated pointcloud std::lock_guard lock(mutex_); - auto concatenated_cloud_result = concatenateClouds(topic_to_cloud_map_); + auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); ros2_parent_node_->publishClouds( concatenated_cloud_result, reference_timestamp_min_, reference_timestamp_max_); - deleteCollector(); + delete_collector(); } -ConcatenatedCloudResult CloudCollector::concatenateClouds( +ConcatenatedCloudResult CloudCollector::concatenate_pointclouds( std::unordered_map topic_to_cloud_map) { - return combine_cloud_handler_->combinePointClouds(topic_to_cloud_map); + return combine_cloud_handler_->combine_pointclouds(topic_to_cloud_map); } -void CloudCollector::deleteCollector() +void CloudCollector::delete_collector() { auto it = std::find_if( collectors_.begin(), collectors_.end(), @@ -102,7 +102,7 @@ void CloudCollector::deleteCollector() } std::unordered_map -CloudCollector::getTopicToCloudMap() +CloudCollector::get_topic_to_cloud_map() { return topic_to_cloud_map_; } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 9d1ea74e3b3e8..f975edc12064b 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -42,8 +42,7 @@ CombineCloudHandler::CombineCloudHandler( { } -// TODO(vivid): change this to process_twist_message -void CombineCloudHandler::processTwist( +void CombineCloudHandler::process_twist( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg) { geometry_msgs::msg::TwistStamped msg; @@ -70,8 +69,7 @@ void CombineCloudHandler::processTwist( twist_queue_.push_back(msg); } -// TODO(vivid): change this to process_odometry_message -void CombineCloudHandler::processOdometry( +void CombineCloudHandler::process_odometry( const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_msg) { geometry_msgs::msg::TwistStamped msg; @@ -98,12 +96,12 @@ void CombineCloudHandler::processOdometry( twist_queue_.push_back(msg); } -std::deque CombineCloudHandler::getTwistQueue() +std::deque CombineCloudHandler::get_twist_queue() { return twist_queue_; } -void CombineCloudHandler::correctPointCloudMotion( +void CombineCloudHandler::correct_pointcloud_motion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, std::unordered_map & transform_memo, @@ -118,7 +116,8 @@ void CombineCloudHandler::correctPointCloudMotion( if (transform_memo.find(stamp) != transform_memo.end()) { new_to_old_transform = transform_memo[stamp]; } else { - new_to_old_transform = computeTransformToAdjustForOldTimestamp(stamp, current_cloud_stamp); + new_to_old_transform = + compute_transform_to_adjust_for_old_timestamp(stamp, current_cloud_stamp); transform_memo[stamp] = new_to_old_transform; } adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform; @@ -128,7 +127,7 @@ void CombineCloudHandler::correctPointCloudMotion( adjust_to_old_data_transform, *transformed_cloud_ptr, *transformed_delay_compensated_cloud_ptr); } -ConcatenatedCloudResult CombineCloudHandler::combinePointClouds( +ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( std::unordered_map & topic_to_cloud_map) { ConcatenatedCloudResult concatenate_cloud_result; @@ -153,7 +152,7 @@ ConcatenatedCloudResult CombineCloudHandler::combinePointClouds( std::shared_ptr transformed_delay_compensated_cloud_ptr; if (is_motion_compensated_) { transformed_delay_compensated_cloud_ptr = std::make_shared(); - correctPointCloudMotion( + correct_pointcloud_motion( transformed_cloud_ptr, pc_stamps, transform_memo, transformed_delay_compensated_cloud_ptr); } else { transformed_delay_compensated_cloud_ptr = transformed_cloud_ptr; @@ -226,7 +225,7 @@ ConcatenatedCloudResult CombineCloudHandler::combinePointClouds( return concatenate_cloud_result; } -Eigen::Matrix4f CombineCloudHandler::computeTransformToAdjustForOldTimestamp( +Eigen::Matrix4f CombineCloudHandler::compute_transform_to_adjust_for_old_timestamp( const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) { // return identity if no twist is available diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index c9f4ee0cf2347..404378b564d25 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -101,7 +101,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro if (params_.publish_synchronized_pointcloud) { for (auto & topic : params_.input_topics) { std::string new_topic = - replaceSyncTopicNamePostfix(topic, params_.synchronized_pointcloud_postfix); + replace_sync_topic_name_postfix(topic, params_.synchronized_pointcloud_postfix); auto publisher = this->create_publisher( new_topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); topic_to_transformed_cloud_publisher_map_.insert({topic, publisher}); @@ -159,10 +159,10 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Diagnostic Updater diagnostic_updater_.setHardwareID("concatenate_data_checker"); diagnostic_updater_.add( - "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus); + "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::check_concat_status); } -std::string PointCloudConcatenateDataSynchronizerComponent::replaceSyncTopicNamePostfix( +std::string PointCloudConcatenateDataSynchronizerComponent::replace_sync_topic_name_postfix( const std::string & original_topic_name, const std::string & postfix) { std::string replaced_topic_name; @@ -217,7 +217,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( return; } else { // convert to XYZIRC pointcloud if pointcloud is not empty - convertToXYZIRCCloud(input, xyzirc_input_ptr); + convert_to_xyzirc_cloud(input, xyzirc_input_ptr); } // protect cloud collectors list @@ -229,7 +229,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( if (!cloud_collectors_.empty()) { for (const auto & cloud_collector : cloud_collectors_) { auto [reference_timestamp_min, reference_timestamp_max] = - cloud_collector->getReferenceTimeStampBoundary(); + cloud_collector->get_reference_timestamp_boundary(); if ( rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] < @@ -237,7 +237,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] > reference_timestamp_min - topic_to_noise_window_map_[topic_name]) { cloud_collectors_lock.unlock(); - cloud_collector->processCloud(topic_name, input_ptr); + cloud_collector->process_pointcloud(topic_name, input_ptr); collector_found = true; break; } @@ -252,23 +252,23 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( cloud_collectors_.push_back(new_cloud_collector); cloud_collectors_lock.unlock(); - new_cloud_collector->setReferenceTimeStamp( + new_cloud_collector->set_reference_timestamp( rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name], topic_to_noise_window_map_[topic_name]); - new_cloud_collector->processCloud(topic_name, input_ptr); + new_cloud_collector->process_pointcloud(topic_name, input_ptr); } } void PointCloudConcatenateDataSynchronizerComponent::twist_callback( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input) { - combine_cloud_handler_->processTwist(input); + combine_cloud_handler_->process_twist(input); } void PointCloudConcatenateDataSynchronizerComponent::odom_callback( const nav_msgs::msg::Odometry::ConstSharedPtr input) { - combine_cloud_handler_->processOdometry(input); + combine_cloud_handler_->process_odometry(input); } void PointCloudConcatenateDataSynchronizerComponent::publishClouds( @@ -342,7 +342,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( } } -void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( +void PointCloudConcatenateDataSynchronizerComponent::convert_to_xyzirc_cloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) { @@ -397,20 +397,21 @@ void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( } } -std::string PointCloudConcatenateDataSynchronizerComponent::formatTimestamp(double timestamp) +std::string PointCloudConcatenateDataSynchronizerComponent::format_timestamp(double timestamp) { std::ostringstream oss; oss << std::fixed << std::setprecision(9) << timestamp; return oss.str(); } -void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( +void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( diagnostic_updater::DiagnosticStatusWrapper & stat) { if (publish_pointcloud_ || drop_previous_but_late_pointcloud_) { - stat.add("concatenated cloud timestamp", formatTimestamp(current_concatenate_cloud_timestamp_)); - stat.add("reference timestamp min", formatTimestamp(diagnostic_reference_timestamp_min_)); - stat.add("reference timestamp max", formatTimestamp(diagnostic_reference_timestamp_max_)); + stat.add( + "concatenated cloud timestamp", format_timestamp(current_concatenate_cloud_timestamp_)); + stat.add("reference timestamp min", format_timestamp(diagnostic_reference_timestamp_min_)); + stat.add("reference timestamp max", format_timestamp(diagnostic_reference_timestamp_max_)); bool topic_miss = false; @@ -422,7 +423,7 @@ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( diagnostic_topic_to_original_stamp_map_.end()) { cloud_status = 1; stat.add( - topic + " timestamp", formatTimestamp(diagnostic_topic_to_original_stamp_map_[topic])); + topic + " timestamp", format_timestamp(diagnostic_topic_to_original_stamp_map_[topic])); } else { topic_miss = true; cloud_status = 0; diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index b36ea771123ae..9197abd6bf6d1 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -189,11 +189,11 @@ TEST_F(ConcatenateCloudTest, TestProcessTwist) twist_msg->twist.twist.linear.x = 1.0; twist_msg->twist.twist.angular.z = 0.1; - combine_cloud_handler_->processTwist(twist_msg); + combine_cloud_handler_->process_twist(twist_msg); - ASSERT_FALSE(combine_cloud_handler_->getTwistQueue().empty()); - EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.linear.x, 1.0); - EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.angular.z, 0.1); + ASSERT_FALSE(combine_cloud_handler_->get_twist_queue().empty()); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.angular.z, 0.1); } TEST_F(ConcatenateCloudTest, TestProcessOdometry) @@ -203,11 +203,11 @@ TEST_F(ConcatenateCloudTest, TestProcessOdometry) odom_msg->twist.twist.linear.x = 1.0; odom_msg->twist.twist.angular.z = 0.1; - combine_cloud_handler_->processOdometry(odom_msg); + combine_cloud_handler_->process_odometry(odom_msg); - ASSERT_FALSE(combine_cloud_handler_->getTwistQueue().empty()); - EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.linear.x, 1.0); - EXPECT_EQ(combine_cloud_handler_->getTwistQueue().front().twist.angular.z, 0.1); + ASSERT_FALSE(combine_cloud_handler_->get_twist_queue().empty()); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.angular.z, 0.1); } TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) @@ -220,15 +220,15 @@ TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) twist_msg1->header.stamp = rclcpp::Time(9, 130'000'000, RCL_ROS_TIME); twist_msg1->twist.twist.linear.x = 1.0; twist_msg1->twist.twist.angular.z = 0.1; - combine_cloud_handler_->processTwist(twist_msg1); + combine_cloud_handler_->process_twist(twist_msg1); auto twist_msg2 = std::make_shared(); twist_msg2->header.stamp = rclcpp::Time(9, 160'000'000, RCL_ROS_TIME); twist_msg2->twist.twist.linear.x = 1.0; twist_msg2->twist.twist.angular.z = 0.1; - combine_cloud_handler_->processTwist(twist_msg2); + combine_cloud_handler_->process_twist(twist_msg2); - Eigen::Matrix4f transform = combine_cloud_handler_->computeTransformToAdjustForOldTimestamp( + Eigen::Matrix4f transform = combine_cloud_handler_->compute_transform_to_adjust_for_old_timestamp( pointcloud_stamp1, pointcloud_stamp2); // translation @@ -254,15 +254,15 @@ TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) twist_msg3->header.stamp = rclcpp::Time(11, 130'000'000, RCL_ROS_TIME); twist_msg3->twist.twist.linear.x = 1.0; twist_msg3->twist.twist.angular.z = 0.1; - combine_cloud_handler_->processTwist(twist_msg3); + combine_cloud_handler_->process_twist(twist_msg3); auto twist_msg4 = std::make_shared(); twist_msg4->header.stamp = rclcpp::Time(11, 160'000'000, RCL_ROS_TIME); twist_msg4->twist.twist.linear.x = 1.0; twist_msg4->twist.twist.angular.z = 0.1; - combine_cloud_handler_->processTwist(twist_msg4); + combine_cloud_handler_->process_twist(twist_msg4); - transform = combine_cloud_handler_->computeTransformToAdjustForOldTimestamp( + transform = combine_cloud_handler_->compute_transform_to_adjust_for_old_timestamp( pointcloud_stamp3, pointcloud_stamp4); // translation @@ -290,8 +290,8 @@ TEST_F(ConcatenateCloudTest, TestSetAndGetReferenceTimeStampBoundary) { double reference_timestamp = 10.0; double noise_window = 0.1; - collector_->setReferenceTimeStamp(reference_timestamp, noise_window); - auto [min, max] = collector_->getReferenceTimeStampBoundary(); + collector_->set_reference_timestamp(reference_timestamp, noise_window); + auto [min, max] = collector_->get_reference_timestamp_boundary(); EXPECT_DOUBLE_EQ(min, 9.9); EXPECT_DOUBLE_EQ(max, 10.1); } @@ -321,7 +321,7 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) topic_to_cloud_map["lidar_right"] = right_pointcloud_ptr; auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = - collector_->concatenateClouds(topic_to_cloud_map); + collector_->concatenate_pointclouds(topic_to_cloud_map); // test output concatenate cloud // No input twist, so it will not do the motion compensation @@ -444,7 +444,7 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) TEST_F(ConcatenateCloudTest, TestDeleteCollector) { - collector_->deleteCollector(); + collector_->delete_collector(); EXPECT_TRUE(collectors_.empty()); } @@ -455,9 +455,9 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) generatePointCloudMsg(true, false, "lidar_top", timestamp); sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = std::make_shared(top_pointcloud); - collector_->processCloud("lidar_top", top_pointcloud_ptr); + collector_->process_pointcloud("lidar_top", top_pointcloud_ptr); - auto topic_to_cloud_map = collector_->getTopicToCloudMap(); + auto topic_to_cloud_map = collector_->get_topic_to_cloud_map(); EXPECT_EQ(topic_to_cloud_map["lidar_top"], top_pointcloud_ptr); EXPECT_FALSE(collectors_.empty()); @@ -488,9 +488,9 @@ TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) sensor_msgs::msg::PointCloud2::SharedPtr right_pointcloud_ptr = std::make_shared(right_pointcloud); - collector_->processCloud("lidar_top", top_pointcloud_ptr); - collector_->processCloud("lidar_left", left_pointcloud_ptr); - collector_->processCloud("lidar_right", right_pointcloud_ptr); + collector_->process_pointcloud("lidar_top", top_pointcloud_ptr); + collector_->process_pointcloud("lidar_left", left_pointcloud_ptr); + collector_->process_pointcloud("lidar_right", right_pointcloud_ptr); EXPECT_TRUE(collectors_.empty()); } From 52ed5ed0b19bad40a86a1405cc8db1d35b012567 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 27 Sep 2024 21:49:48 +0900 Subject: [PATCH 59/90] chore: fix logic of publish synchronized pointcloud Signed-off-by: vividf --- .../combine_cloud_handler.hpp | 9 ++-- .../concatenate_and_time_sync_node.hpp | 1 - .../combine_cloud_handler.cpp | 47 +++++++++++-------- .../concatenate_and_time_sync_node.cpp | 33 ++++++------- .../test/test_concatenate_node_unit.cpp | 21 +++++---- 5 files changed, 61 insertions(+), 50 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 7de66d42026a0..082a37a223ed9 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -17,9 +17,9 @@ #include #include #include +#include #include #include -#include #include #include @@ -51,7 +51,7 @@ namespace autoware::pointcloud_preprocessor struct ConcatenatedCloudResult { sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr{nullptr}; - std::unordered_map + std::optional> topic_to_transformed_cloud_map; std::unordered_map topic_to_original_stamp_map; }; @@ -64,6 +64,7 @@ class CombineCloudHandler std::vector input_topics_; std::string output_frame_; bool is_motion_compensated_; + bool publish_synchronized_pointcloud_; bool keep_input_frame_in_synchronized_pointcloud_; std::unique_ptr managed_tf_buffer_{nullptr}; @@ -88,8 +89,8 @@ class CombineCloudHandler public: CombineCloudHandler( rclcpp::Node & node, std::vector input_topics, std::string output_frame, - bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud, - bool has_static_tf_only); + bool is_motion_compensated, bool publish_synchronized_pointcloud, + bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only); void process_twist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input); void process_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 4bbfa0885f005..4ca904e585e55 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -14,7 +14,6 @@ #pragma once -#include #include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index f975edc12064b..7ccee2e223b23 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -30,12 +30,13 @@ namespace autoware::pointcloud_preprocessor CombineCloudHandler::CombineCloudHandler( rclcpp::Node & node, std::vector input_topics, std::string output_frame, - bool is_motion_compensated, bool keep_input_frame_in_synchronized_pointcloud, - bool has_static_tf_only) + bool is_motion_compensated, bool publish_synchronized_pointcloud, + bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only) : node_(node), input_topics_(input_topics), output_frame_(output_frame), is_motion_compensated_(is_motion_compensated), + publish_synchronized_pointcloud_(publish_synchronized_pointcloud), keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud), managed_tf_buffer_( std::make_unique(&node_, has_static_tf_only)) @@ -201,23 +202,31 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( concatenate_cloud_result.concatenate_cloud_ptr->width * concatenate_cloud_result.concatenate_cloud_ptr->point_step; - // convert to original sensor frame if necessary - bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); - if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { - auto transformed_cloud_ptr_in_sensor_frame = - std::make_shared(); - managed_tf_buffer_->transformPointcloud( - cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, - *transformed_cloud_ptr_in_sensor_frame); - transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; - transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id; - concatenate_cloud_result.topic_to_transformed_cloud_map[topic] = - transformed_cloud_ptr_in_sensor_frame; - } else { - transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp; - transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_; - concatenate_cloud_result.topic_to_transformed_cloud_map[topic] = - transformed_delay_compensated_cloud_ptr; + if (publish_synchronized_pointcloud_) { + if (!concatenate_cloud_result.topic_to_transformed_cloud_map) { + // Initialize the map if it is not present + concatenate_cloud_result.topic_to_transformed_cloud_map = + std::unordered_map(); + } + // convert to original sensor frame if necessary + bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); + if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { + auto transformed_cloud_ptr_in_sensor_frame = + std::make_shared(); + managed_tf_buffer_->transformPointcloud( + cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, + *transformed_cloud_ptr_in_sensor_frame); + transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; + transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id; + + (*concatenate_cloud_result.topic_to_transformed_cloud_map)[topic] = + transformed_cloud_ptr_in_sensor_frame; + } else { + transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp; + transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_; + (*concatenate_cloud_result.topic_to_transformed_cloud_map)[topic] = + transformed_delay_compensated_cloud_ptr; + } } } concatenate_cloud_result.concatenate_cloud_ptr->header.stamp = oldest_stamp; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 404378b564d25..1d621740a3e39 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -154,7 +154,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Combine cloud handler combine_cloud_handler_ = std::make_shared( *this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, - params_.keep_input_frame_in_synchronized_pointcloud, params_.has_static_tf_only); + params_.publish_synchronized_pointcloud, params_.keep_input_frame_in_synchronized_pointcloud, + params_.has_static_tf_only); // Diagnostic Updater diagnostic_updater_.setHardwareID("concatenate_data_checker"); @@ -295,13 +296,16 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( concatenated_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); // publish transformed raw pointclouds - if (params_.publish_synchronized_pointcloud) { + if ( + params_.publish_synchronized_pointcloud && + concatenated_cloud_result.topic_to_transformed_cloud_map) { for (auto topic : params_.input_topics) { + // Get a reference to the internal map if ( - concatenated_cloud_result.topic_to_transformed_cloud_map.find(topic) != - concatenated_cloud_result.topic_to_transformed_cloud_map.end()) { + (*concatenated_cloud_result.topic_to_transformed_cloud_map).find(topic) != + (*concatenated_cloud_result.topic_to_transformed_cloud_map).end()) { auto transformed_cloud_output = std::make_unique( - *concatenated_cloud_result.topic_to_transformed_cloud_map[topic]); + *(*concatenated_cloud_result.topic_to_transformed_cloud_map).at(topic)); topic_to_transformed_cloud_publisher_map_[topic]->publish( std::move(transformed_cloud_output)); } else { @@ -327,17 +331,14 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - for (const auto & [topic, transformed_cloud] : - concatenated_cloud_result.topic_to_transformed_cloud_map) { - if (transformed_cloud != nullptr) { - const auto pipeline_latency_ms = - std::chrono::duration( - std::chrono::nanoseconds( - (this->get_clock()->now() - transformed_cloud->header.stamp).nanoseconds())) - .count(); - debug_publisher_->publish( - "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); - } + for (const auto & [topic, stamp] : concatenated_cloud_result.topic_to_original_stamp_map) { + const auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::duration_cast( + std::chrono::duration(this->get_clock()->now().nanoseconds() - stamp * 1e9))) + .count(); + debug_publisher_->publish( + "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); } } } diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 9197abd6bf6d1..d00b463b2f9eb 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -62,7 +62,7 @@ class ConcatenateCloudTest : public ::testing::Test std::make_shared( *concatenate_node_.get(), std::vector{"lidar_top", "lidar_left", "lidar_right"}, "base_link", true, true, - false); + true, false); collector_ = std::make_shared( std::dynamic_pointer_cast< @@ -370,12 +370,13 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) oss.clear(); oss.str(""); i = 0; + sensor_msgs::PointCloud2Iterator top_pc_iter_x( - *topic_to_transformed_cloud_map["lidar_top"], "x"); + *(topic_to_transformed_cloud_map.value().at("lidar_top")), "x"); sensor_msgs::PointCloud2Iterator top_pc_iter_y( - *topic_to_transformed_cloud_map["lidar_top"], "y"); + *(topic_to_transformed_cloud_map.value().at("lidar_top")), "y"); sensor_msgs::PointCloud2Iterator top_pc_iter_z( - *topic_to_transformed_cloud_map["lidar_top"], "z"); + *(topic_to_transformed_cloud_map.value().at("lidar_top")), "z"); for (; top_pc_iter_x != top_pc_iter_x.end(); ++top_pc_iter_x, ++top_pc_iter_y, ++top_pc_iter_z, ++i) { @@ -394,11 +395,11 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) oss.str(""); i = 0; sensor_msgs::PointCloud2Iterator left_pc_iter_x( - *topic_to_transformed_cloud_map["lidar_left"], "x"); + *(topic_to_transformed_cloud_map.value().at("lidar_left")), "x"); sensor_msgs::PointCloud2Iterator left_pc_iter_y( - *topic_to_transformed_cloud_map["lidar_left"], "y"); + *(topic_to_transformed_cloud_map.value().at("lidar_left")), "y"); sensor_msgs::PointCloud2Iterator left_pc_iter_z( - *topic_to_transformed_cloud_map["lidar_left"], "z"); + *(topic_to_transformed_cloud_map.value().at("lidar_left")), "z"); for (; left_pc_iter_x != left_pc_iter_x.end(); ++left_pc_iter_x, ++left_pc_iter_y, ++left_pc_iter_z, ++i) { @@ -417,11 +418,11 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) oss.str(""); i = 0; sensor_msgs::PointCloud2Iterator right_pc_iter_x( - *topic_to_transformed_cloud_map["lidar_right"], "x"); + *(topic_to_transformed_cloud_map.value().at("lidar_right")), "x"); sensor_msgs::PointCloud2Iterator right_pc_iter_y( - *topic_to_transformed_cloud_map["lidar_right"], "y"); + *(topic_to_transformed_cloud_map.value().at("lidar_right")), "y"); sensor_msgs::PointCloud2Iterator right_pc_iter_z( - *topic_to_transformed_cloud_map["lidar_right"], "z"); + *(topic_to_transformed_cloud_map.value().at("lidar_right")), "z"); for (; right_pc_iter_x != right_pc_iter_x.end(); ++right_pc_iter_x, ++right_pc_iter_y, ++right_pc_iter_z, ++i) { From b863d4939291bdf1878ccf29c17bc633a2b25c33 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 27 Sep 2024 22:03:25 +0900 Subject: [PATCH 60/90] chore: fix cpp check Signed-off-by: vividf --- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 1d621740a3e39..bba13a5834e3d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -354,17 +354,17 @@ void PointCloudConcatenateDataSynchronizerComponent::convert_to_xyzirc_cloud( output_modifier.reserve(input_ptr->width); bool has_valid_intensity = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; }); bool has_valid_return_type = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; }); bool has_valid_channel = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; }); From 92d69a4c6a4bb13c0ef2aa3d5e593fbda283c247 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 30 Sep 2024 10:55:26 +0900 Subject: [PATCH 61/90] chore: remove logging and throw error directly Signed-off-by: vividf --- .../concatenate_and_time_sync_node.cpp | 31 ++++++------------- 1 file changed, 9 insertions(+), 22 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index bba13a5834e3d..b924eafba8253 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -43,7 +43,6 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); - bool parameters_valid = true; // initialize parameters params_.has_static_tf_only = declare_parameter("has_static_tf_only"); params_.maximum_queue_size = declare_parameter("maximum_queue_size"); @@ -66,26 +65,21 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro declare_parameter>("lidar_timestamp_noise_window"); if (params_.input_topics.empty()) { - RCLCPP_ERROR(get_logger(), "Need a 'input_topics' parameter to be set before continuing!"); - parameters_valid = false; + throw std::runtime_error("Need a 'input_topics' parameter to be set before continuing."); } else if (params_.input_topics.size() == 1) { - RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue."); - parameters_valid = false; + throw std::runtime_error("Only one topic given. Need at least two topics to continue."); } if (params_.output_frame.empty()) { - RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); - parameters_valid = false; + throw std::runtime_error("Need an 'output_frame' parameter to be set before continuing."); } if (params_.lidar_timestamp_offsets.size() != params_.input_topics.size()) { - RCLCPP_ERROR( - get_logger(), "The number of topics does not match the number of timestamp offsets"); - parameters_valid = false; + throw std::runtime_error( + "The number of topics does not match the number of timestamp offsets."); } if (params_.lidar_timestamp_noise_window.size() != params_.input_topics.size()) { - RCLCPP_ERROR( - get_logger(), "The number of topics does not match the number of timestamp noise window"); - parameters_valid = false; + throw std::runtime_error( + "The number of topics does not match the number of timestamp noise window."); } for (size_t i = 0; i < params_.input_topics.size(); i++) { @@ -123,18 +117,11 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, std::placeholders::_1)); } else { - RCLCPP_ERROR_STREAM( - get_logger(), "input_twist_topic_type is invalid: " << params_.input_twist_topic_type); - parameters_valid = false; + throw std::runtime_error( + "input_twist_topic_type is invalid: " + params_.input_twist_topic_type); } } - if (!parameters_valid) { - throw std::runtime_error( - "Invalid parameter setting detected. Please review the provided parameter values and refer " - "to the error logs for detailed information."); - } - for (const std::string & topic : params_.input_topics) { std::function callback = std::bind( &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1, From edb061080dd50fc7c5f9d6aab69e0d432bff9685 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 30 Sep 2024 13:34:31 +0900 Subject: [PATCH 62/90] chore: fix clangd warnings Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 6 +-- .../combine_cloud_handler.hpp | 3 -- .../concatenate_and_time_sync_node.hpp | 11 +++-- .../src/concatenate_data/cloud_collector.cpp | 6 +-- .../concatenate_and_time_sync_node.cpp | 44 +++++++++---------- 5 files changed, 32 insertions(+), 38 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 16d85d645259a..7d7e9277b641c 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -32,7 +32,7 @@ class CloudCollector { public: CloudCollector( - std::shared_ptr ros2_parent_node, + std::shared_ptr && ros2_parent_node, std::list> & collectors, std::shared_ptr combine_cloud_handler, int num_of_clouds, double time); @@ -57,8 +57,8 @@ class CloudCollector std::unordered_map topic_to_cloud_map_; uint64_t num_of_clouds_; double timeout_sec_; - double reference_timestamp_min_; - double reference_timestamp_max_; + double reference_timestamp_min_{0.0}; + double reference_timestamp_max_{0.0}; std::mutex mutex_; }; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 082a37a223ed9..d8a363c63be21 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -16,15 +16,12 @@ #include #include -#include #include -#include #include #include #include // ROS includes -#include "autoware_point_types/types.hpp" #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 4ca904e585e55..f4d651aa3b0f1 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -17,7 +17,6 @@ #include #include #include -#include #include #include #include @@ -57,8 +56,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node { public: explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); - virtual ~PointCloudConcatenateDataSynchronizerComponent() {} - void publishClouds( + ~PointCloudConcatenateDataSynchronizerComponent() override = default; + void publish_clouds( ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, double reference_timestamp_max); @@ -96,7 +95,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unordered_map topic_to_noise_window_map_; // default postfix name for synchronized pointcloud - static constexpr const char * default_sync_topic_postfix_ = "_synchronized"; + static constexpr const char * default_sync_topic_postfix = "_synchronized"; // subscribers std::vector::SharedPtr> pointcloud_subs_; @@ -117,11 +116,11 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input); void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input); - std::string format_timestamp(double timestamp); + static std::string format_timestamp(double timestamp); void check_concat_status(diagnostic_updater::DiagnosticStatusWrapper & stat); std::string replace_sync_topic_name_postfix( const std::string & original_topic_name, const std::string & postfix); - void convert_to_xyzirc_cloud( + static void convert_to_xyzirc_cloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); }; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index e3160018e81c0..e25ad352f284c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -25,10 +25,10 @@ namespace autoware::pointcloud_preprocessor { CloudCollector::CloudCollector( - std::shared_ptr ros2_parent_node, + std::shared_ptr && ros2_parent_node, std::list> & collectors, std::shared_ptr combine_cloud_handler, int num_of_clouds, double timeout_sec) -: ros2_parent_node_(ros2_parent_node), +: ros2_parent_node_(std::move(ros2_parent_node)), collectors_(collectors), combine_cloud_handler_(combine_cloud_handler), num_of_clouds_(num_of_clouds), @@ -80,7 +80,7 @@ void CloudCollector::concatenate_callback() // lock for protecting collector list and concatenated pointcloud std::lock_guard lock(mutex_); auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); - ros2_parent_node_->publishClouds( + ros2_parent_node_->publish_clouds( concatenated_cloud_result, reference_timestamp_min_, reference_timestamp_max_); delete_collector(); } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index b924eafba8253..c22876b19c258 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -45,7 +45,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // initialize parameters params_.has_static_tf_only = declare_parameter("has_static_tf_only"); - params_.maximum_queue_size = declare_parameter("maximum_queue_size"); + params_.maximum_queue_size = static_cast(declare_parameter("maximum_queue_size")); params_.timeout_sec = declare_parameter("timeout_sec"); params_.is_motion_compensated = declare_parameter("is_motion_compensated"); params_.publish_synchronized_pointcloud = @@ -66,7 +66,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro if (params_.input_topics.empty()) { throw std::runtime_error("Need a 'input_topics' parameter to be set before continuing."); - } else if (params_.input_topics.size() == 1) { + } + if (params_.input_topics.size() == 1) { throw std::runtime_error("Only one topic given. Need at least two topics to continue."); } @@ -155,18 +156,18 @@ std::string PointCloudConcatenateDataSynchronizerComponent::replace_sync_topic_n { 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("/"); + 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; } + // 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( @@ -175,7 +176,7 @@ std::string PointCloudConcatenateDataSynchronizerComponent::replace_sync_topic_n << " 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_; + replaced_topic_name = original_topic_name + default_sync_topic_postfix; } return replaced_topic_name; } @@ -203,11 +204,11 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( RCLCPP_WARN_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); return; - } else { - // convert to XYZIRC pointcloud if pointcloud is not empty - convert_to_xyzirc_cloud(input, xyzirc_input_ptr); } + // convert to XYZIRC pointcloud if pointcloud is not empty + convert_to_xyzirc_cloud(input, xyzirc_input_ptr); + // protect cloud collectors list std::unique_lock cloud_collectors_lock(cloud_collectors_mutex_); @@ -259,7 +260,7 @@ void PointCloudConcatenateDataSynchronizerComponent::odom_callback( combine_cloud_handler_->process_odometry(input); } -void PointCloudConcatenateDataSynchronizerComponent::publishClouds( +void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, double reference_timestamp_max) { @@ -286,7 +287,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publishClouds( if ( params_.publish_synchronized_pointcloud && concatenated_cloud_result.topic_to_transformed_cloud_map) { - for (auto topic : params_.input_topics) { + for (const auto & topic : params_.input_topics) { // Get a reference to the internal map if ( (*concatenated_cloud_result.topic_to_transformed_cloud_map).find(topic) != @@ -403,36 +404,33 @@ void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( bool topic_miss = false; - int concatenate_status = 1; - for (auto topic : params_.input_topics) { - int cloud_status; // 1 for success, 0 for failure + int concatenated_cloud_status = 1; // 1 for success, 0 for failure + int cloud_status = 1; // for each lidar's pointcloud + for (const auto & topic : params_.input_topics) { if ( diagnostic_topic_to_original_stamp_map_.find(topic) != diagnostic_topic_to_original_stamp_map_.end()) { - cloud_status = 1; stat.add( topic + " timestamp", format_timestamp(diagnostic_topic_to_original_stamp_map_[topic])); } else { topic_miss = true; + concatenated_cloud_status = 0; cloud_status = 0; - concatenate_status = 0; } stat.add(topic, cloud_status); } - stat.add("concatenate status", concatenate_status); + stat.add("concatenate status", concatenated_cloud_status); + + int8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::string message = "Concatenated pointcloud is published and include all topics"; - int8_t level; - std::string message; if (topic_miss) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; message = "Concatenated pointcloud is published but miss some topics"; } else if (drop_previous_but_late_pointcloud_) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; message = "Concatenated pointcloud is not published as it is too late"; - } else { - level = diagnostic_msgs::msg::DiagnosticStatus::OK; - message = "Concatenated pointcloud is published and include all topics"; } stat.summary(level, message); From b6700a9963c6cc2806fcabd93a4c2f6708641fc6 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 30 Sep 2024 14:06:50 +0900 Subject: [PATCH 63/90] chore: fix json schema Signed-off-by: vividf --- ...concatenate_and_time_sync_node.schema.json | 24 +++++++++++++------ 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 37608d2900fe3..022e7f30f8d73 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -9,11 +9,13 @@ "maximum_queue_size": { "type": "integer", "default": "5", + "minimum": 1, "description": "Maximum size of the queue for the Keep Last policy in QoS history." }, "timeout_sec": { "type": "number", "default": "0.1", + "minimum": 0.001, "description": "Timer's timeout duration in seconds when collectors are created. Collectors will concatenate the point clouds when timeout_sec reaches zero." }, "is_motion_compensated": { @@ -43,36 +45,44 @@ }, "input_twist_topic_type": { "type": "string", + "enum": ["twist", "odom"], "default": "twist", "description": "Type of the input twist topic." }, "input_topics": { "type": "array", "items": { - "type": "string" + "type": "string", + "minLength": 1 }, - "default": [], + "default": ["cloud_topic1", "cloud_topic2", "cloud_topic3"], + "minItems": 2, "description": "List of input point cloud topics." }, "output_frame": { "type": "string", "default": "base_link", + "minLength": 1, "description": "Output frame." }, "lidar_timestamp_offsets": { "type": "array", "items": { - "type": "number" + "type": "number", + "minimum": 0.0 }, - "default": [], - "description": "List of LiDAR timestamp offsets in seconds. The offset values should be specified in the same order as the input_topics." + "default": [0.0, 0.0, 0.0], + "minItems": 2, + "description": "List of LiDAR timestamp offsets in seconds (relative to the earliest LiDAR timestamp). The offsets should be provided in the same order as the input topics." }, "lidar_timestamp_noise_window": { "type": "array", "items": { - "type": "number" + "type": "number", + "minimum": 0.0 }, - "default": [], + "default": [0.01, 0.01, 0.01], + "minItems": 2, "description": "List of LiDAR timestamp noise windows in seconds. The noise values should be specified in the same order as the input_topics." }, "has_static_tf_only": { From 130bcb87d6c697663a8bed2fd5de9f14290a39f9 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 30 Sep 2024 14:13:00 +0900 Subject: [PATCH 64/90] chore: fix clangd warning Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 2 +- .../src/concatenate_data/cloud_collector.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 7d7e9277b641c..b7a3cacc19325 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -34,7 +34,7 @@ class CloudCollector CloudCollector( std::shared_ptr && ros2_parent_node, std::list> & collectors, - std::shared_ptr combine_cloud_handler, int num_of_clouds, double time); + std::shared_ptr & combine_cloud_handler, int num_of_clouds, double time); void set_reference_timestamp(double timestamp, double noise_window); std::tuple get_reference_timestamp_boundary(); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index e25ad352f284c..b6f84889f704c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -27,7 +27,8 @@ namespace autoware::pointcloud_preprocessor CloudCollector::CloudCollector( std::shared_ptr && ros2_parent_node, std::list> & collectors, - std::shared_ptr combine_cloud_handler, int num_of_clouds, double timeout_sec) + std::shared_ptr & combine_cloud_handler, int num_of_clouds, + double timeout_sec) : ros2_parent_node_(std::move(ros2_parent_node)), collectors_(collectors), combine_cloud_handler_(combine_cloud_handler), From 31500f83abe8b482d06dc0c9dabd2cd0b4510a24 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 30 Sep 2024 14:32:58 +0900 Subject: [PATCH 65/90] chore: remove unused variable Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index f4d651aa3b0f1..3144a03a92fd1 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -88,7 +88,6 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unordered_map diagnostic_topic_to_original_stamp_map_; std::shared_ptr combine_cloud_handler_; - std::shared_ptr cloud_collector_; std::list> cloud_collectors_; std::mutex cloud_collectors_mutex_; std::unordered_map topic_to_offset_map_; From 000c890bf32853e2bbdf283ccf5020d52415ea10 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 1 Oct 2024 14:40:03 +0900 Subject: [PATCH 66/90] chore: fix launcher Signed-off-by: vividf --- .../launch/concatenate_and_time_sync_node.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml index aa9579305dfb8..f553c15f01210 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml @@ -5,7 +5,7 @@ - + From 55e0d242b6991006d79b0e303efb29cbdfe0de09 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 1 Oct 2024 19:37:35 +0900 Subject: [PATCH 67/90] chore: fix clangd warning Signed-off-by: vividf --- .../test/test_concatenate_node_component.py | 76 +++++++++---------- .../test/test_concatenate_node_unit.cpp | 36 ++++----- 2 files changed, 56 insertions(+), 56 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index 86b138d553af8..0aeced645de96 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -65,8 +65,8 @@ STANDARD_TOLERANCE = 1e-4 COARSE_TOLERANCE = TIMESTAMP_NOISE * 2 -global_seconds = 10 -global_nanoseconds = 100000000 +GLOBAL_SECONDS = 10 +GLOBAL_NANOSECONDS = 100000000 @pytest.mark.launch_test @@ -216,7 +216,7 @@ def generate_transform_msg( qw: float, ) -> TransformStamped: tf_msg = TransformStamped() - tf_msg.header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanoseconds).to_msg() + tf_msg.header.stamp = Time(seconds=GLOBAL_SECONDS, nanoseconds=GLOBAL_NANOSECONDS).to_msg() tf_msg.header.frame_id = parent_frame tf_msg.child_frame_id = child_frame tf_msg.transform.translation.x = x @@ -271,7 +271,7 @@ def generate_static_transform_msgs() -> List[TransformStamped]: def generate_twist_msg() -> TwistWithCovarianceStamped: twist_header = Header() - twist_header.stamp = Time(seconds=global_seconds, nanoseconds=global_nanoseconds).to_msg() + twist_header.stamp = Time(seconds=GLOBAL_SECONDS, nanoseconds=GLOBAL_NANOSECONDS).to_msg() twist_header.frame_id = "base_link" twist_msg = TwistWithCovarianceStamped() twist_msg.header = twist_header @@ -355,14 +355,14 @@ def test_1_normal_inputs(self): 2. The motion compensation of concatenation works well. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -414,7 +414,7 @@ def test_1_normal_inputs(self): "The concatenate pointcloud frame id is not base_link", ) - global_seconds += 1 + GLOBAL_SECONDS += 1 def test_2_normal_inputs_with_noise(self): """Test the normal situation when no pointcloud is delayed or dropped. Additionally, the pointcloud's timestamp is not ideal which has some noise. @@ -423,16 +423,16 @@ def test_2_normal_inputs_with_noise(self): 1. Concatenate works fine when pointclouds' timestamp has noise. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): noise = random.uniform(-10, 10) * MILLISECONDS - pointcloud_seconds = global_seconds + pointcloud_seconds = GLOBAL_SECONDS pointcloud_nanoseconds = ( - global_nanoseconds + frame_idx * MILLISECONDS * 40 + noise + GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 + noise ) # add 40 ms and noise (-10 to 10 ms) pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -485,14 +485,14 @@ def test_3_abnormal_null_pointcloud(self): 1. The concatenate node ignore empty pointcloud and concatenate the remain pointcloud. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -545,7 +545,7 @@ def test_3_abnormal_null_pointcloud(self): "The concatenation node have weird output", ) - global_seconds += 1 + GLOBAL_SECONDS += 1 def test_4_abnormal_null_pointcloud_and_drop(self): """Test the abnormal situation when a pointcloud is empty and other pointclouds are dropped. @@ -554,13 +554,13 @@ def test_4_abnormal_null_pointcloud_and_drop(self): 1. The concatenate node ignore empty pointcloud and do not publish any pointcloud. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -584,7 +584,7 @@ def test_4_abnormal_null_pointcloud_and_drop(self): "The number of concatenate pointcloud has different number as expected.", ) - global_seconds += 1 + GLOBAL_SECONDS += 1 def test_5_abnormal_multiple_pointcloud_drop(self): """Test the abnormal situation when multiple pointclouds were dropped (only one pointcloud arrive). @@ -593,13 +593,13 @@ def test_5_abnormal_multiple_pointcloud_drop(self): 1. The concatenate node concatenates the single pointcloud after the timeout. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -648,14 +648,14 @@ def test_6_abnormal_single_pointcloud_drop(self): 1. The concatenate node concatenate the remain pointcloud after the timeout. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -699,7 +699,7 @@ def test_6_abnormal_single_pointcloud_drop(self): "The concatenation node have weird output", ) - global_seconds += 1 + GLOBAL_SECONDS += 1 def test_7_abnormal_pointcloud_delay(self): """Test the abnormal situation when a pointcloud was delayed after the timeout. @@ -709,14 +709,14 @@ def test_7_abnormal_pointcloud_delay(self): 2. The concatenate node will publish the delayed pointcloud after the timeout. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -732,9 +732,9 @@ def test_7_abnormal_pointcloud_delay(self): time.sleep(TIMEOUT_SEC) # timeout threshold rclpy.spin_once(self.node, timeout_sec=0.1) - pointcloud_seconds = global_seconds + pointcloud_seconds = GLOBAL_SECONDS pointcloud_nanoseconds = ( - global_nanoseconds + (len(INPUT_LIDAR_TOPICS) - 1) * MILLISECONDS * 40 + GLOBAL_NANOSECONDS + (len(INPUT_LIDAR_TOPICS) - 1) * MILLISECONDS * 40 ) # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds @@ -797,7 +797,7 @@ def test_7_abnormal_pointcloud_delay(self): "The concatenation node have weird output", ) - global_seconds += 1 + GLOBAL_SECONDS += 1 def test_8_abnormal_pointcloud_drop_continue_normal(self): """Test the abnormal situation when a pointcloud was dropped. Afterward, next iteration of pointclouds comes normally. @@ -807,14 +807,14 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): 2. The concatenate node concatenate next iteration pointclouds when all of the pointcloud arrived. """ time.sleep(1) - global global_seconds + global GLOBAL_SECONDS twist_msg = generate_twist_msg() self.twist_publisher.publish(twist_msg) for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): - pointcloud_seconds = global_seconds - pointcloud_nanoseconds = global_nanoseconds + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms pointcloud_timestamp = Time( seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds ).to_msg() @@ -830,9 +830,9 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): time.sleep(TIMEOUT_SEC) rclpy.spin_once(self.node) - next_global_nanosecond = global_nanoseconds + 100 * MILLISECONDS + next_global_nanosecond = GLOBAL_NANOSECONDS + 100 * MILLISECONDS for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): - pointcloud_seconds = global_seconds + pointcloud_seconds = GLOBAL_SECONDS pointcloud_nanoseconds = ( next_global_nanosecond + frame_idx * MILLISECONDS * 40 ) # add 40 ms @@ -901,4 +901,4 @@ def test_8_abnormal_pointcloud_drop_continue_normal(self): "The concatenation node have weird output", ) - global_seconds += 1 + GLOBAL_SECONDS += 1 diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index d00b463b2f9eb..7f15599810e0d 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -60,9 +60,8 @@ class ConcatenateCloudTest : public ::testing::Test node_options); combine_cloud_handler_ = std::make_shared( - *concatenate_node_.get(), - std::vector{"lidar_top", "lidar_left", "lidar_right"}, "base_link", true, true, - true, false); + *concatenate_node_, std::vector{"lidar_top", "lidar_left", "lidar_right"}, + "base_link", true, true, true, false); collector_ = std::make_shared( std::dynamic_pointer_cast< @@ -74,7 +73,7 @@ class ConcatenateCloudTest : public ::testing::Test // Setup TF tf_broadcaster_ = std::make_shared(concatenate_node_); - tf_broadcaster_->sendTransform(generateStaticTransformMsg()); + tf_broadcaster_->sendTransform(generate_static_transform_msgs()); // Spin the node for a while to ensure transforms are published auto start = std::chrono::steady_clock::now(); @@ -85,7 +84,7 @@ class ConcatenateCloudTest : public ::testing::Test } } - geometry_msgs::msg::TransformStamped generateTransformMsg( + static geometry_msgs::msg::TransformStamped generate_transform_msg( const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, double qx, double qy, double qz, double qw) { @@ -104,8 +103,9 @@ class ConcatenateCloudTest : public ::testing::Test return tf_msg; } - sensor_msgs::msg::PointCloud2 generatePointCloudMsg( - bool generate_points, bool is_lidar_frame, std::string topic_name, rclcpp::Time stamp) + static sensor_msgs::msg::PointCloud2 generate_pointcloud_msg( + bool generate_points, bool is_lidar_frame, const std::string & topic_name, + const rclcpp::Time & stamp) { sensor_msgs::msg::PointCloud2 pointcloud_msg; pointcloud_msg.header.stamp = stamp; @@ -156,13 +156,13 @@ class ConcatenateCloudTest : public ::testing::Test return pointcloud_msg; } - std::vector generateStaticTransformMsg() + static std::vector generate_static_transform_msgs() { // generate defined transformations return { - generateTransformMsg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), - generateTransformMsg("base_link", "lidar_left", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; - generateTransformMsg("base_link", "lidar_right", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453); + generate_transform_msg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), + generate_transform_msg("base_link", "lidar_left", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; + generate_transform_msg("base_link", "lidar_right", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453); } std::shared_ptr @@ -302,11 +302,11 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = - generatePointCloudMsg(true, false, "lidar_top", top_timestamp); + generate_pointcloud_msg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = - generatePointCloudMsg(true, false, "lidar_left", left_timestamp); + generate_pointcloud_msg(true, false, "lidar_left", left_timestamp); sensor_msgs::msg::PointCloud2 right_pointcloud = - generatePointCloudMsg(true, false, "lidar_right", right_timestamp); + generate_pointcloud_msg(true, false, "lidar_right", right_timestamp); sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = std::make_shared(top_pointcloud); @@ -453,7 +453,7 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) { rclcpp::Time timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = - generatePointCloudMsg(true, false, "lidar_top", timestamp); + generate_pointcloud_msg(true, false, "lidar_top", timestamp); sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = std::make_shared(top_pointcloud); collector_->process_pointcloud("lidar_top", top_pointcloud_ptr); @@ -476,11 +476,11 @@ TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = - generatePointCloudMsg(true, false, "lidar_top", top_timestamp); + generate_pointcloud_msg(true, false, "lidar_top", top_timestamp); sensor_msgs::msg::PointCloud2 left_pointcloud = - generatePointCloudMsg(true, false, "lidar_left", left_timestamp); + generate_pointcloud_msg(true, false, "lidar_left", left_timestamp); sensor_msgs::msg::PointCloud2 right_pointcloud = - generatePointCloudMsg(true, false, "lidar_right", right_timestamp); + generate_pointcloud_msg(true, false, "lidar_right", right_timestamp); sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = std::make_shared(top_pointcloud); From 9199a3d41a06826231bcfc3b96592beddce7c68a Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 4 Oct 2024 20:27:43 +0900 Subject: [PATCH 68/90] chore: ensure thread safety Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 8 ++--- .../concatenate_and_time_sync_node.hpp | 3 ++ .../src/concatenate_data/cloud_collector.cpp | 16 ++-------- .../combine_cloud_handler.cpp | 4 +-- .../concatenate_and_time_sync_node.cpp | 30 ++++++++++++++++++- .../test/test_concatenate_node_unit.cpp | 19 +++++++----- 6 files changed, 48 insertions(+), 32 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index b7a3cacc19325..7b2b6503be097 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -16,7 +16,6 @@ #include "combine_cloud_handler.hpp" -#include #include #include #include @@ -28,12 +27,11 @@ namespace autoware::pointcloud_preprocessor class PointCloudConcatenateDataSynchronizerComponent; class CombineCloudHandler; -class CloudCollector +class CloudCollector { public: CloudCollector( std::shared_ptr && ros2_parent_node, - std::list> & collectors, std::shared_ptr & combine_cloud_handler, int num_of_clouds, double time); void set_reference_timestamp(double timestamp, double noise_window); @@ -44,14 +42,13 @@ class CloudCollector ConcatenatedCloudResult concatenate_pointclouds( std::unordered_map topic_to_cloud_map); - void delete_collector(); + //void delete_collector(); std::unordered_map get_topic_to_cloud_map(); private: std::shared_ptr ros2_parent_node_; - std::list> & collectors_; std::shared_ptr combine_cloud_handler_; rclcpp::TimerBase::SharedPtr timer_; std::unordered_map topic_to_cloud_map_; @@ -59,7 +56,6 @@ class CloudCollector double timeout_sec_; double reference_timestamp_min_{0.0}; double reference_timestamp_max_{0.0}; - std::mutex mutex_; }; } // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 3144a03a92fd1..a44878a23e2e9 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -60,6 +60,9 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node void publish_clouds( ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, double reference_timestamp_max); + void delete_collector(CloudCollector & cloud_collector); + std::list> get_cloud_collectors(); + void add_cloud_collector(const std::shared_ptr & collector); private: struct Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index b6f84889f704c..fabb7136f8256 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -26,11 +26,9 @@ namespace autoware::pointcloud_preprocessor CloudCollector::CloudCollector( std::shared_ptr && ros2_parent_node, - std::list> & collectors, std::shared_ptr & combine_cloud_handler, int num_of_clouds, double timeout_sec) : ros2_parent_node_(std::move(ros2_parent_node)), - collectors_(collectors), combine_cloud_handler_(combine_cloud_handler), num_of_clouds_(num_of_clouds), timeout_sec_(timeout_sec) @@ -78,12 +76,11 @@ void CloudCollector::concatenate_callback() // pointclouds in the collector. timer_->cancel(); - // lock for protecting collector list and concatenated pointcloud - std::lock_guard lock(mutex_); auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); + ros2_parent_node_->publish_clouds( concatenated_cloud_result, reference_timestamp_min_, reference_timestamp_max_); - delete_collector(); + ros2_parent_node_->delete_collector(*this); } ConcatenatedCloudResult CloudCollector::concatenate_pointclouds( @@ -92,15 +89,6 @@ ConcatenatedCloudResult CloudCollector::concatenate_pointclouds( return combine_cloud_handler_->combine_pointclouds(topic_to_cloud_map); } -void CloudCollector::delete_collector() -{ - auto it = std::find_if( - collectors_.begin(), collectors_.end(), - [this](const std::shared_ptr & collector) { return collector.get() == this; }); - if (it != collectors_.end()) { - collectors_.erase(it); - } -} std::unordered_map CloudCollector::get_topic_to_cloud_map() diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 7ccee2e223b23..9cdc7ad5d0b2f 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -21,8 +21,6 @@ #include #include #include -#include -#include #include namespace autoware::pointcloud_preprocessor @@ -135,7 +133,7 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( std::vector pc_stamps; for (const auto & [topic, cloud] : topic_to_cloud_map) { - pc_stamps.push_back(rclcpp::Time(cloud->header.stamp)); + pc_stamps.emplace_back(rclcpp::Time(cloud->header.stamp)); } std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); const auto oldest_stamp = pc_stamps.back(); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index c22876b19c258..0b757ca0bd4ff 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -237,7 +237,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( if (!collector_found) { auto new_cloud_collector = std::make_shared( std::dynamic_pointer_cast(shared_from_this()), - cloud_collectors_, combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec); + combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec); cloud_collectors_.push_back(new_cloud_collector); cloud_collectors_lock.unlock(); @@ -331,6 +331,23 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( } } +void PointCloudConcatenateDataSynchronizerComponent::delete_collector(CloudCollector & cloud_collector) { + // protect cloud collectors list + std::lock_guard cloud_collectors_lock(cloud_collectors_mutex_); + + // change this to something else + auto it = std::find_if( + cloud_collectors_.begin(), cloud_collectors_.end(), + [&cloud_collector](const std::shared_ptr & collector) { return collector.get() == &cloud_collector; }); + if (it != cloud_collectors_.end()) { + cloud_collectors_.erase(it); + } + else { + throw std::runtime_error("Try to delete a cloud_collector that is not in the cloud_collectors"); + } +} + + void PointCloudConcatenateDataSynchronizerComponent::convert_to_xyzirc_cloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) @@ -445,6 +462,17 @@ void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( } } +std::list> PointCloudConcatenateDataSynchronizerComponent::get_cloud_collectors() +{ + return cloud_collectors_; +} + +void PointCloudConcatenateDataSynchronizerComponent::add_cloud_collector(const std::shared_ptr & collector) +{ + cloud_collectors_.push_back(collector); +} + + } // namespace autoware::pointcloud_preprocessor #include diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 7f15599810e0d..d0fbfe87b543c 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -67,9 +67,8 @@ class ConcatenateCloudTest : public ::testing::Test std::dynamic_pointer_cast< autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( concatenate_node_->shared_from_this()), - collectors_, combine_cloud_handler_, number_of_pointcloud, timeout_sec); + combine_cloud_handler_, number_of_pointcloud, timeout_sec); - collectors_.push_back(collector_); // Setup TF tf_broadcaster_ = std::make_shared(concatenate_node_); @@ -167,7 +166,6 @@ class ConcatenateCloudTest : public ::testing::Test std::shared_ptr concatenate_node_; - std::list> collectors_; std::shared_ptr combine_cloud_handler_; std::shared_ptr collector_; std::shared_ptr tf_broadcaster_; @@ -445,12 +443,15 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) TEST_F(ConcatenateCloudTest, TestDeleteCollector) { - collector_->delete_collector(); - EXPECT_TRUE(collectors_.empty()); + concatenate_node_->add_cloud_collector(collector_); + concatenate_node_->delete_collector(*collector_); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); } TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) { + concatenate_node_->add_cloud_collector(collector_); + rclcpp::Time timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); sensor_msgs::msg::PointCloud2 top_pointcloud = generate_pointcloud_msg(true, false, "lidar_top", timestamp); @@ -460,18 +461,20 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) auto topic_to_cloud_map = collector_->get_topic_to_cloud_map(); EXPECT_EQ(topic_to_cloud_map["lidar_top"], top_pointcloud_ptr); - EXPECT_FALSE(collectors_.empty()); + EXPECT_FALSE(concatenate_node_->get_cloud_collectors().empty()); // Sleep for timeout seconds (200 ms) std::this_thread::sleep_for(std::chrono::milliseconds(200)); rclcpp::spin_some(concatenate_node_); // Collector should concatenate and publish the pointcloud, also delete itself. - EXPECT_TRUE(collectors_.empty()); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); } TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) { + concatenate_node_->add_cloud_collector(collector_); + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); @@ -493,7 +496,7 @@ TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) collector_->process_pointcloud("lidar_left", left_pointcloud_ptr); collector_->process_pointcloud("lidar_right", right_pointcloud_ptr); - EXPECT_TRUE(collectors_.empty()); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); } int main(int argc, char ** argv) From d6c7a481ad495016623b59278727058258c8ace6 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 4 Oct 2024 11:30:03 +0000 Subject: [PATCH 69/90] style(pre-commit): autofix --- .../concatenate_data/cloud_collector.hpp | 4 ++-- .../src/concatenate_data/cloud_collector.cpp | 1 - .../concatenate_and_time_sync_node.cpp | 19 +++++++++++-------- .../test/test_concatenate_node_unit.cpp | 1 - 4 files changed, 13 insertions(+), 12 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 7b2b6503be097..bb00f767a3573 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -27,7 +27,7 @@ namespace autoware::pointcloud_preprocessor class PointCloudConcatenateDataSynchronizerComponent; class CombineCloudHandler; -class CloudCollector +class CloudCollector { public: CloudCollector( @@ -42,7 +42,7 @@ class CloudCollector ConcatenatedCloudResult concatenate_pointclouds( std::unordered_map topic_to_cloud_map); - //void delete_collector(); + // void delete_collector(); std::unordered_map get_topic_to_cloud_map(); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index fabb7136f8256..a8224658ec7f8 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -89,7 +89,6 @@ ConcatenatedCloudResult CloudCollector::concatenate_pointclouds( return combine_cloud_handler_->combine_pointclouds(topic_to_cloud_map); } - std::unordered_map CloudCollector::get_topic_to_cloud_map() { diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 0b757ca0bd4ff..578f3e278897c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -331,23 +331,25 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( } } -void PointCloudConcatenateDataSynchronizerComponent::delete_collector(CloudCollector & cloud_collector) { +void PointCloudConcatenateDataSynchronizerComponent::delete_collector( + CloudCollector & cloud_collector) +{ // protect cloud collectors list std::lock_guard cloud_collectors_lock(cloud_collectors_mutex_); // change this to something else auto it = std::find_if( cloud_collectors_.begin(), cloud_collectors_.end(), - [&cloud_collector](const std::shared_ptr & collector) { return collector.get() == &cloud_collector; }); + [&cloud_collector](const std::shared_ptr & collector) { + return collector.get() == &cloud_collector; + }); if (it != cloud_collectors_.end()) { cloud_collectors_.erase(it); - } - else { + } else { throw std::runtime_error("Try to delete a cloud_collector that is not in the cloud_collectors"); } } - void PointCloudConcatenateDataSynchronizerComponent::convert_to_xyzirc_cloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) @@ -462,17 +464,18 @@ void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( } } -std::list> PointCloudConcatenateDataSynchronizerComponent::get_cloud_collectors() +std::list> +PointCloudConcatenateDataSynchronizerComponent::get_cloud_collectors() { return cloud_collectors_; } -void PointCloudConcatenateDataSynchronizerComponent::add_cloud_collector(const std::shared_ptr & collector) +void PointCloudConcatenateDataSynchronizerComponent::add_cloud_collector( + const std::shared_ptr & collector) { cloud_collectors_.push_back(collector); } - } // namespace autoware::pointcloud_preprocessor #include diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index d0fbfe87b543c..15a17d8f6c9f1 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -69,7 +69,6 @@ class ConcatenateCloudTest : public ::testing::Test concatenate_node_->shared_from_this()), combine_cloud_handler_, number_of_pointcloud, timeout_sec); - // Setup TF tf_broadcaster_ = std::make_shared(concatenate_node_); tf_broadcaster_->sendTransform(generate_static_transform_msgs()); From 481591720940aea841c684f82a9aee9ba0118d27 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 7 Oct 2024 13:13:33 +0900 Subject: [PATCH 70/90] chore: clean code Signed-off-by: vividf --- .../pointcloud_preprocessor/concatenate_data/cloud_collector.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index bb00f767a3573..1cf569df0b98f 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -42,7 +42,6 @@ class CloudCollector ConcatenatedCloudResult concatenate_pointclouds( std::unordered_map topic_to_cloud_map); - // void delete_collector(); std::unordered_map get_topic_to_cloud_map(); From 40fe11ebf057baaa121714260085b75c1e70b0ba Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 7 Oct 2024 14:13:27 +0900 Subject: [PATCH 71/90] chore: add parameters for handling rosbag replay in loops Signed-off-by: vividf --- .../concatenate_and_time_sync_node.param.yaml | 2 ++ .../concatenate_and_time_sync_node.hpp | 2 ++ ...concatenate_and_time_sync_node.schema.json | 27 ++++++++++++++----- .../concatenate_and_time_sync_node.cpp | 16 ++++++++++- .../test/test_concatenate_node_component.py | 2 ++ .../test/test_concatenate_node_unit.cpp | 2 ++ 6 files changed, 43 insertions(+), 8 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml index d99849b532f3e..5f5014d173111 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -1,6 +1,8 @@ /**: ros__parameters: has_static_tf_only: false + rosbag_replay: true + rosbag_length: 20.0 maximum_queue_size: 5 timeout_sec: 0.2 is_motion_compensated: true diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index a44878a23e2e9..58a576d445e7e 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -68,6 +68,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node struct Parameters { bool has_static_tf_only; + bool rosbag_replay; + double rosbag_length; int maximum_queue_size; double timeout_sec; bool is_motion_compensated; diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 022e7f30f8d73..5df447959c728 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -6,6 +6,22 @@ "concatenate_and_time_sync_node": { "type": "object", "properties": { + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." + }, + "rosbag_replay": { + "type": "boolean", + "default": true, + "description": "Flag to indicate whether the user is replaying the rosbag in loops without relaunching the node." + }, + "rosbag_length": { + "type": "boolean", + "default": 20.0, + "minimum": 0.0, + "description": "If rosbag_replay is enabled, this value helps the node determine if the rosbag has started from the beginning again. The value should be set slightly smaller (by 2-3 seconds) than the actual length of the bag." + }, "maximum_queue_size": { "type": "integer", "default": "5", @@ -84,14 +100,12 @@ "default": [0.01, 0.01, 0.01], "minItems": 2, "description": "List of LiDAR timestamp noise windows in seconds. The noise values should be specified in the same order as the input_topics." - }, - "has_static_tf_only": { - "type": "boolean", - "default": false, - "description": "Flag to indicate if only static TF is used." } }, "required": [ + "has_static_tf_only", + "rosbag_replay", + "rosbag_length", "maximum_queue_size", "timeout_sec", "is_motion_compensated", @@ -103,8 +117,7 @@ "input_topics", "output_frame", "lidar_timestamp_offsets", - "lidar_timestamp_noise_window", - "has_static_tf_only" + "lidar_timestamp_noise_window" ] } }, diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 578f3e278897c..beea27d50a184 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -45,6 +45,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // initialize parameters params_.has_static_tf_only = declare_parameter("has_static_tf_only"); + params_.rosbag_replay = declare_parameter("rosbag_replay"); + params_.rosbag_length = declare_parameter("rosbag_length"); params_.maximum_queue_size = static_cast(declare_parameter("maximum_queue_size")); params_.timeout_sec = declare_parameter("timeout_sec"); params_.is_motion_compensated = declare_parameter("is_motion_compensated"); @@ -275,9 +277,21 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( if ( current_concatenate_cloud_timestamp_ < latest_concatenate_cloud_timestamp_ && !params_.publish_previous_but_late_pointcloud) { - drop_previous_but_late_pointcloud_ = true; + // Check if we're in rosbag replay mode and the time difference is close to the rosbag length + if ( + params_.rosbag_replay && + (latest_concatenate_cloud_timestamp_ - current_concatenate_cloud_timestamp_ > + params_.rosbag_length)) { + publish_pointcloud_ = true; // Force publishing in this case + } else { + drop_previous_but_late_pointcloud_ = true; // Otherwise, drop the late pointcloud + } } else { + // Publish pointcloud if timestamps are valid or the condition doesn't apply publish_pointcloud_ = true; + } + + if (publish_pointcloud_) { latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; auto concatenate_pointcloud_output = std::make_unique( *concatenated_cloud_result.concatenate_cloud_ptr); diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index 0aeced645de96..9cf2134703b20 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -85,6 +85,8 @@ def generate_test_description(): parameters=[ { "has_static_tf_only": False, + "rosbag_replay": False, + "rosbag_length": 0.0, "maximum_queue_size": 5, "timeout_sec": TIMEOUT_SEC, "is_motion_compensated": True, diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 15a17d8f6c9f1..b166e878f0f31 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -42,6 +42,8 @@ class ConcatenateCloudTest : public ::testing::Test // They just helps to setup the concatenate node node_options.parameter_overrides( {{"has_static_tf_only", false}, + {"rosbag_replay", false}, + {"rosbag_length", 0.0}, {"maximum_queue_size", 5}, {"timeout_sec", 0.2}, {"is_motion_compensated", true}, From 3433bf0b4aa5171cd676700e1e447d4d306bd4e8 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 7 Oct 2024 18:40:29 +0900 Subject: [PATCH 72/90] chore: fix diagonistic Signed-off-by: vividf --- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index beea27d50a184..3e1b1758dfa84 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -437,9 +437,9 @@ void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( bool topic_miss = false; - int concatenated_cloud_status = 1; // 1 for success, 0 for failure - int cloud_status = 1; // for each lidar's pointcloud + int concatenated_cloud_status = 1; // Status of concatenated cloud, 1: success, 0: failure for (const auto & topic : params_.input_topics) { + int cloud_status = 1; // Status of each lidar's pointcloud if ( diagnostic_topic_to_original_stamp_map_.find(topic) != diagnostic_topic_to_original_stamp_map_.end()) { From 09b8ce384e413c3a16b538a260fb263567a0bdb7 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 21 Oct 2024 15:27:02 +0900 Subject: [PATCH 73/90] chore: reduce copy operation Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.hpp | 2 +- .../src/concatenate_data/cloud_collector.cpp | 2 +- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 58a576d445e7e..f8b0201f0967e 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -58,7 +58,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); ~PointCloudConcatenateDataSynchronizerComponent() override = default; void publish_clouds( - ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, + ConcatenatedCloudResult && concatenated_cloud_result, double reference_timestamp_min, double reference_timestamp_max); void delete_collector(CloudCollector & cloud_collector); std::list> get_cloud_collectors(); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index a8224658ec7f8..60d1e2e4ebc80 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -79,7 +79,7 @@ void CloudCollector::concatenate_callback() auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); ros2_parent_node_->publish_clouds( - concatenated_cloud_result, reference_timestamp_min_, reference_timestamp_max_); + std::move(concatenated_cloud_result), reference_timestamp_min_, reference_timestamp_max_); ros2_parent_node_->delete_collector(*this); } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 3e1b1758dfa84..fc97980cd8fd7 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -263,7 +263,7 @@ void PointCloudConcatenateDataSynchronizerComponent::odom_callback( } void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( - ConcatenatedCloudResult concatenated_cloud_result, double reference_timestamp_min, + ConcatenatedCloudResult && concatenated_cloud_result, double reference_timestamp_min, double reference_timestamp_max) { // should never come to this state. @@ -294,7 +294,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( if (publish_pointcloud_) { latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; auto concatenate_pointcloud_output = std::make_unique( - *concatenated_cloud_result.concatenate_cloud_ptr); + std::move(*concatenated_cloud_result.concatenate_cloud_ptr)); concatenated_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); // publish transformed raw pointclouds From 782228fb9b1e97b5f066647c37ae357324ad2b71 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 21 Oct 2024 16:08:49 +0900 Subject: [PATCH 74/90] chore: reserve space for concatenated pointcloud Signed-off-by: vividf --- .../combine_cloud_handler.cpp | 51 +++++-------------- 1 file changed, 12 insertions(+), 39 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 9cdc7ad5d0b2f..b8c6e5aa3ae15 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -140,6 +140,18 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( std::unordered_map transform_memo; + // Before combining the pointclouds, initialize and reserve space for the concatenated pointcloud + concatenate_cloud_result.concatenate_cloud_ptr = + std::make_shared(); + + // Reserve space based on the total size of the pointcloud data to speed up the concatenation + // process + size_t total_data_size = 0; + for (const auto & [topic, cloud] : topic_to_cloud_map) { + total_data_size += cloud->data.size(); + } + concatenate_cloud_result.concatenate_cloud_ptr->data.reserve(total_data_size); + for (const auto & [topic, cloud] : topic_to_cloud_map) { auto transformed_cloud_ptr = std::make_shared(); managed_tf_buffer_->transformPointcloud(output_frame_, *cloud, *transformed_cloud_ptr); @@ -157,49 +169,10 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( transformed_delay_compensated_cloud_ptr = transformed_cloud_ptr; } - // Check if concatenate_cloud_ptr is nullptr, if so initialize it - if (concatenate_cloud_result.concatenate_cloud_ptr == nullptr) { - // Initialize concatenate_cloud_ptr without copying the data - concatenate_cloud_result.concatenate_cloud_ptr = - std::make_shared(); - concatenate_cloud_result.concatenate_cloud_ptr->header = - transformed_delay_compensated_cloud_ptr->header; - concatenate_cloud_result.concatenate_cloud_ptr->height = - transformed_delay_compensated_cloud_ptr->height; - concatenate_cloud_result.concatenate_cloud_ptr->width = - 0; // Will be updated with total points - concatenate_cloud_result.concatenate_cloud_ptr->is_dense = - transformed_delay_compensated_cloud_ptr->is_dense; - concatenate_cloud_result.concatenate_cloud_ptr->is_bigendian = - transformed_delay_compensated_cloud_ptr->is_bigendian; - concatenate_cloud_result.concatenate_cloud_ptr->fields = - transformed_delay_compensated_cloud_ptr->fields; - concatenate_cloud_result.concatenate_cloud_ptr->point_step = - transformed_delay_compensated_cloud_ptr->point_step; - concatenate_cloud_result.concatenate_cloud_ptr->row_step = - 0; // Will be updated after concatenation - concatenate_cloud_result.concatenate_cloud_ptr->data.clear(); - - // Reserve space for the data (assume max points you expect to concatenate) - auto num_of_points = transformed_delay_compensated_cloud_ptr->width * - transformed_delay_compensated_cloud_ptr->height; - concatenate_cloud_result.concatenate_cloud_ptr->data.reserve( - num_of_points * concatenate_cloud_result.concatenate_cloud_ptr->point_step); - } - - // Concatenate the current pointcloud to the concatenated cloud pcl::concatenatePointCloud( *concatenate_cloud_result.concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concatenate_cloud_result.concatenate_cloud_ptr); - // Update width and row_step to reflect the new size - concatenate_cloud_result.concatenate_cloud_ptr->width = - concatenate_cloud_result.concatenate_cloud_ptr->data.size() / - concatenate_cloud_result.concatenate_cloud_ptr->point_step; - concatenate_cloud_result.concatenate_cloud_ptr->row_step = - concatenate_cloud_result.concatenate_cloud_ptr->width * - concatenate_cloud_result.concatenate_cloud_ptr->point_step; - if (publish_synchronized_pointcloud_) { if (!concatenate_cloud_result.topic_to_transformed_cloud_map) { // Initialize the map if it is not present From 360611489426baac301ad48a190ce4ef7fdac5f2 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 21 Oct 2024 16:12:35 +0900 Subject: [PATCH 75/90] chore: fix clangd error Signed-off-by: vividf --- .../src/concatenate_data/combine_cloud_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index b8c6e5aa3ae15..bc6a5b6bc81d3 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -133,7 +133,7 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( std::vector pc_stamps; for (const auto & [topic, cloud] : topic_to_cloud_map) { - pc_stamps.emplace_back(rclcpp::Time(cloud->header.stamp)); + pc_stamps.emplace_back(cloud->header.stamp); } std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); const auto oldest_stamp = pc_stamps.back(); From 6ed75375b58f85d6c153b49c5e14ab3aaba52bd8 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 21 Oct 2024 16:32:41 +0900 Subject: [PATCH 76/90] chore: fix pipeline latency Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index fc97980cd8fd7..1a3b9d7a03a7e 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -334,11 +334,9 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( "debug/processing_time_ms", processing_time_ms); for (const auto & [topic, stamp] : concatenated_cloud_result.topic_to_original_stamp_map) { - const auto pipeline_latency_ms = - std::chrono::duration( - std::chrono::duration_cast( - std::chrono::duration(this->get_clock()->now().nanoseconds() - stamp * 1e9))) - .count(); + const auto pipeline_latency_ms = std::chrono::duration( + this->get_clock()->now().nanoseconds() - stamp * 1e9) + .count(); debug_publisher_->publish( "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); } From 0248a24cdb98f1cd9d79c2e7c812dbf99d5d4b82 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 21 Oct 2024 20:59:05 +0900 Subject: [PATCH 77/90] chore: add debug mode Signed-off-by: vividf --- .../concatenate_data/cloud_collector.hpp | 4 ++- .../concatenate_and_time_sync_node.hpp | 1 + .../src/concatenate_data/cloud_collector.cpp | 29 +++++++++++++++++-- .../concatenate_and_time_sync_node.cpp | 11 ++++++- .../test/test_concatenate_node_component.py | 1 + .../test/test_concatenate_node_unit.cpp | 8 +++-- 6 files changed, 47 insertions(+), 7 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index 1cf569df0b98f..b90fd4a526632 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -32,7 +32,8 @@ class CloudCollector public: CloudCollector( std::shared_ptr && ros2_parent_node, - std::shared_ptr & combine_cloud_handler, int num_of_clouds, double time); + std::shared_ptr & combine_cloud_handler, int num_of_clouds, + double timeout_sec, bool debug_mode); void set_reference_timestamp(double timestamp, double noise_window); std::tuple get_reference_timestamp_boundary(); @@ -55,6 +56,7 @@ class CloudCollector double timeout_sec_; double reference_timestamp_min_{0.0}; double reference_timestamp_max_{0.0}; + bool debug_mode_; }; } // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index f8b0201f0967e..2438725f867e0 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -67,6 +67,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node private: struct Parameters { + bool debug_mode; bool has_static_tf_only; bool rosbag_replay; double rosbag_length; diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 60d1e2e4ebc80..5b87fda0ee0e2 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -27,11 +27,12 @@ namespace autoware::pointcloud_preprocessor CloudCollector::CloudCollector( std::shared_ptr && ros2_parent_node, std::shared_ptr & combine_cloud_handler, int num_of_clouds, - double timeout_sec) + double timeout_sec, bool debug_mode) : ros2_parent_node_(std::move(ros2_parent_node)), combine_cloud_handler_(combine_cloud_handler), num_of_clouds_(num_of_clouds), - timeout_sec_(timeout_sec) + timeout_sec_(timeout_sec), + debug_mode_(debug_mode) { const auto period_ns = std::chrono::duration_cast( std::chrono::duration(timeout_sec_)); @@ -74,12 +75,36 @@ void CloudCollector::concatenate_callback() { // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the // pointclouds in the collector. + auto time_until_trigger = timer_->time_until_trigger(); timer_->cancel(); auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); + if (debug_mode_) { + std::stringstream log_stream; + log_stream << "Collector's concatenate callback time: " + << ros2_parent_node_->get_clock()->now().seconds() << " seconds\n"; + + log_stream << "Collector's reference time min: " << reference_timestamp_min_ + << " to max: " << reference_timestamp_max_ << " seconds\n"; + + log_stream << "Time until trigger: " << (time_until_trigger.count() / 1e9) << " seconds\n"; + + log_stream << "Pointclouds: ["; + for (auto it = concatenated_cloud_result.topic_to_original_stamp_map.begin(); + it != concatenated_cloud_result.topic_to_original_stamp_map.end(); ++it) { + log_stream << "[" << it->first << ", " << it->second << "]"; + if (std::next(it) != concatenated_cloud_result.topic_to_original_stamp_map.end()) { + log_stream << ", "; + } + } + log_stream << "]\n"; + + RCLCPP_INFO(ros2_parent_node_->get_logger(), "%s", log_stream.str().c_str()); + } ros2_parent_node_->publish_clouds( std::move(concatenated_cloud_result), reference_timestamp_min_, reference_timestamp_max_); + ros2_parent_node_->delete_collector(*this); } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 1a3b9d7a03a7e..a30c0a0b13f1e 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -44,6 +44,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro stop_watch_ptr_->tic("processing_time"); // initialize parameters + params_.debug_mode = declare_parameter("debug_mode"); params_.has_static_tf_only = declare_parameter("has_static_tf_only"); params_.rosbag_replay = declare_parameter("rosbag_replay"); params_.rosbag_length = declare_parameter("rosbag_length"); @@ -200,6 +201,14 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( return; } + if (params_.debug_mode) { + RCLCPP_INFO( + this->get_logger(), " pointcloud %s timestamp: %lf arrive time: %lf seconds, latency: %lf", + topic_name.c_str(), rclcpp::Time(input_ptr->header.stamp).seconds(), + this->get_clock()->now().seconds(), + this->get_clock()->now().seconds() - rclcpp::Time(input_ptr->header.stamp).seconds()); + } + sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); auto input = std::make_shared(*input_ptr); if (input->data.empty()) { @@ -239,7 +248,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( if (!collector_found) { auto new_cloud_collector = std::make_shared( std::dynamic_pointer_cast(shared_from_this()), - combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec); + combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec, params_.debug_mode); cloud_collectors_.push_back(new_cloud_collector); cloud_collectors_lock.unlock(); diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index 9cf2134703b20..d346a80534c8f 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -84,6 +84,7 @@ def generate_test_description(): ], parameters=[ { + "debug_mode": True, "has_static_tf_only": False, "rosbag_replay": False, "rosbag_length": 0.0, diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index b166e878f0f31..8f58e1c32e02e 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -41,7 +41,8 @@ class ConcatenateCloudTest : public ::testing::Test // Instead of "input_topics", other parameters are not used. // They just helps to setup the concatenate node node_options.parameter_overrides( - {{"has_static_tf_only", false}, + {{"debug_mode", true}, + {"has_static_tf_only", false}, {"rosbag_replay", false}, {"rosbag_length", 0.0}, {"maximum_queue_size", 5}, @@ -69,7 +70,7 @@ class ConcatenateCloudTest : public ::testing::Test std::dynamic_pointer_cast< autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( concatenate_node_->shared_from_this()), - combine_cloud_handler_, number_of_pointcloud, timeout_sec); + combine_cloud_handler_, number_of_pointcloud, timeout_sec, collector_debug_mode); // Setup TF tf_broadcaster_ = std::make_shared(concatenate_node_); @@ -177,7 +178,8 @@ class ConcatenateCloudTest : public ::testing::Test static constexpr float standard_tolerance{1e-4}; static constexpr int number_of_pointcloud{3}; static constexpr float timeout_sec{0.2}; - bool debug_{false}; + static constexpr bool collector_debug_mode{true}; // For showing collector information + bool debug_{false}; // For the Unit test }; //////////////////////////////// Test combine_cloud_handler //////////////////////////////// From 76d3b4c248b48968b756d2ccd6c97ff1941316c5 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 22 Oct 2024 10:28:49 +0900 Subject: [PATCH 78/90] chore: refactor convert_to_xyzirc_cloud function Signed-off-by: vividf --- .../combine_cloud_handler.hpp | 7 +++ .../concatenate_and_time_sync_node.hpp | 8 --- .../combine_cloud_handler.cpp | 63 ++++++++++++++++++- .../concatenate_and_time_sync_node.cpp | 62 +----------------- 4 files changed, 70 insertions(+), 70 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index d8a363c63be21..c56b65ebabcd1 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -22,6 +22,7 @@ #include // ROS includes +#include "autoware_point_types/types.hpp" #include #include @@ -44,6 +45,8 @@ namespace autoware::pointcloud_preprocessor { +using autoware_point_types::PointXYZIRC; +using point_cloud_msg_wrapper::PointCloud2Modifier; struct ConcatenatedCloudResult { @@ -77,6 +80,10 @@ class CombineCloudHandler } }; + static void convert_to_xyzirc_cloud( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_cloud, + sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud); + void correct_pointcloud_motion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 2438725f867e0..3e6febbdbe844 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -22,7 +22,6 @@ #include // ROS includes -#include "autoware_point_types/types.hpp" #include "cloud_collector.hpp" #include "combine_cloud_handler.hpp" @@ -48,10 +47,6 @@ namespace autoware::pointcloud_preprocessor { - -using autoware_point_types::PointXYZIRC; -using point_cloud_msg_wrapper::PointCloud2Modifier; - class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node { public: @@ -125,9 +120,6 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node void check_concat_status(diagnostic_updater::DiagnosticStatusWrapper & stat); std::string replace_sync_topic_name_postfix( const std::string & original_topic_name, const std::string & postfix); - static void convert_to_xyzirc_cloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, - sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); }; } // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index bc6a5b6bc81d3..6888f45ce53c1 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -100,6 +100,61 @@ std::deque CombineCloudHandler::get_twist_queu return twist_queue_; } +void CombineCloudHandler::convert_to_xyzirc_cloud( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_cloud, + sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud) +{ + xyzirc_cloud->header = input_cloud->header; + + PointCloud2Modifier output_modifier{ + *xyzirc_cloud, input_cloud->header.frame_id}; + output_modifier.reserve(input_cloud->width); + + bool has_valid_intensity = + std::any_of(input_cloud->fields.begin(), input_cloud->fields.end(), [](const auto & field) { + return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_return_type = + std::any_of(input_cloud->fields.begin(), input_cloud->fields.end(), [](const auto & field) { + return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_channel = + std::any_of(input_cloud->fields.begin(), input_cloud->fields.end(), [](const auto & field) { + return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; + }); + + sensor_msgs::PointCloud2Iterator it_x(*input_cloud, "x"); + sensor_msgs::PointCloud2Iterator it_y(*input_cloud, "y"); + sensor_msgs::PointCloud2Iterator it_z(*input_cloud, "z"); + + if (has_valid_intensity && has_valid_return_type && has_valid_channel) { + sensor_msgs::PointCloud2Iterator it_i(*input_cloud, "intensity"); + sensor_msgs::PointCloud2Iterator it_r(*input_cloud, "return_type"); + sensor_msgs::PointCloud2Iterator it_c(*input_cloud, "channel"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { + PointXYZIRC point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + point.intensity = *it_i; + point.return_type = *it_r; + point.channel = *it_c; + output_modifier.push_back(std::move(point)); + } + } else { + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { + PointXYZIRC point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + output_modifier.push_back(std::move(point)); + } + } +} + void CombineCloudHandler::correct_pointcloud_motion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, @@ -153,8 +208,14 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( concatenate_cloud_result.concatenate_cloud_ptr->data.reserve(total_data_size); for (const auto & [topic, cloud] : topic_to_cloud_map) { + // convert to XYZIRC pointcloud if pointcloud is not empty + // auto xyzirc_cloud = std::make_shared(); + + sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_cloud(new sensor_msgs::msg::PointCloud2()); + convert_to_xyzirc_cloud(cloud, xyzirc_cloud); + auto transformed_cloud_ptr = std::make_shared(); - managed_tf_buffer_->transformPointcloud(output_frame_, *cloud, *transformed_cloud_ptr); + managed_tf_buffer_->transformPointcloud(output_frame_, *xyzirc_cloud, *transformed_cloud_ptr); concatenate_cloud_result.topic_to_original_stamp_map[topic] = rclcpp::Time(cloud->header.stamp).seconds(); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index a30c0a0b13f1e..f1ed64e03df51 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -209,17 +209,12 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( this->get_clock()->now().seconds() - rclcpp::Time(input_ptr->header.stamp).seconds()); } - sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); - auto input = std::make_shared(*input_ptr); - if (input->data.empty()) { + if (input_ptr->data.empty()) { RCLCPP_WARN_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); return; } - // convert to XYZIRC pointcloud if pointcloud is not empty - convert_to_xyzirc_cloud(input, xyzirc_input_ptr); - // protect cloud collectors list std::unique_lock cloud_collectors_lock(cloud_collectors_mutex_); @@ -371,61 +366,6 @@ void PointCloudConcatenateDataSynchronizerComponent::delete_collector( } } -void PointCloudConcatenateDataSynchronizerComponent::convert_to_xyzirc_cloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, - sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) -{ - output_ptr->header = input_ptr->header; - - PointCloud2Modifier output_modifier{ - *output_ptr, input_ptr->header.frame_id}; - output_modifier.reserve(input_ptr->width); - - bool has_valid_intensity = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; - }); - - bool has_valid_return_type = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; - }); - - bool has_valid_channel = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; - }); - - sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); - sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); - sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); - - if (has_valid_intensity && has_valid_return_type && has_valid_channel) { - sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); - sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); - sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); - - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { - PointXYZIRC point; - point.x = *it_x; - point.y = *it_y; - point.z = *it_z; - point.intensity = *it_i; - point.return_type = *it_r; - point.channel = *it_c; - output_modifier.push_back(std::move(point)); - } - } else { - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { - PointXYZIRC point; - point.x = *it_x; - point.y = *it_y; - point.z = *it_z; - output_modifier.push_back(std::move(point)); - } - } -} - std::string PointCloudConcatenateDataSynchronizerComponent::format_timestamp(double timestamp) { std::ostringstream oss; From e709d37756d342601d7c795487ef43bdba9cb159 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 22 Oct 2024 10:35:17 +0900 Subject: [PATCH 79/90] chore: fix json schema Signed-off-by: vividf --- .../config/concatenate_and_time_sync_node.param.yaml | 1 + .../schema/concatenate_and_time_sync_node.schema.json | 8 +++++++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml index 5f5014d173111..20e0bb057cc4d 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + debug_mode: false has_static_tf_only: false rosbag_replay: true rosbag_length: 20.0 diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 5df447959c728..98196262f8339 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -6,6 +6,11 @@ "concatenate_and_time_sync_node": { "type": "object", "properties": { + "debug_mode": { + "type": "boolean", + "default": false, + "description": "Flag to enables debug mode to display additional logging information." + }, "has_static_tf_only": { "type": "boolean", "default": false, @@ -17,7 +22,7 @@ "description": "Flag to indicate whether the user is replaying the rosbag in loops without relaunching the node." }, "rosbag_length": { - "type": "boolean", + "type": "number", "default": 20.0, "minimum": 0.0, "description": "If rosbag_replay is enabled, this value helps the node determine if the rosbag has started from the beginning again. The value should be set slightly smaller (by 2-3 seconds) than the actual length of the bag." @@ -103,6 +108,7 @@ } }, "required": [ + "debug_mode", "has_static_tf_only", "rosbag_replay", "rosbag_length", From fcdb98908b098a13098ad624cac5870397abfcc4 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 22 Oct 2024 11:01:10 +0900 Subject: [PATCH 80/90] chore: fix logging output Signed-off-by: vividf --- .../src/concatenate_data/cloud_collector.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 5b87fda0ee0e2..307927f2eebec 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -81,6 +81,7 @@ void CloudCollector::concatenate_callback() auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); if (debug_mode_) { std::stringstream log_stream; + log_stream << std::fixed << std::setprecision(6); log_stream << "Collector's concatenate callback time: " << ros2_parent_node_->get_clock()->now().seconds() << " seconds\n"; From 460b467ecb2de51e7639476b2dd514992df15cde Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 22 Oct 2024 16:13:34 +0900 Subject: [PATCH 81/90] chore: fix the output order of the debug mode Signed-off-by: vividf --- .../src/concatenate_data/cloud_collector.cpp | 25 ++++++++++--------- 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index 307927f2eebec..b0a7f746be778 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -73,13 +73,8 @@ void CloudCollector::process_pointcloud( void CloudCollector::concatenate_callback() { - // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the - // pointclouds in the collector. - auto time_until_trigger = timer_->time_until_trigger(); - timer_->cancel(); - - auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); if (debug_mode_) { + auto time_until_trigger = timer_->time_until_trigger(); std::stringstream log_stream; log_stream << std::fixed << std::setprecision(6); log_stream << "Collector's concatenate callback time: " @@ -91,18 +86,24 @@ void CloudCollector::concatenate_callback() log_stream << "Time until trigger: " << (time_until_trigger.count() / 1e9) << " seconds\n"; log_stream << "Pointclouds: ["; - for (auto it = concatenated_cloud_result.topic_to_original_stamp_map.begin(); - it != concatenated_cloud_result.topic_to_original_stamp_map.end(); ++it) { - log_stream << "[" << it->first << ", " << it->second << "]"; - if (std::next(it) != concatenated_cloud_result.topic_to_original_stamp_map.end()) { - log_stream << ", "; - } + std::string separator = ""; + for (const auto & [topic, cloud] : topic_to_cloud_map_) { + log_stream << separator; + log_stream << "[" << topic << ", " << rclcpp::Time(cloud->header.stamp).seconds() << "]"; + separator = ", "; } + log_stream << "]\n"; RCLCPP_INFO(ros2_parent_node_->get_logger(), "%s", log_stream.str().c_str()); } + // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the + // pointclouds in the collector. + timer_->cancel(); + + auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); + ros2_parent_node_->publish_clouds( std::move(concatenated_cloud_result), reference_timestamp_min_, reference_timestamp_max_); From 798cbd6e6a67f2536b9af52225e7af29f381c18d Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 23 Oct 2024 21:44:39 +0900 Subject: [PATCH 82/90] chore: fix pipeline latency output Signed-off-by: vividf --- .../src/concatenate_data/concatenate_and_time_sync_node.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index f1ed64e03df51..569a15d75c23b 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -338,9 +338,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( "debug/processing_time_ms", processing_time_ms); for (const auto & [topic, stamp] : concatenated_cloud_result.topic_to_original_stamp_map) { - const auto pipeline_latency_ms = std::chrono::duration( - this->get_clock()->now().nanoseconds() - stamp * 1e9) - .count(); + const auto pipeline_latency_ms = (this->get_clock()->now().seconds() - stamp) * 1000; debug_publisher_->publish( "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); } From a2e8b77be9bcdce4e139cd42e26bc7cca519850b Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 24 Oct 2024 17:46:31 +0900 Subject: [PATCH 83/90] chore: clean code Signed-off-by: vividf --- .../config/concatenate_and_time_sync_node.param.yaml | 2 +- .../src/concatenate_data/combine_cloud_handler.cpp | 4 +--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml index 20e0bb057cc4d..48a8467cbfe72 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -2,7 +2,7 @@ ros__parameters: debug_mode: false has_static_tf_only: false - rosbag_replay: true + rosbag_replay: false rosbag_length: 20.0 maximum_queue_size: 5 timeout_sec: 0.2 diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 6888f45ce53c1..1693f4e2972e6 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -209,9 +209,7 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( for (const auto & [topic, cloud] : topic_to_cloud_map) { // convert to XYZIRC pointcloud if pointcloud is not empty - // auto xyzirc_cloud = std::make_shared(); - - sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_cloud(new sensor_msgs::msg::PointCloud2()); + auto xyzirc_cloud = std::make_shared(); convert_to_xyzirc_cloud(cloud, xyzirc_cloud); auto transformed_cloud_ptr = std::make_shared(); From 2562d6ec3debf5d865d6e31bbec7b017931d8102 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 24 Oct 2024 18:08:25 +0900 Subject: [PATCH 84/90] chore: set some parameters to false in testing Signed-off-by: vividf --- .../test/test_concatenate_node_component.py | 6 ++++-- .../test/test_concatenate_node_unit.cpp | 6 +++--- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index d346a80534c8f..3ea2948e393fc 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -58,7 +58,6 @@ TIMESTAMP_NOISE = 0.01 # 10 ms NUM_OF_POINTS = 3 -DEBUG = False MILLISECONDS = 1000000 @@ -68,6 +67,9 @@ GLOBAL_SECONDS = 10 GLOBAL_NANOSECONDS = 100000000 +# Set to True if you want to check the output of the component tests. +DEBUG = False + @pytest.mark.launch_test def generate_test_description(): @@ -84,7 +86,7 @@ def generate_test_description(): ], parameters=[ { - "debug_mode": True, + "debug_mode": False, "has_static_tf_only": False, "rosbag_replay": False, "rosbag_length": 0.0, diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index 8f58e1c32e02e..bd22376b1c564 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -41,7 +41,7 @@ class ConcatenateCloudTest : public ::testing::Test // Instead of "input_topics", other parameters are not used. // They just helps to setup the concatenate node node_options.parameter_overrides( - {{"debug_mode", true}, + {{"debug_mode", false}, {"has_static_tf_only", false}, {"rosbag_replay", false}, {"rosbag_length", 0.0}, @@ -178,8 +178,8 @@ class ConcatenateCloudTest : public ::testing::Test static constexpr float standard_tolerance{1e-4}; static constexpr int number_of_pointcloud{3}; static constexpr float timeout_sec{0.2}; - static constexpr bool collector_debug_mode{true}; // For showing collector information - bool debug_{false}; // For the Unit test + static constexpr bool collector_debug_mode{false}; // For showing collector information + bool debug_{false}; // For the Unit test }; //////////////////////////////// Test combine_cloud_handler //////////////////////////////// From a970f795a15949be8c4f94f921fd57002bffa8d9 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 24 Oct 2024 18:13:07 +0900 Subject: [PATCH 85/90] chore: fix default value for schema Signed-off-by: vividf --- .../schema/concatenate_and_time_sync_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 98196262f8339..581e540b43e02 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -18,7 +18,7 @@ }, "rosbag_replay": { "type": "boolean", - "default": true, + "default": false, "description": "Flag to indicate whether the user is replaying the rosbag in loops without relaunching the node." }, "rosbag_length": { From 4e39bbcdbc04e6e76b221140ff760073ce801cb6 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 28 Oct 2024 12:41:23 +0900 Subject: [PATCH 86/90] chore: fix diagnostic msgs Signed-off-by: vividf --- .../concatenate_data/concatenate_and_time_sync_node.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 569a15d75c23b..219f391b58b22 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -403,12 +403,17 @@ void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( int8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::string message = "Concatenated pointcloud is published and include all topics"; - if (topic_miss) { + if (topic_miss && drop_previous_but_late_pointcloud_) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - message = "Concatenated pointcloud is published but miss some topics"; + message = + "Concatenated pointcloud is missing some topics and is not published because it arrived " + "too late."; } else if (drop_previous_but_late_pointcloud_) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; message = "Concatenated pointcloud is not published as it is too late"; + } else if (topic_miss) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = "Concatenated pointcloud is published but miss some topics"; } stat.summary(level, message); From afa000d15a36542e0b180908ee0c3f26b365262f Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 29 Oct 2024 14:48:56 +0900 Subject: [PATCH 87/90] chore: fix parameter for sample ros bag Signed-off-by: vividf --- .../config/concatenate_and_time_sync_node.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml index 48a8467cbfe72..c5bd139e1e962 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -13,10 +13,10 @@ synchronized_pointcloud_postfix: pointcloud input_twist_topic_type: twist input_topics: [ - "/sensing/lidar/left/pointcloud_before_sync", "/sensing/lidar/right/pointcloud_before_sync", - "/sensing/lidar/top/pointcloud_before_sync" + "/sensing/lidar/top/pointcloud_before_sync", + "/sensing/lidar/left/pointcloud_before_sync", ] output_frame: base_link - lidar_timestamp_offsets: [0.0, 0.04, 0.08] + lidar_timestamp_offsets: [0.0, 0.015, 0.016] lidar_timestamp_noise_window: [0.01, 0.01, 0.01] From 3123849d4b69b30eb6ef597830e7a2a289577da2 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 13 Nov 2024 14:21:37 +0900 Subject: [PATCH 88/90] chore: update readme Signed-off-by: vividf --- .../docs/concatenate-data.md | 20 ++++++++++++++++++- 1 file changed, 19 insertions(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index d558fa4ba98d1..e0d114b5a4f23 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -57,7 +57,25 @@ When network issues occur or when point clouds experience delays in the previous #### lidar_timestamp_offsets -Since different vehicles have varied designs for LiDAR scanning, the timestamps of each LiDAR may differ. Users need to know the offsets between each LiDAR and set the values in `lidar_timestamp_offsets`. For instance, if there are three LiDARs (left, right, top), and the timestamps for the left, right, and top point clouds are 0.01, 0.05, and 0.09 seconds respectively, the parameters should be set as [0.0, 0.04, 0.08]. This reflects the timestamp differences between the current point cloud and the point cloud with the earliest timestamp. Note that the order of the `lidar_timestamp_offsets` corresponds to the order of the `input_topics`. +Since different vehicles have varied designs for LiDAR scanning, the timestamps of each LiDAR may differ. Users need to know the offsets between each LiDAR and set the values in `lidar_timestamp_offsets`. + +To monitor the timestamps of each LiDAR, run the following command: + +```bash +ros2 topic echo "pointcloud_topic" --field header +``` + +The timestamps should increase steadily by approximately 100 ms, as per the Autoware default. You should see output like this: + +```bash +nanosec: 156260951 +nanosec: 257009560 +nanosec: 355444581 +``` + +This pattern indicates a LiDAR timestamp is 0.05. + +If there are three LiDARs (left, right, top), and the timestamps for the left, right, and top point clouds are `0.01`, `0.05`, and `0.09` seconds respectively, the parameters should be set as [0.0, 0.04, 0.08]. This reflects the timestamp differences between the current point cloud and the point cloud with the earliest timestamp. Note that the order of the `lidar_timestamp_offsets` corresponds to the order of the `input_topics`. The figure below demonstrates how `lidar_timestamp_offsets` works with `concatenate_and_time_sync_node`. From 4f7b536fb78a0d3d3ed932ff418e7ec91082d499 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos-Tsunekawa Date: Fri, 22 Nov 2024 13:36:38 +0900 Subject: [PATCH 89/90] feat: implemented a cuda accelerated pointcloud concatenation and integrated it with the cuda blackboard Signed-off-by: Kenzo Lobos-Tsunekawa --- .../CMakeLists.txt | 18 + .../concatenate_and_time_sync_node.param.yaml | 1 + .../concatenate_data/cloud_collector.hpp | 19 +- .../combine_cloud_handler.hpp | 104 ++++- .../combine_cloud_handler_kernel.hpp | 61 +++ .../concatenate_and_time_sync_node.hpp | 71 ++- .../utility/memory.hpp | 22 + .../package.xml | 1 + .../src/concatenate_data/cloud_collector.cpp | 96 +++- .../combine_cloud_handler.cpp | 410 +++++++++++++++--- .../combine_cloud_handler_kernel.cu | 57 +++ .../concatenate_and_time_sync_node.cpp | 355 ++++++++++++--- .../src/utility/memory.cpp | 98 +++-- .../test/test_concatenate_node_unit.cpp | 28 +- 14 files changed, 1122 insertions(+), 219 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler_kernel.hpp create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler_kernel.cu diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index b4c49863fdba6..14dd278fc760a 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -13,11 +13,19 @@ find_package(Sophus REQUIRED) find_package(Boost REQUIRED) find_package(PCL REQUIRED) find_package(CGAL REQUIRED COMPONENTS Core) +find_package(CUDA) + +if(${CUDA_FOUND}) + add_definitions(-DUSE_CUDA) +else() + message("CUDA wat not found. Disabling CUDA-dependent functionalities") +endif() include_directories( include SYSTEM ${Boost_INCLUDE_DIRS} + ${CUDA_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ${Sophus_INCLUDE_DIRS} @@ -63,6 +71,14 @@ ament_target_dependencies(faster_voxel_grid_downsample_filter sensor_msgs ) +cuda_add_library(pointcloud_preprocessor_filter_cuda SHARED + src/concatenate_data/combine_cloud_handler_kernel.cu +) + +target_include_directories(pointcloud_preprocessor_filter_cuda PUBLIC + ${cuda_blackboard_INCLUDE_DIRS} +) + ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/concatenate_data/concatenate_and_time_sync_node.cpp src/concatenate_data/combine_cloud_handler.cpp @@ -93,8 +109,10 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED target_link_libraries(pointcloud_preprocessor_filter pointcloud_preprocessor_filter_base + pointcloud_preprocessor_filter_cuda faster_voxel_grid_downsample_filter ${Boost_LIBRARIES} + ${CUDA_LIBRARIES} ${OpenCV_LIBRARIES} ${Sophus_LIBRARIES} ${PCL_LIBRARIES} diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml index c5bd139e1e962..cbf3e0d64cd1c 100644 --- a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + use_cuda: false debug_mode: false has_static_tf_only: false rosbag_replay: false diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp index b90fd4a526632..855a181029ac7 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -25,33 +25,36 @@ namespace autoware::pointcloud_preprocessor { class PointCloudConcatenateDataSynchronizerComponent; + +template class CombineCloudHandler; +template class CloudCollector { public: CloudCollector( std::shared_ptr && ros2_parent_node, - std::shared_ptr & combine_cloud_handler, int num_of_clouds, - double timeout_sec, bool debug_mode); + std::shared_ptr> & combine_cloud_handler, + int num_of_clouds, double timeout_sec, bool debug_mode); void set_reference_timestamp(double timestamp, double noise_window); std::tuple get_reference_timestamp_boundary(); void process_pointcloud( - const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); + const std::string & topic_name, typename PointCloudMessage::ConstSharedPtr cloud); void concatenate_callback(); - ConcatenatedCloudResult concatenate_pointclouds( - std::unordered_map topic_to_cloud_map); + ConcatenatedCloudResult concatenate_pointclouds( + std::unordered_map topic_to_cloud_map); - std::unordered_map + std::unordered_map get_topic_to_cloud_map(); private: std::shared_ptr ros2_parent_node_; - std::shared_ptr combine_cloud_handler_; + std::shared_ptr> combine_cloud_handler_; rclcpp::TimerBase::SharedPtr timer_; - std::unordered_map topic_to_cloud_map_; + std::unordered_map topic_to_cloud_map_; uint64_t num_of_clouds_; double timeout_sec_; double reference_timestamp_min_{0.0}; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp index 41a643fa81e74..856359f860038 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include @@ -43,12 +44,20 @@ #include #include +#ifdef USE_CUDA +#include +#endif + namespace autoware::pointcloud_preprocessor { using autoware::point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; -struct ConcatenatedCloudResult +template +struct ConcatenatedCloudResult; + +template <> +struct ConcatenatedCloudResult { sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr{nullptr}; std::optional> @@ -56,9 +65,20 @@ struct ConcatenatedCloudResult std::unordered_map topic_to_original_stamp_map; }; -class CombineCloudHandler +#ifdef USE_CUDA +template <> +struct ConcatenatedCloudResult +{ + cuda_blackboard::CudaPointCloud2::UniquePtr concatenate_cloud_ptr{nullptr}; + std::optional> + topic_to_transformed_cloud_map; + std::unordered_map topic_to_original_stamp_map; +}; +#endif + +class CombineCloudHandlerBase { -private: +protected: rclcpp::Node & node_; std::vector input_topics_; @@ -80,9 +100,41 @@ class CombineCloudHandler } }; +public: + CombineCloudHandlerBase( + rclcpp::Node & node, std::vector input_topics, std::string output_frame, + bool is_motion_compensated, bool publish_synchronized_pointcloud, + bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only); + + virtual ~CombineCloudHandlerBase() = default; + + void process_twist( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg); + + void process_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input); + + Eigen::Matrix4f compute_transform_to_adjust_for_old_timestamp( + const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); + + std::deque get_twist_queue(); +}; + +template +class CombineCloudHandler : public CombineCloudHandlerBase +{ +public: + ConcatenatedCloudResult combine_pointclouds( + std::unordered_map & + topic_to_cloud_map); +}; + +template <> +class CombineCloudHandler : public CombineCloudHandlerBase +{ +protected: static void convert_to_xyzirc_cloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_cloud, - sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud); + const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud, + typename sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud); void correct_pointcloud_motion( const std::shared_ptr & transformed_cloud_ptr, @@ -95,16 +147,44 @@ class CombineCloudHandler rclcpp::Node & node, std::vector input_topics, std::string output_frame, bool is_motion_compensated, bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only); - void process_twist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & input); - void process_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr & input); - ConcatenatedCloudResult combine_pointclouds( - std::unordered_map & topic_to_cloud_map); + ConcatenatedCloudResult combine_pointclouds( + std::unordered_map & + topic_to_cloud_map); +}; - Eigen::Matrix4f compute_transform_to_adjust_for_old_timestamp( - const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); +#ifdef USE_CUDA - std::deque get_twist_queue(); +template <> +class CombineCloudHandler : public CombineCloudHandlerBase +{ +protected: + struct CudaConcatStruct + { + cudaStream_t stream; + std::unique_ptr cloud_ptr; + std::size_t max_pointcloud_size_{0}; + }; + + std::unordered_map cuda_concat_struct_map_; + std::unique_ptr concatenated_cloud_ptr; + std::size_t max_concat_pointcloud_size_{0}; + std::mutex mutex_; + +public: + CombineCloudHandler( + rclcpp::Node & node, std::vector input_topics, std::string output_frame, + bool is_motion_compensated, bool publish_synchronized_pointcloud, + bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only); + + void allocate_pointclouds(); + +public: + ConcatenatedCloudResult combine_pointclouds( + std::unordered_map & + topic_to_cloud_map); }; +#endif + } // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler_kernel.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler_kernel.hpp new file mode 100644 index 0000000000000..c9a284123315c --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler_kernel.hpp @@ -0,0 +1,61 @@ +// Copyright 2024 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. + +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_KERNEL_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_KERNEL_HPP_ + +#ifdef USE_CUDA +#include +#endif + +#include + +namespace autoware::pointcloud_preprocessor +{ + +struct TransformStruct +{ + float translation_x; + float translation_y; + float translation_z; + float m11; + float m12; + float m13; + float m21; + float m22; + float m23; + float m31; + float m32; + float m33; +}; + +struct PointTypeStruct +{ + float x; + float y; + float z; + std::uint8_t intensity; + std::uint8_t return_type; + std::uint16_t channel; +}; + +#ifdef USE_CUDA +void transform_launch( + const PointTypeStruct * input_points, int num_points, TransformStruct transform, + PointTypeStruct * output_points, cudaStream_t & stream); +#endif + +} // namespace autoware::pointcloud_preprocessor + +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__COMBINE_CLOUD_HANDLER_KERNEL_HPP_ diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp index 3e6febbdbe844..ca56ca5a0678d 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -45,6 +45,12 @@ #include #include +#ifdef USE_CUDA +#include +#include +#include +#endif + namespace autoware::pointcloud_preprocessor { class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node @@ -52,16 +58,34 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node public: explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); ~PointCloudConcatenateDataSynchronizerComponent() override = default; + + template + bool publish_clouds_preprocess( + const ConcatenatedCloudResult & concatenated_cloud_result); + + template + void publish_clouds_postprocess( + const ConcatenatedCloudResult & concatenated_cloud_result, + double reference_timestamp_min, double reference_timestamp_max); + + template void publish_clouds( - ConcatenatedCloudResult && concatenated_cloud_result, double reference_timestamp_min, - double reference_timestamp_max); - void delete_collector(CloudCollector & cloud_collector); - std::list> get_cloud_collectors(); - void add_cloud_collector(const std::shared_ptr & collector); + ConcatenatedCloudResult && concatenated_cloud_result, + double reference_timestamp_min, double reference_timestamp_max); + + template + void delete_collector(CloudCollector & cloud_collector); + + template + std::list>> get_cloud_collectors(); + + template + void add_cloud_collector(const std::shared_ptr> & collector); private: struct Parameters { + bool use_cuda; bool debug_mode; bool has_static_tf_only; bool rosbag_replay; @@ -88,8 +112,14 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node double diagnostic_reference_timestamp_max_{0.0}; std::unordered_map diagnostic_topic_to_original_stamp_map_; - std::shared_ptr combine_cloud_handler_; - std::list> cloud_collectors_; + std::shared_ptr combine_cloud_handler_; + std::list>> cloud_collectors_; + +#ifdef USE_CUDA + std::list>> + cuda_cloud_collectors_; +#endif + std::mutex cloud_collectors_mutex_; std::unordered_map topic_to_offset_map_; std::unordered_map topic_to_noise_window_map_; @@ -98,11 +128,24 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node static constexpr const char * default_sync_topic_postfix = "_synchronized"; // subscribers +#ifdef USE_CUDA + std::vector< + std::shared_ptr>> + cuda_pointcloud_subs_; +#endif std::vector::SharedPtr> pointcloud_subs_; rclcpp::Subscription::SharedPtr twist_sub_; rclcpp::Subscription::SharedPtr odom_sub_; // publishers +#ifdef USE_CUDA + std::shared_ptr> + cuda_concatenated_cloud_publisher_; + std::unordered_map< + std::string, + std::shared_ptr>> + topic_to_transformed_cuda_cloud_publisher_map_; +#endif rclcpp::Publisher::SharedPtr concatenated_cloud_publisher_; std::unordered_map::SharedPtr> topic_to_transformed_cloud_publisher_map_; @@ -111,8 +154,20 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unique_ptr> stop_watch_ptr_; diagnostic_updater::Updater diagnostic_updater_{this}; + template + bool cloud_callback_preprocess( + const typename PointCloudMessage::ConstSharedPtr & input_ptr, const std::string & topic_name); + void cloud_callback( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name); + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, + const std::string & topic_name); + +#ifdef USE_CUDA + void cuda_cloud_callback( + const cuda_blackboard::CudaPointCloud2::ConstSharedPtr & input_ptr, + const std::string & topic_name); +#endif + void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input); void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp index 4810c5ce84130..db8b440be8126 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp @@ -17,20 +17,42 @@ #include +#include + namespace autoware::pointcloud_preprocessor::utils { +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to + * say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */ +bool is_data_layout_compatible_with_point_xyzi( + const std::vector & fields); + /** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to * say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */ bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input); +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is + * to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRC */ +bool is_data_layout_compatible_with_point_xyzirc( + const std::vector & fields); + /** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is * to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRC */ bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCloud2 & input); +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRADRT. That + * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */ +bool is_data_layout_compatible_with_point_xyziradrt( + const std::vector & fields); + /** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRADRT. That * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */ bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::PointCloud2 & input); +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT. That + * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */ +bool is_data_layout_compatible_with_point_xyzircaedt( + const std::vector & fields); + /** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT. That * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */ bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input); diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 85e42b4291626..8764dc38c6412 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -31,6 +31,7 @@ autoware_point_types autoware_universe_utils cgal + cuda_blackboard cv_bridge diagnostic_updater image_transport diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp index b0a7f746be778..277d89335eea6 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -19,15 +19,20 @@ #include +#ifdef USE_CUDA +#include +#endif + #include namespace autoware::pointcloud_preprocessor { -CloudCollector::CloudCollector( +template +CloudCollector::CloudCollector( std::shared_ptr && ros2_parent_node, - std::shared_ptr & combine_cloud_handler, int num_of_clouds, - double timeout_sec, bool debug_mode) + std::shared_ptr> & combine_cloud_handler, + int num_of_clouds, double timeout_sec, bool debug_mode) : ros2_parent_node_(std::move(ros2_parent_node)), combine_cloud_handler_(combine_cloud_handler), num_of_clouds_(num_of_clouds), @@ -42,19 +47,23 @@ CloudCollector::CloudCollector( std::bind(&CloudCollector::concatenate_callback, this)); } -void CloudCollector::set_reference_timestamp(double timestamp, double noise_window) +template +void CloudCollector::set_reference_timestamp( + double timestamp, double noise_window) { reference_timestamp_max_ = timestamp + noise_window; reference_timestamp_min_ = timestamp - noise_window; } -std::tuple CloudCollector::get_reference_timestamp_boundary() +template +std::tuple CloudCollector::get_reference_timestamp_boundary() { return std::make_tuple(reference_timestamp_min_, reference_timestamp_max_); } -void CloudCollector::process_pointcloud( - const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) +template +void CloudCollector::process_pointcloud( + const std::string & topic_name, typename PointCloudMessage::ConstSharedPtr cloud) { // Check if the map already contains an entry for the same topic. This shouldn't happen if the // parameter 'lidar_timestamp_noise_window' is set correctly. @@ -71,7 +80,18 @@ void CloudCollector::process_pointcloud( } } -void CloudCollector::concatenate_callback() +template +void CloudCollector::concatenate_callback() +{ + static_assert( + std::is_same::value || + std::is_same::value, + "This function is only available for sensor_msgs::msg::PointCloud2 and " + "cuda_blackboard::CudaPointCloud2"); +} + +template <> +void CloudCollector::concatenate_callback() { if (debug_mode_) { auto time_until_trigger = timer_->time_until_trigger(); @@ -110,16 +130,68 @@ void CloudCollector::concatenate_callback() ros2_parent_node_->delete_collector(*this); } -ConcatenatedCloudResult CloudCollector::concatenate_pointclouds( - std::unordered_map topic_to_cloud_map) +#ifdef USE_CUDA + +template <> +void CloudCollector::concatenate_callback() +{ + if (debug_mode_) { + auto time_until_trigger = timer_->time_until_trigger(); + std::stringstream log_stream; + log_stream << std::fixed << std::setprecision(6); + log_stream << "Collector's concatenate callback time: " + << ros2_parent_node_->get_clock()->now().seconds() << " seconds\n"; + + log_stream << "Collector's reference time min: " << reference_timestamp_min_ + << " to max: " << reference_timestamp_max_ << " seconds\n"; + + log_stream << "Time until trigger: " << (time_until_trigger.count() / 1e9) << " seconds\n"; + + log_stream << "Pointclouds: ["; + std::string separator = ""; + for (const auto & [topic, cloud] : topic_to_cloud_map_) { + log_stream << separator; + log_stream << "[" << topic << ", " << rclcpp::Time(cloud->header.stamp).seconds() << "]"; + separator = ", "; + } + + log_stream << "]\n"; + + RCLCPP_INFO(ros2_parent_node_->get_logger(), "%s", log_stream.str().c_str()); + } + + // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the + // pointclouds in the collector. + timer_->cancel(); + + auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); + + ros2_parent_node_->publish_clouds( + std::move(concatenated_cloud_result), reference_timestamp_min_, reference_timestamp_max_); + + ros2_parent_node_->delete_collector(*this); +} +#endif + +template +ConcatenatedCloudResult +CloudCollector::concatenate_pointclouds( + std::unordered_map topic_to_cloud_map) { return combine_cloud_handler_->combine_pointclouds(topic_to_cloud_map); } -std::unordered_map -CloudCollector::get_topic_to_cloud_map() +template +std::unordered_map +CloudCollector::get_topic_to_cloud_map() { return topic_to_cloud_map_; } } // namespace autoware::pointcloud_preprocessor + +template class autoware::pointcloud_preprocessor::CloudCollector; + +#ifdef USE_CUDA +template class autoware::pointcloud_preprocessor::CloudCollector; +#endif diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp index 135ab943bebd4..a2e049c72711d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -14,19 +14,58 @@ #include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" +#ifdef USE_CUDA +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler_kernel.hpp" +#endif + #include #include +#ifdef USE_CUDA +#include + +#include +#endif + #include #include #include #include +#ifdef USE_CUDA + +#define CHECK_OFFSET(structure1, structure2, field) \ + static_assert( \ + offsetof(structure1, field) == offsetof(structure2, field), \ + "Offset of " #field " in " #structure1 " does not match expected offset.") + +static_assert( + sizeof(autoware::pointcloud_preprocessor::PointTypeStruct) == + sizeof(autoware::point_types::PointXYZIRC)); + +CHECK_OFFSET( + autoware::pointcloud_preprocessor::PointTypeStruct, autoware::point_types::PointXYZIRCAEDT, x); +CHECK_OFFSET( + autoware::pointcloud_preprocessor::PointTypeStruct, autoware::point_types::PointXYZIRCAEDT, y); +CHECK_OFFSET( + autoware::pointcloud_preprocessor::PointTypeStruct, autoware::point_types::PointXYZIRCAEDT, z); +CHECK_OFFSET( + autoware::pointcloud_preprocessor::PointTypeStruct, autoware::point_types::PointXYZIRCAEDT, + intensity); +CHECK_OFFSET( + autoware::pointcloud_preprocessor::PointTypeStruct, autoware::point_types::PointXYZIRCAEDT, + return_type); +CHECK_OFFSET( + autoware::pointcloud_preprocessor::PointTypeStruct, autoware::point_types::PointXYZIRCAEDT, + channel); + +#endif + namespace autoware::pointcloud_preprocessor { -CombineCloudHandler::CombineCloudHandler( +CombineCloudHandlerBase::CombineCloudHandlerBase( rclcpp::Node & node, std::vector input_topics, std::string output_frame, bool is_motion_compensated, bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only) @@ -41,7 +80,7 @@ CombineCloudHandler::CombineCloudHandler( { } -void CombineCloudHandler::process_twist( +void CombineCloudHandlerBase::process_twist( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg) { geometry_msgs::msg::TwistStamped msg; @@ -68,7 +107,7 @@ void CombineCloudHandler::process_twist( twist_queue_.push_back(msg); } -void CombineCloudHandler::process_odometry( +void CombineCloudHandlerBase::process_odometry( const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_msg) { geometry_msgs::msg::TwistStamped msg; @@ -95,14 +134,91 @@ void CombineCloudHandler::process_odometry( twist_queue_.push_back(msg); } -std::deque CombineCloudHandler::get_twist_queue() +std::deque CombineCloudHandlerBase::get_twist_queue() { return twist_queue_; } -void CombineCloudHandler::convert_to_xyzirc_cloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_cloud, - sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud) +Eigen::Matrix4f CombineCloudHandlerBase::compute_transform_to_adjust_for_old_timestamp( + const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) +{ + // return identity if no twist is available + if (twist_queue_.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), + "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud " + "untransformed."); + return Eigen::Matrix4f::Identity(); + } + + auto old_twist_it = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), old_stamp, + [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { + return rclcpp::Time(x.header.stamp) < t; + }); + old_twist_it = old_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : old_twist_it; + + auto new_twist_it = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), new_stamp, + [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { + return rclcpp::Time(x.header.stamp) < t; + }); + new_twist_it = new_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : new_twist_it; + + auto prev_time = old_stamp; + double x = 0.0; + double y = 0.0; + double yaw = 0.0; + tf2::Quaternion baselink_quat{}; + for (auto twist_it = old_twist_it; twist_it != new_twist_it + 1; ++twist_it) { + const double dt = + (twist_it != new_twist_it) + ? (rclcpp::Time((*twist_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( + node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), + "Time difference is too large. Cloud not interpolate. Please confirm twist topic and " + "timestamp"); + break; + } + + const double distance = (*twist_it).twist.linear.x * dt; + yaw += (*twist_it).twist.angular.z * dt; + x += distance * std::cos(yaw); + y += distance * std::sin(yaw); + prev_time = (*twist_it).header.stamp; + } + + Eigen::Matrix4f transformation_matrix = Eigen::Matrix4f::Identity(); + + float cos_yaw = std::cos(yaw); + float sin_yaw = std::sin(yaw); + + transformation_matrix(0, 3) = x; + transformation_matrix(1, 3) = y; + transformation_matrix(0, 0) = cos_yaw; + transformation_matrix(0, 1) = -sin_yaw; + transformation_matrix(1, 0) = sin_yaw; + transformation_matrix(1, 1) = cos_yaw; + + return transformation_matrix; +} + +CombineCloudHandler::CombineCloudHandler( + rclcpp::Node & node, std::vector input_topics, std::string output_frame, + bool is_motion_compensated, bool publish_synchronized_pointcloud, + bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only) +: CombineCloudHandlerBase( + node, input_topics, output_frame, is_motion_compensated, publish_synchronized_pointcloud, + keep_input_frame_in_synchronized_pointcloud, has_static_tf_only) +{ +} + +void CombineCloudHandler::convert_to_xyzirc_cloud( + const typename sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud, + typename sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud) { xyzirc_cloud->header = input_cloud->header; @@ -125,14 +241,14 @@ void CombineCloudHandler::convert_to_xyzirc_cloud( return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; }); - sensor_msgs::PointCloud2Iterator it_x(*input_cloud, "x"); - sensor_msgs::PointCloud2Iterator it_y(*input_cloud, "y"); - sensor_msgs::PointCloud2Iterator it_z(*input_cloud, "z"); + sensor_msgs::PointCloud2ConstIterator it_x(*input_cloud, "x"); + sensor_msgs::PointCloud2ConstIterator it_y(*input_cloud, "y"); + sensor_msgs::PointCloud2ConstIterator it_z(*input_cloud, "z"); if (has_valid_intensity && has_valid_return_type && has_valid_channel) { - sensor_msgs::PointCloud2Iterator it_i(*input_cloud, "intensity"); - sensor_msgs::PointCloud2Iterator it_r(*input_cloud, "return_type"); - sensor_msgs::PointCloud2Iterator it_c(*input_cloud, "channel"); + sensor_msgs::PointCloud2ConstIterator it_i(*input_cloud, "intensity"); + sensor_msgs::PointCloud2ConstIterator it_r(*input_cloud, "return_type"); + sensor_msgs::PointCloud2ConstIterator it_c(*input_cloud, "channel"); for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { PointXYZIRC point; @@ -155,7 +271,7 @@ void CombineCloudHandler::convert_to_xyzirc_cloud( } } -void CombineCloudHandler::correct_pointcloud_motion( +void CombineCloudHandler::correct_pointcloud_motion( const std::shared_ptr & transformed_cloud_ptr, const std::vector & pc_stamps, std::unordered_map & transform_memo, @@ -181,10 +297,13 @@ void CombineCloudHandler::correct_pointcloud_motion( adjust_to_old_data_transform, *transformed_cloud_ptr, *transformed_delay_compensated_cloud_ptr); } -ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( - std::unordered_map & topic_to_cloud_map) +/* template<> */ +ConcatenatedCloudResult +CombineCloudHandler::combine_pointclouds( + std::unordered_map & + topic_to_cloud_map) { - ConcatenatedCloudResult concatenate_cloud_result; + ConcatenatedCloudResult concatenate_cloud_result; std::vector pc_stamps; for (const auto & [topic, cloud] : topic_to_cloud_map) { @@ -236,7 +355,7 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( if (!concatenate_cloud_result.topic_to_transformed_cloud_map) { // Initialize the map if it is not present concatenate_cloud_result.topic_to_transformed_cloud_map = - std::unordered_map(); + std::unordered_map(); } // convert to original sensor frame if necessary bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); @@ -264,71 +383,222 @@ ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( return concatenate_cloud_result; } -Eigen::Matrix4f CombineCloudHandler::compute_transform_to_adjust_for_old_timestamp( - const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) +#ifdef USE_CUDA + +CombineCloudHandler::CombineCloudHandler( + rclcpp::Node & node, std::vector input_topics, std::string output_frame, + bool is_motion_compensated, bool publish_synchronized_pointcloud, + bool keep_input_frame_in_synchronized_pointcloud, bool has_static_tf_only) +: CombineCloudHandlerBase( + node, input_topics, output_frame, is_motion_compensated, publish_synchronized_pointcloud, + keep_input_frame_in_synchronized_pointcloud, has_static_tf_only) { - // return identity if no twist is available - if (twist_queue_.empty()) { - RCLCPP_WARN_STREAM_THROTTLE( - node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), - "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud " - "untransformed."); - return Eigen::Matrix4f::Identity(); + for (const auto & topic : input_topics_) { + CudaConcatStruct cuda_concat_struct; + cudaStreamCreate(&cuda_concat_struct.stream); + cuda_concat_struct_map_[topic] = std::move(cuda_concat_struct); } +} - auto old_twist_it = std::lower_bound( - std::begin(twist_queue_), std::end(twist_queue_), old_stamp, - [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { - return rclcpp::Time(x.header.stamp) < t; - }); - old_twist_it = old_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : old_twist_it; +void CombineCloudHandler::allocate_pointclouds() +{ + std::lock_guard lock(mutex_); - auto new_twist_it = std::lower_bound( - std::begin(twist_queue_), std::end(twist_queue_), new_stamp, - [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { - return rclcpp::Time(x.header.stamp) < t; - }); - new_twist_it = new_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : new_twist_it; + for (const auto & topic : input_topics_) { + auto & concat_struct = cuda_concat_struct_map_[topic]; + concat_struct.cloud_ptr = std::make_unique(); + concat_struct.cloud_ptr->data = + cuda_blackboard::make_unique(concat_struct.max_pointcloud_size_); + } - auto prev_time = old_stamp; - double x = 0.0; - double y = 0.0; - double yaw = 0.0; - tf2::Quaternion baselink_quat{}; - for (auto twist_it = old_twist_it; twist_it != new_twist_it + 1; ++twist_it) { - const double dt = - (twist_it != new_twist_it) - ? (rclcpp::Time((*twist_it).header.stamp) - rclcpp::Time(prev_time)).seconds() - : (rclcpp::Time(new_stamp) - rclcpp::Time(prev_time)).seconds(); + concatenated_cloud_ptr = std::make_unique(); + concatenated_cloud_ptr->data = cuda_blackboard::make_unique( + max_concat_pointcloud_size_ * input_topics_.size()); +} - if (std::fabs(dt) > 0.1) { - RCLCPP_WARN_STREAM_THROTTLE( - node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), - "Time difference is too large. Cloud not interpolate. Please confirm twist topic and " - "timestamp"); - break; +ConcatenatedCloudResult +CombineCloudHandler::combine_pointclouds( + std::unordered_map & + topic_to_cloud_map) +{ + ConcatenatedCloudResult concatenate_cloud_result; + std::lock_guard lock(mutex_); + + std::vector pc_stamps; + for (const auto & [topic, cloud] : topic_to_cloud_map) { + pc_stamps.emplace_back(cloud->header.stamp); + } + std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); + auto oldest_stamp = pc_stamps.back(); + + // Before combining the pointclouds, initialize and reserve space for the concatenated pointcloud + concatenate_cloud_result.concatenate_cloud_ptr = + std::make_unique(); + + // Reserve space based on the total size of the pointcloud data to speed up the concatenation + // process + size_t total_data_size = 0; + size_t total_points = 0; + for (const auto & [topic, cloud] : topic_to_cloud_map) { + total_data_size += (cloud->height * cloud->row_step); + total_points += (cloud->height * cloud->width); + } + + const auto point_fields = topic_to_cloud_map.begin()->second->fields; + + if (total_data_size > max_concat_pointcloud_size_ || !concatenated_cloud_ptr) { + max_concat_pointcloud_size_ = (total_data_size + 1024) / 1024 * 1024; + concatenated_cloud_ptr = std::make_unique(); + concatenated_cloud_ptr->data = cuda_blackboard::make_unique( + max_concat_pointcloud_size_ * input_topics_.size()); + } + + concatenate_cloud_result.concatenate_cloud_ptr = std::move(concatenated_cloud_ptr); + + PointTypeStruct * output_points = + reinterpret_cast(concatenate_cloud_result.concatenate_cloud_ptr->data.get()); + std::size_t concatenated_start_index = 0; + + for (const auto & [topic, cloud] : topic_to_cloud_map) { + const std::size_t num_points = cloud->height * cloud->width; + + // Compute motion compensation transform + Eigen::Matrix4f transform = Eigen::Matrix4f::Identity(); + + // Transform if needed + managed_tf_buffer_->getTransform(output_frame_, cloud->header.frame_id, transform); + + rclcpp::Time current_cloud_stamp = rclcpp::Time(cloud->header.stamp); + + if (is_motion_compensated_) { + transform = compute_transform_to_adjust_for_old_timestamp(oldest_stamp, current_cloud_stamp) * + transform; } - const double distance = (*twist_it).twist.linear.x * dt; - yaw += (*twist_it).twist.angular.z * dt; - x += distance * std::cos(yaw); - y += distance * std::sin(yaw); - prev_time = (*twist_it).header.stamp; + TransformStruct transform_struct; + transform_struct.translation_x = transform(0, 3); + transform_struct.translation_y = transform(1, 3); + transform_struct.translation_z = transform(2, 3); + transform_struct.m11 = transform(0, 0); + transform_struct.m12 = transform(0, 1); + transform_struct.m13 = transform(0, 2); + transform_struct.m21 = transform(1, 0); + transform_struct.m22 = transform(1, 1); + transform_struct.m23 = transform(1, 2); + transform_struct.m31 = transform(2, 0); + transform_struct.m32 = transform(2, 1); + transform_struct.m33 = transform(2, 2); + + auto & stream = cuda_concat_struct_map_[topic].stream; + + cudaMemset(output_points + concatenated_start_index, 222, num_points); + + // Apply the kernel to the pointclouds + transform_launch( + reinterpret_cast(cloud->data.get()), num_points, transform_struct, + output_points + concatenated_start_index, stream); + concatenated_start_index += num_points; } - Eigen::Matrix4f transformation_matrix = Eigen::Matrix4f::Identity(); + concatenate_cloud_result.concatenate_cloud_ptr->header.frame_id = output_frame_; + concatenate_cloud_result.concatenate_cloud_ptr->width = concatenated_start_index; + concatenate_cloud_result.concatenate_cloud_ptr->height = 1; + concatenate_cloud_result.concatenate_cloud_ptr->point_step = sizeof(PointTypeStruct); + concatenate_cloud_result.concatenate_cloud_ptr->row_step = + concatenated_start_index * sizeof(PointTypeStruct); + concatenate_cloud_result.concatenate_cloud_ptr->fields = point_fields; + concatenate_cloud_result.concatenate_cloud_ptr->is_bigendian = false; + concatenate_cloud_result.concatenate_cloud_ptr->is_dense = true; + + // Second round is for when we need to publish sync pointclouds + if (publish_synchronized_pointcloud_) { + if (!concatenate_cloud_result.topic_to_transformed_cloud_map) { + // Initialize the map if it is not present + concatenate_cloud_result.topic_to_transformed_cloud_map = + std::unordered_map(); + } - float cos_yaw = std::cos(yaw); - float sin_yaw = std::sin(yaw); + concatenated_start_index = 0; - transformation_matrix(0, 3) = x; - transformation_matrix(1, 3) = y; - transformation_matrix(0, 0) = cos_yaw; - transformation_matrix(0, 1) = -sin_yaw; - transformation_matrix(1, 0) = sin_yaw; - transformation_matrix(1, 1) = cos_yaw; + for (const auto & [topic, cloud] : topic_to_cloud_map) { + const std::size_t num_points = cloud->height * cloud->width; + const std::size_t data_size = cloud->height * cloud->row_step; - return transformation_matrix; + auto & concat_struct = cuda_concat_struct_map_[topic]; + + if (data_size > concat_struct.max_pointcloud_size_ || !concat_struct.cloud_ptr) { + concat_struct.max_pointcloud_size_ = (data_size + 1024) / 1024 * 1024; + concat_struct.cloud_ptr = std::make_unique(); + concat_struct.cloud_ptr->data = cuda_blackboard::make_unique(data_size); + } + // convert to original sensor frame if necessary + + auto & output_cloud = (*concatenate_cloud_result.topic_to_transformed_cloud_map)[topic]; + bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); + + output_cloud = std::move(concat_struct.cloud_ptr); + + auto & stream = cuda_concat_struct_map_[topic].stream; + + if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { + Eigen::Matrix4f transform; + managed_tf_buffer_->getTransform(cloud->header.frame_id, output_frame_, transform); + + TransformStruct transform_struct; + transform_struct.translation_x = transform(0, 3); + transform_struct.translation_y = transform(1, 3); + transform_struct.translation_z = transform(2, 3); + transform_struct.m11 = transform(0, 0); + transform_struct.m12 = transform(0, 1); + transform_struct.m13 = transform(0, 2); + transform_struct.m21 = transform(1, 0); + transform_struct.m22 = transform(1, 1); + transform_struct.m23 = transform(1, 2); + transform_struct.m31 = transform(2, 0); + transform_struct.m32 = transform(2, 1); + transform_struct.m33 = transform(2, 2); + + transform_launch( + output_points + concatenated_start_index, num_points, transform_struct, + reinterpret_cast(output_cloud->data.get()), stream); + output_cloud->header.frame_id = cloud->header.frame_id; + } else { + cudaMemcpyAsync( + output_cloud->data.get(), output_points + concatenated_start_index, data_size, + cudaMemcpyDeviceToDevice, stream); + output_cloud->header.frame_id = output_frame_; + } + + output_cloud->header.stamp = cloud->header.stamp; + output_cloud->width = cloud->width; + output_cloud->height = cloud->height; + output_cloud->point_step = sizeof(PointTypeStruct); + output_cloud->row_step = cloud->width * sizeof(PointTypeStruct); + output_cloud->fields = point_fields; + output_cloud->is_bigendian = false; + output_cloud->is_dense = true; + + concatenated_start_index += cloud->height * cloud->width; + } + } + + // Sync all streams + for (const auto & [topic, cuda_concat_struct] : cuda_concat_struct_map_) { + cudaStreamSynchronize(cuda_concat_struct.stream); + } + + concatenate_cloud_result.concatenate_cloud_ptr->header.stamp = oldest_stamp; + + return concatenate_cloud_result; } +#endif } // namespace autoware::pointcloud_preprocessor + +template class autoware::pointcloud_preprocessor::CombineCloudHandler< + sensor_msgs::msg::PointCloud2>; + +#ifdef USE_CUDA +template class autoware::pointcloud_preprocessor::CombineCloudHandler< + cuda_blackboard::CudaPointCloud2>; +#endif diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler_kernel.cu b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler_kernel.cu new file mode 100644 index 0000000000000..497d7e26f6459 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler_kernel.cu @@ -0,0 +1,57 @@ +// Copyright 2024 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. + +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler_kernel.hpp" + +#include + +#include + +namespace autoware::pointcloud_preprocessor +{ + +__global__ void transform_kernel( + const PointTypeStruct * input_points, int num_points, TransformStruct transform, + PointTypeStruct * output_points) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx < num_points) { + float x = input_points[idx].x; + float y = input_points[idx].y; + float z = input_points[idx].z; + + output_points[idx].x = + transform.m11 * x + transform.m12 * y + transform.m13 * z + transform.translation_x; + output_points[idx].y = + transform.m21 * x + transform.m22 * y + transform.m23 * z + transform.translation_y; + output_points[idx].z = + transform.m31 * x + transform.m32 * y + transform.m33 * z + transform.translation_z; + output_points[idx].intensity = input_points[idx].intensity; + output_points[idx].return_type = input_points[idx].return_type; + output_points[idx].channel = input_points[idx].channel; + } +} + +void transform_launch( + const PointTypeStruct * input_points, int num_points, TransformStruct transform, + PointTypeStruct * output_points, cudaStream_t & stream) +{ + int threadsPerBlock = 256; + int blocksPerGrid = (num_points + threadsPerBlock - 1) / threadsPerBlock; + + transform_kernel<<>>( + input_points, num_points, transform, output_points); +} + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp index 219f391b58b22..8850ac7933606 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -44,6 +44,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro stop_watch_ptr_->tic("processing_time"); // initialize parameters + params_.use_cuda = declare_parameter("use_cuda"); params_.debug_mode = declare_parameter("debug_mode"); params_.has_static_tf_only = declare_parameter("has_static_tf_only"); params_.rosbag_replay = declare_parameter("rosbag_replay"); @@ -67,6 +68,12 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro params_.lidar_timestamp_noise_window = declare_parameter>("lidar_timestamp_noise_window"); +#ifndef USE_CUDA + if (use_cuda) { + throw std::runtime_error("Attempted to use CUDA functionalities but CUDA is not available."); + } +#endif + if (params_.input_topics.empty()) { throw std::runtime_error("Need a 'input_topics' parameter to be set before continuing."); } @@ -92,19 +99,38 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } // Publishers - concatenated_cloud_publisher_ = this->create_publisher( - "output", rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + if (!params_.use_cuda) { + concatenated_cloud_publisher_ = this->create_publisher( + "output", rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + + // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud + if (params_.publish_synchronized_pointcloud) { + for (auto & topic : params_.input_topics) { + std::string new_topic = + replace_sync_topic_name_postfix(topic, params_.synchronized_pointcloud_postfix); + auto publisher = this->create_publisher( + new_topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + topic_to_transformed_cloud_publisher_map_.insert({topic, publisher}); + } + } + } + +#ifdef USE_CUDA + if (params_.use_cuda) { + cuda_concatenated_cloud_publisher_ = + std::make_shared>( + *this, "output"); - // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud - if (params_.publish_synchronized_pointcloud) { for (auto & topic : params_.input_topics) { std::string new_topic = replace_sync_topic_name_postfix(topic, params_.synchronized_pointcloud_postfix); - auto publisher = this->create_publisher( - new_topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); - topic_to_transformed_cloud_publisher_map_.insert({topic, publisher}); + auto publisher = std::make_shared< + cuda_blackboard::CudaBlackboardPublisher>( + *this, new_topic); + topic_to_transformed_cuda_cloud_publisher_map_.insert({topic, publisher}); } } +#endif // Subscribers if (params_.is_motion_compensated) { @@ -126,27 +152,59 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro } } - for (const std::string & topic : params_.input_topics) { - std::function callback = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1, - topic); + if (!params_.use_cuda) { + for (const std::string & topic : params_.input_topics) { + std::function callback = + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, + std::placeholders::_1, topic); - auto pointcloud_sub = this->create_subscription( - topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size), callback); - pointcloud_subs_.push_back(pointcloud_sub); - } - RCLCPP_DEBUG_STREAM( - get_logger(), - "Subscribing to " << params_.input_topics.size() << " user given topics as inputs:"); - for (const auto & input_topic : params_.input_topics) { - RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); + auto pointcloud_sub = this->create_subscription( + topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size), callback); + pointcloud_subs_.push_back(pointcloud_sub); + } + RCLCPP_DEBUG_STREAM( + get_logger(), + "Subscribing to " << params_.input_topics.size() << " user given topics as inputs:"); + for (const auto & input_topic : params_.input_topics) { + RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); + } + + // Combine cloud handler + combine_cloud_handler_ = std::make_shared>( + *this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, + params_.publish_synchronized_pointcloud, params_.keep_input_frame_in_synchronized_pointcloud, + params_.has_static_tf_only); } - // Combine cloud handler - combine_cloud_handler_ = std::make_shared( - *this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, - params_.publish_synchronized_pointcloud, params_.keep_input_frame_in_synchronized_pointcloud, - params_.has_static_tf_only); +#ifdef USE_CUDA + if (params_.use_cuda) { + for (const std::string & topic : params_.input_topics) { + std::function callback = + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::cuda_cloud_callback, this, + std::placeholders::_1, topic); + + auto cuda_pointcloud_sub = std::make_shared< + cuda_blackboard::CudaBlackboardSubscriber>( + *this, topic, false, callback); + cuda_pointcloud_subs_.push_back(cuda_pointcloud_sub); + } + RCLCPP_DEBUG_STREAM( + get_logger(), + "Subscribing to " << params_.input_topics.size() << " user given topics as inputs:"); + for (const auto & input_topic : params_.input_topics) { + RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); + } + + // Combine cloud handler + combine_cloud_handler_ = + std::make_shared>( + *this, params_.input_topics, params_.output_frame, params_.is_motion_compensated, + params_.publish_synchronized_pointcloud, + params_.keep_input_frame_in_synchronized_pointcloud, params_.has_static_tf_only); + } +#endif // Diagnostic Updater diagnostic_updater_.setHardwareID("concatenate_data_checker"); @@ -184,8 +242,9 @@ std::string PointCloudConcatenateDataSynchronizerComponent::replace_sync_topic_n return replaced_topic_name; } -void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name) +template +bool PointCloudConcatenateDataSynchronizerComponent::cloud_callback_preprocess( + const typename PointCloudMessage::ConstSharedPtr & input_ptr, const std::string & topic_name) { stop_watch_ptr_->toc("processing_time", true); if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { @@ -198,7 +257,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); } - return; + return false; } if (params_.debug_mode) { @@ -209,9 +268,18 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( this->get_clock()->now().seconds() - rclcpp::Time(input_ptr->header.stamp).seconds()); } - if (input_ptr->data.empty()) { + if (input_ptr->width * input_ptr->height == 0) { RCLCPP_WARN_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); + } + + return true; +} + +void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name) +{ + if (!cloud_callback_preprocess(input_ptr, topic_name)) { return; } @@ -239,11 +307,14 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( } } - // if point cloud didn't find matched collector, create a new collector. + // if the point cloud didn't find a matching collector, create a new one. if (!collector_found) { - auto new_cloud_collector = std::make_shared( + auto combine_cloud_handler = + std::dynamic_pointer_cast>( + combine_cloud_handler_); + auto new_cloud_collector = std::make_shared>( std::dynamic_pointer_cast(shared_from_this()), - combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec, params_.debug_mode); + combine_cloud_handler, params_.input_topics.size(), params_.timeout_sec, params_.debug_mode); cloud_collectors_.push_back(new_cloud_collector); cloud_collectors_lock.unlock(); @@ -254,6 +325,58 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( } } +#ifdef USE_CUDA +void PointCloudConcatenateDataSynchronizerComponent::cuda_cloud_callback( + const cuda_blackboard::CudaPointCloud2::ConstSharedPtr & input_ptr, + const std::string & topic_name) +{ + if (!cloud_callback_preprocess(input_ptr, topic_name)) { + return; + } + + // protect cloud collectors list + std::unique_lock cloud_collectors_lock(cloud_collectors_mutex_); + + // For each callback, check whether there is a exist collector that matches this cloud + bool collector_found = false; + + if (!cuda_cloud_collectors_.empty()) { + for (const auto & cuda_cloud_collector : cuda_cloud_collectors_) { + auto [reference_timestamp_min, reference_timestamp_max] = + cuda_cloud_collector->get_reference_timestamp_boundary(); + + if ( + rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] < + reference_timestamp_max + topic_to_noise_window_map_[topic_name] && + rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name] > + reference_timestamp_min - topic_to_noise_window_map_[topic_name]) { + cloud_collectors_lock.unlock(); + cuda_cloud_collector->process_pointcloud(topic_name, input_ptr); + collector_found = true; + break; + } + } + } + + // if the point cloud didn't find a matching collector, create a new one. + if (!collector_found) { + auto combine_cloud_handler = + std::dynamic_pointer_cast>( + combine_cloud_handler_); + auto new_cloud_collector = std::make_shared>( + std::dynamic_pointer_cast(shared_from_this()), + combine_cloud_handler, params_.input_topics.size(), params_.timeout_sec, params_.debug_mode); + + cuda_cloud_collectors_.push_back(new_cloud_collector); + cloud_collectors_lock.unlock(); + new_cloud_collector->set_reference_timestamp( + rclcpp::Time(input_ptr->header.stamp).seconds() - topic_to_offset_map_[topic_name], + topic_to_noise_window_map_[topic_name]); + new_cloud_collector->process_pointcloud(topic_name, input_ptr); + } +} +#endif + void PointCloudConcatenateDataSynchronizerComponent::twist_callback( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input) { @@ -266,14 +389,14 @@ void PointCloudConcatenateDataSynchronizerComponent::odom_callback( combine_cloud_handler_->process_odometry(input); } -void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( - ConcatenatedCloudResult && concatenated_cloud_result, double reference_timestamp_min, - double reference_timestamp_max) +template +bool PointCloudConcatenateDataSynchronizerComponent::publish_clouds_preprocess( + const ConcatenatedCloudResult & concatenated_cloud_result) { // should never come to this state. if (concatenated_cloud_result.concatenate_cloud_ptr == nullptr) { RCLCPP_ERROR(this->get_logger(), "Concatenate cloud is a nullptr."); - return; + return false; } current_concatenate_cloud_timestamp_ = rclcpp::Time(concatenated_cloud_result.concatenate_cloud_ptr->header.stamp).seconds(); @@ -295,6 +418,45 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( publish_pointcloud_ = true; } + return true; +} + +template +void PointCloudConcatenateDataSynchronizerComponent::publish_clouds_postprocess( + const ConcatenatedCloudResult & concatenated_cloud_result, + double reference_timestamp_min, double reference_timestamp_max) +{ + diagnostic_reference_timestamp_min_ = reference_timestamp_min; + diagnostic_reference_timestamp_max_ = reference_timestamp_max; + diagnostic_topic_to_original_stamp_map_ = concatenated_cloud_result.topic_to_original_stamp_map; + diagnostic_updater_.force_update(); + + // 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( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + + for (const auto & [topic, stamp] : concatenated_cloud_result.topic_to_original_stamp_map) { + const auto pipeline_latency_ms = (this->get_clock()->now().seconds() - stamp) * 1000; + debug_publisher_->publish( + "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); + } + } +} + +template <> +void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( + ConcatenatedCloudResult && concatenated_cloud_result, + double reference_timestamp_min, double reference_timestamp_max) +{ + if (!publish_clouds_preprocess(concatenated_cloud_result)) { + return; + } + if (publish_pointcloud_) { latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; auto concatenate_pointcloud_output = std::make_unique( @@ -323,30 +485,13 @@ void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( } } - diagnostic_reference_timestamp_min_ = reference_timestamp_min; - diagnostic_reference_timestamp_max_ = reference_timestamp_max; - diagnostic_topic_to_original_stamp_map_ = concatenated_cloud_result.topic_to_original_stamp_map; - diagnostic_updater_.force_update(); - - // 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( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); - - for (const auto & [topic, stamp] : concatenated_cloud_result.topic_to_original_stamp_map) { - const auto pipeline_latency_ms = (this->get_clock()->now().seconds() - stamp) * 1000; - debug_publisher_->publish( - "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); - } - } + publish_clouds_postprocess( + concatenated_cloud_result, reference_timestamp_min, reference_timestamp_max); } +template <> void PointCloudConcatenateDataSynchronizerComponent::delete_collector( - CloudCollector & cloud_collector) + CloudCollector & cloud_collector) { // protect cloud collectors list std::lock_guard cloud_collectors_lock(cloud_collectors_mutex_); @@ -354,7 +499,8 @@ void PointCloudConcatenateDataSynchronizerComponent::delete_collector( // change this to something else auto it = std::find_if( cloud_collectors_.begin(), cloud_collectors_.end(), - [&cloud_collector](const std::shared_ptr & collector) { + [&cloud_collector]( + const std::shared_ptr> & collector) { return collector.get() == &cloud_collector; }); if (it != cloud_collectors_.end()) { @@ -364,6 +510,77 @@ void PointCloudConcatenateDataSynchronizerComponent::delete_collector( } } +#ifdef USE_CUDA + +template <> +void PointCloudConcatenateDataSynchronizerComponent::publish_clouds< + cuda_blackboard::CudaPointCloud2>( + ConcatenatedCloudResult && concatenated_cloud_result, + double reference_timestamp_min, double reference_timestamp_max) +{ + if (!publish_clouds_preprocess(concatenated_cloud_result)) { + return; + } + + if (publish_pointcloud_) { + latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; + + cuda_concatenated_cloud_publisher_->publish( + std::move(concatenated_cloud_result.concatenate_cloud_ptr)); + + // publish transformed raw pointclouds + if ( + params_.publish_synchronized_pointcloud && + concatenated_cloud_result.topic_to_transformed_cloud_map) { + for (const auto & topic : params_.input_topics) { + // Get a reference to the internal map + if ( + (*concatenated_cloud_result.topic_to_transformed_cloud_map).find(topic) != + (*concatenated_cloud_result.topic_to_transformed_cloud_map).end()) { + topic_to_transformed_cuda_cloud_publisher_map_[topic]->publish( + std::move((*concatenated_cloud_result.topic_to_transformed_cloud_map).at(topic))); + } else { + RCLCPP_WARN( + this->get_logger(), + "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.", topic.c_str()); + } + } + } + } + + publish_clouds_postprocess( + concatenated_cloud_result, reference_timestamp_min, reference_timestamp_max); + + auto combine_cloud_handler = + std::dynamic_pointer_cast>( + combine_cloud_handler_); + + combine_cloud_handler->allocate_pointclouds(); +} + +template <> +void PointCloudConcatenateDataSynchronizerComponent::delete_collector( + CloudCollector & cuda_cloud_collector) +{ + // protect cloud collectors list + std::lock_guard cloud_collectors_lock(cloud_collectors_mutex_); + + // change this to something else + auto it = std::find_if( + cuda_cloud_collectors_.begin(), cuda_cloud_collectors_.end(), + [&cuda_cloud_collector]( + const std::shared_ptr> & collector) { + return collector.get() == &cuda_cloud_collector; + }); + if (it != cuda_cloud_collectors_.end()) { + cuda_cloud_collectors_.erase(it); + } else { + throw std::runtime_error("Try to delete a cloud_collector that is not in the cloud_collectors"); + } +} + +#endif + std::string PointCloudConcatenateDataSynchronizerComponent::format_timestamp(double timestamp) { std::ostringstream oss; @@ -428,18 +645,36 @@ void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( } } -std::list> +template <> +std::list>> PointCloudConcatenateDataSynchronizerComponent::get_cloud_collectors() { return cloud_collectors_; } +template <> void PointCloudConcatenateDataSynchronizerComponent::add_cloud_collector( - const std::shared_ptr & collector) + const std::shared_ptr> & collector) { cloud_collectors_.push_back(collector); } +#ifdef USE_CUDA +template <> +std::list>> +PointCloudConcatenateDataSynchronizerComponent::get_cloud_collectors() +{ + return cuda_cloud_collectors_; +} + +template <> +void PointCloudConcatenateDataSynchronizerComponent::add_cloud_collector( + const std::shared_ptr> & collector) +{ + cuda_cloud_collectors_.push_back(collector); +} +#endif + } // namespace autoware::pointcloud_preprocessor #include diff --git a/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp b/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp index c1fd55943d13a..675833f9d8c90 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp @@ -18,30 +18,31 @@ namespace autoware::pointcloud_preprocessor::utils { -bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input) +bool is_data_layout_compatible_with_point_xyzi( + const std::vector & fields) { using PointIndex = autoware::point_types::PointXYZIIndex; using autoware::point_types::PointXYZI; - if (input.fields.size() < 4) { + if (fields.size() < 4) { return false; } bool same_layout = true; - const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + const auto & field_x = fields.at(static_cast(PointIndex::X)); same_layout &= field_x.name == "x"; same_layout &= field_x.offset == offsetof(PointXYZI, x); same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_x.count == 1; - const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + const auto & field_y = fields.at(static_cast(PointIndex::Y)); same_layout &= field_y.name == "y"; same_layout &= field_y.offset == offsetof(PointXYZI, y); same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_y.count == 1; - const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + const auto & field_z = fields.at(static_cast(PointIndex::Z)); same_layout &= field_z.name == "z"; same_layout &= field_z.offset == offsetof(PointXYZI, z); same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_z.count == 1; - const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + const auto & field_intensity = fields.at(static_cast(PointIndex::Intensity)); same_layout &= field_intensity.name == "intensity"; same_layout &= field_intensity.offset == offsetof(PointXYZI, intensity); same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::FLOAT32; @@ -49,40 +50,46 @@ bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointClou return same_layout; } -bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCloud2 & input) +bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input) +{ + return is_data_layout_compatible_with_point_xyzi(input.fields); +} + +bool is_data_layout_compatible_with_point_xyzirc( + const std::vector & fields) { using PointIndex = autoware::point_types::PointXYZIRCIndex; using autoware::point_types::PointXYZIRC; - if (input.fields.size() < 6) { + if (fields.size() < 6) { return false; } bool same_layout = true; - const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + const auto & field_x = fields.at(static_cast(PointIndex::X)); same_layout &= field_x.name == "x"; same_layout &= field_x.offset == offsetof(PointXYZIRC, x); same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_x.count == 1; - const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + const auto & field_y = fields.at(static_cast(PointIndex::Y)); same_layout &= field_y.name == "y"; same_layout &= field_y.offset == offsetof(PointXYZIRC, y); same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_y.count == 1; - const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + const auto & field_z = fields.at(static_cast(PointIndex::Z)); same_layout &= field_z.name == "z"; same_layout &= field_z.offset == offsetof(PointXYZIRC, z); same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_z.count == 1; - const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + const auto & field_intensity = fields.at(static_cast(PointIndex::Intensity)); same_layout &= field_intensity.name == "intensity"; same_layout &= field_intensity.offset == offsetof(PointXYZIRC, intensity); same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::UINT8; same_layout &= field_intensity.count == 1; - const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); + const auto & field_return_type = fields.at(static_cast(PointIndex::ReturnType)); same_layout &= field_return_type.name == "return_type"; same_layout &= field_return_type.offset == offsetof(PointXYZIRC, return_type); same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; same_layout &= field_return_type.count == 1; - const auto & field_ring = input.fields.at(static_cast(PointIndex::Channel)); + const auto & field_ring = fields.at(static_cast(PointIndex::Channel)); same_layout &= field_ring.name == "channel"; same_layout &= field_ring.offset == offsetof(PointXYZIRC, channel); same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; @@ -91,55 +98,61 @@ bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCl return same_layout; } -bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::PointCloud2 & input) +bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCloud2 & input) +{ + return is_data_layout_compatible_with_point_xyzirc(input.fields); +} + +bool is_data_layout_compatible_with_point_xyziradrt( + const std::vector & fields) { using PointIndex = autoware::point_types::PointXYZIRADRTIndex; using autoware::point_types::PointXYZIRADRT; - if (input.fields.size() < 9) { + if (fields.size() < 9) { return false; } bool same_layout = true; - const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + const auto & field_x = fields.at(static_cast(PointIndex::X)); same_layout &= field_x.name == "x"; same_layout &= field_x.offset == offsetof(PointXYZIRADRT, x); same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_x.count == 1; - const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + const auto & field_y = fields.at(static_cast(PointIndex::Y)); same_layout &= field_y.name == "y"; same_layout &= field_y.offset == offsetof(PointXYZIRADRT, y); same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_y.count == 1; - const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + const auto & field_z = fields.at(static_cast(PointIndex::Z)); same_layout &= field_z.name == "z"; same_layout &= field_z.offset == offsetof(PointXYZIRADRT, z); same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_z.count == 1; - const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + const auto & field_intensity = fields.at(static_cast(PointIndex::Intensity)); same_layout &= field_intensity.name == "intensity"; same_layout &= field_intensity.offset == offsetof(PointXYZIRADRT, intensity); same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_intensity.count == 1; - const auto & field_ring = input.fields.at(static_cast(PointIndex::Ring)); + const auto & field_ring = fields.at(static_cast(PointIndex::Ring)); same_layout &= field_ring.name == "ring"; same_layout &= field_ring.offset == offsetof(PointXYZIRADRT, ring); same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; same_layout &= field_ring.count == 1; - const auto & field_azimuth = input.fields.at(static_cast(PointIndex::Azimuth)); + const auto & field_azimuth = fields.at(static_cast(PointIndex::Azimuth)); same_layout &= field_azimuth.name == "azimuth"; same_layout &= field_azimuth.offset == offsetof(PointXYZIRADRT, azimuth); same_layout &= field_azimuth.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_azimuth.count == 1; - const auto & field_distance = input.fields.at(static_cast(PointIndex::Distance)); + const auto & field_distance = fields.at(static_cast(PointIndex::Distance)); same_layout &= field_distance.name == "distance"; same_layout &= field_distance.offset == offsetof(PointXYZIRADRT, distance); same_layout &= field_distance.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_distance.count == 1; - const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); + const auto & field_return_type = fields.at(static_cast(PointIndex::ReturnType)); same_layout &= field_return_type.name == "return_type"; same_layout &= field_return_type.offset == offsetof(PointXYZIRADRT, return_type); same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; same_layout &= field_return_type.count == 1; - const auto & field_time_stamp = input.fields.at(static_cast(PointIndex::TimeStamp)); + const auto & field_time_stamp = fields.at(static_cast(PointIndex::TimeStamp)); same_layout &= field_time_stamp.name == "time_stamp"; same_layout &= field_time_stamp.offset == offsetof(PointXYZIRADRT, time_stamp); same_layout &= field_time_stamp.datatype == sensor_msgs::msg::PointField::FLOAT64; @@ -147,60 +160,66 @@ bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::Poin return same_layout; } -bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input) +bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::PointCloud2 & input) +{ + return is_data_layout_compatible_with_point_xyziradrt(input.fields); +} + +bool is_data_layout_compatible_with_point_xyzircaedt( + const std::vector & fields) { using PointIndex = autoware::point_types::PointXYZIRCAEDTIndex; using autoware::point_types::PointXYZIRCAEDT; - if (input.fields.size() != 10) { + if (fields.size() != 10) { return false; } bool same_layout = true; - const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + const auto & field_x = fields.at(static_cast(PointIndex::X)); same_layout &= field_x.name == "x"; same_layout &= field_x.offset == offsetof(PointXYZIRCAEDT, x); same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_x.count == 1; - const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + const auto & field_y = fields.at(static_cast(PointIndex::Y)); same_layout &= field_y.name == "y"; same_layout &= field_y.offset == offsetof(PointXYZIRCAEDT, y); same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_y.count == 1; - const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + const auto & field_z = fields.at(static_cast(PointIndex::Z)); same_layout &= field_z.name == "z"; same_layout &= field_z.offset == offsetof(PointXYZIRCAEDT, z); same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_z.count == 1; - const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + const auto & field_intensity = fields.at(static_cast(PointIndex::Intensity)); same_layout &= field_intensity.name == "intensity"; same_layout &= field_intensity.offset == offsetof(PointXYZIRCAEDT, intensity); same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::UINT8; same_layout &= field_intensity.count == 1; - const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); + const auto & field_return_type = fields.at(static_cast(PointIndex::ReturnType)); same_layout &= field_return_type.name == "return_type"; same_layout &= field_return_type.offset == offsetof(PointXYZIRCAEDT, return_type); same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; same_layout &= field_return_type.count == 1; - const auto & field_ring = input.fields.at(static_cast(PointIndex::Channel)); + const auto & field_ring = fields.at(static_cast(PointIndex::Channel)); same_layout &= field_ring.name == "channel"; same_layout &= field_ring.offset == offsetof(PointXYZIRCAEDT, channel); same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; same_layout &= field_ring.count == 1; - const auto & field_azimuth = input.fields.at(static_cast(PointIndex::Azimuth)); + const auto & field_azimuth = fields.at(static_cast(PointIndex::Azimuth)); same_layout &= field_azimuth.name == "azimuth"; same_layout &= field_azimuth.offset == offsetof(PointXYZIRCAEDT, azimuth); same_layout &= field_azimuth.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_azimuth.count == 1; - const auto & field_elevation = input.fields.at(static_cast(PointIndex::Elevation)); + const auto & field_elevation = fields.at(static_cast(PointIndex::Elevation)); same_layout &= field_elevation.name == "elevation"; same_layout &= field_elevation.offset == offsetof(PointXYZIRCAEDT, elevation); same_layout &= field_elevation.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_elevation.count == 1; - const auto & field_distance = input.fields.at(static_cast(PointIndex::Distance)); + const auto & field_distance = fields.at(static_cast(PointIndex::Distance)); same_layout &= field_distance.name == "distance"; same_layout &= field_distance.offset == offsetof(PointXYZIRCAEDT, distance); same_layout &= field_distance.datatype == sensor_msgs::msg::PointField::FLOAT32; same_layout &= field_distance.count == 1; - const auto & field_time_stamp = input.fields.at(static_cast(PointIndex::TimeStamp)); + const auto & field_time_stamp = fields.at(static_cast(PointIndex::TimeStamp)); same_layout &= field_time_stamp.name == "time_stamp"; same_layout &= field_time_stamp.offset == offsetof(PointXYZIRCAEDT, time_stamp); same_layout &= field_time_stamp.datatype == sensor_msgs::msg::PointField::UINT32; @@ -208,4 +227,9 @@ bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::Poi return same_layout; } +bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input) +{ + return is_data_layout_compatible_with_point_xyzircaedt(input.fields); +} + } // namespace autoware::pointcloud_preprocessor::utils diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp index bd22376b1c564..9c7218cd571aa 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -61,12 +61,13 @@ class ConcatenateCloudTest : public ::testing::Test concatenate_node_ = std::make_shared< autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( node_options); - combine_cloud_handler_ = - std::make_shared( - *concatenate_node_, std::vector{"lidar_top", "lidar_left", "lidar_right"}, - "base_link", true, true, true, false); + combine_cloud_handler_ = std::make_shared< + autoware::pointcloud_preprocessor::CombineCloudHandler>( + *concatenate_node_, std::vector{"lidar_top", "lidar_left", "lidar_right"}, + "base_link", true, true, true, false); - collector_ = std::make_shared( + collector_ = std::make_shared< + autoware::pointcloud_preprocessor::CloudCollector>( std::dynamic_pointer_cast< autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( concatenate_node_->shared_from_this()), @@ -168,8 +169,11 @@ class ConcatenateCloudTest : public ::testing::Test std::shared_ptr concatenate_node_; - std::shared_ptr combine_cloud_handler_; - std::shared_ptr collector_; + std::shared_ptr< + autoware::pointcloud_preprocessor::CombineCloudHandler> + combine_cloud_handler_; + std::shared_ptr> + collector_; std::shared_ptr tf_broadcaster_; static constexpr int32_t timestamp_seconds{10}; @@ -316,7 +320,7 @@ TEST_F(ConcatenateCloudTest, TestConcatenateClouds) sensor_msgs::msg::PointCloud2::SharedPtr right_pointcloud_ptr = std::make_shared(right_pointcloud); - std::unordered_map topic_to_cloud_map; + std::unordered_map topic_to_cloud_map; topic_to_cloud_map["lidar_top"] = top_pointcloud_ptr; topic_to_cloud_map["lidar_left"] = left_pointcloud_ptr; topic_to_cloud_map["lidar_right"] = right_pointcloud_ptr; @@ -448,7 +452,7 @@ TEST_F(ConcatenateCloudTest, TestDeleteCollector) { concatenate_node_->add_cloud_collector(collector_); concatenate_node_->delete_collector(*collector_); - EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); } TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) @@ -464,14 +468,14 @@ TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) auto topic_to_cloud_map = collector_->get_topic_to_cloud_map(); EXPECT_EQ(topic_to_cloud_map["lidar_top"], top_pointcloud_ptr); - EXPECT_FALSE(concatenate_node_->get_cloud_collectors().empty()); + EXPECT_FALSE(concatenate_node_->get_cloud_collectors().empty()); // Sleep for timeout seconds (200 ms) std::this_thread::sleep_for(std::chrono::milliseconds(200)); rclcpp::spin_some(concatenate_node_); // Collector should concatenate and publish the pointcloud, also delete itself. - EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); } TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) @@ -499,7 +503,7 @@ TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) collector_->process_pointcloud("lidar_left", left_pointcloud_ptr); collector_->process_pointcloud("lidar_right", right_pointcloud_ptr); - EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); } int main(int argc, char ** argv) From 7fc85e99a4605696c76dda6b8e559301cd23faf7 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos-Tsunekawa Date: Mon, 25 Nov 2024 11:44:41 +0900 Subject: [PATCH 90/90] chore: updated schemaand tests Signed-off-by: Kenzo Lobos-Tsunekawa --- .../schema/concatenate_and_time_sync_node.schema.json | 7 ++++++- .../test/test_concatenate_node_component.py | 1 + 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json index 581e540b43e02..528b52838c796 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -6,10 +6,15 @@ "concatenate_and_time_sync_node": { "type": "object", "properties": { + "use_cuda": { + "type": "boolean", + "default": false, + "description": "Flag that enables cuda accelerated concatenation and the use of the cuda transport layer (cuda blackboard)." + }, "debug_mode": { "type": "boolean", "default": false, - "description": "Flag to enables debug mode to display additional logging information." + "description": "Flag that enables debug mode to display additional logging information." }, "has_static_tf_only": { "type": "boolean", diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py index 3ea2948e393fc..2111a3bd60538 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -86,6 +86,7 @@ def generate_test_description(): ], parameters=[ { + "use_cuda": False, "debug_mode": False, "has_static_tf_only": False, "rosbag_replay": False,