|
| 1 | +// Copyright 2023 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +/* |
| 16 | + * Software License Agreement (BSD License) |
| 17 | + * |
| 18 | + * Copyright (c) 2009, Willow Garage, Inc. |
| 19 | + * All rights reserved. |
| 20 | + * |
| 21 | + * Redistribution and use in source and binary forms, with or without |
| 22 | + * modification, are permitted provided that the following conditions |
| 23 | + * are met: |
| 24 | + * |
| 25 | + * * Redistributions of source code must retain the above copyright |
| 26 | + * notice, this list of conditions and the following disclaimer. |
| 27 | + * * Redistributions in binary form must reproduce the above |
| 28 | + * copyright notice, this list of conditions and the following |
| 29 | + * disclaimer in the documentation and/or other materials provided |
| 30 | + * with the distribution. |
| 31 | + * * Neither the name of Willow Garage, Inc. nor the names of its |
| 32 | + * contributors may be used to endorse or promote products derived |
| 33 | + * from this software without specific prior written permission. |
| 34 | + * |
| 35 | + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 36 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
| 37 | + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
| 38 | + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
| 39 | + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
| 40 | + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
| 41 | + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
| 42 | + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 43 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
| 44 | + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
| 45 | + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 46 | + * POSSIBILITY OF SUCH DAMAGE. |
| 47 | + * |
| 48 | + * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ |
| 49 | + * |
| 50 | + */ |
| 51 | + |
| 52 | +#ifndef POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ |
| 53 | +#define POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ |
| 54 | + |
| 55 | +#include <deque> |
| 56 | +#include <map> |
| 57 | +#include <memory> |
| 58 | +#include <mutex> |
| 59 | +#include <set> |
| 60 | +#include <string> |
| 61 | +#include <vector> |
| 62 | + |
| 63 | +// ROS includes |
| 64 | +#include "autoware_point_types/types.hpp" |
| 65 | + |
| 66 | +#include <diagnostic_updater/diagnostic_updater.hpp> |
| 67 | +#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp> |
| 68 | +#include <tier4_autoware_utils/ros/debug_publisher.hpp> |
| 69 | +#include <tier4_autoware_utils/system/stop_watch.hpp> |
| 70 | + |
| 71 | +#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp> |
| 72 | +#include <diagnostic_msgs/msg/diagnostic_status.hpp> |
| 73 | +#include <geometry_msgs/msg/twist_stamped.hpp> |
| 74 | +#include <sensor_msgs/msg/point_cloud2.hpp> |
| 75 | +#include <sensor_msgs/point_cloud2_iterator.hpp> |
| 76 | +#include <tier4_debug_msgs/msg/int32_stamped.hpp> |
| 77 | +#include <tier4_debug_msgs/msg/string_stamped.hpp> |
| 78 | + |
| 79 | +#include <message_filters/pass_through.h> |
| 80 | +#include <message_filters/subscriber.h> |
| 81 | +#include <message_filters/sync_policies/approximate_time.h> |
| 82 | +#include <message_filters/sync_policies/exact_time.h> |
| 83 | +#include <message_filters/synchronizer.h> |
| 84 | +#include <tf2_ros/buffer.h> |
| 85 | +#include <tf2_ros/transform_listener.h> |
| 86 | + |
| 87 | +namespace pointcloud_preprocessor |
| 88 | +{ |
| 89 | +using autoware_point_types::PointXYZI; |
| 90 | +using point_cloud_msg_wrapper::PointCloud2Modifier; |
| 91 | +/** \brief @b PointCloudConcatenationComponent is a special form of data |
| 92 | + * synchronizer: it listens for a set of input PointCloud messages on the same topic, |
| 93 | + * checks their timestamps, and concatenates their fields together into a single |
| 94 | + * PointCloud output message. |
| 95 | + * \author Radu Bogdan Rusu |
| 96 | + */ |
| 97 | +class PointCloudConcatenationComponent : public rclcpp::Node |
| 98 | +{ |
| 99 | +public: |
| 100 | + typedef sensor_msgs::msg::PointCloud2 PointCloud2; |
| 101 | + |
| 102 | + /** \brief constructor. */ |
| 103 | + explicit PointCloudConcatenationComponent(const rclcpp::NodeOptions & node_options); |
| 104 | + |
| 105 | + /** \brief constructor. |
| 106 | + * \param queue_size the maximum queue size |
| 107 | + */ |
| 108 | + PointCloudConcatenationComponent(const rclcpp::NodeOptions & node_options, int queue_size); |
| 109 | + |
| 110 | + /** \brief Empty destructor. */ |
| 111 | + virtual ~PointCloudConcatenationComponent() {} |
| 112 | + |
| 113 | +private: |
| 114 | + /** \brief The output PointCloud publisher. */ |
| 115 | + rclcpp::Publisher<PointCloud2>::SharedPtr pub_output_; |
| 116 | + /** \brief Delay Compensated PointCloud publisher*/ |
| 117 | + std::map<std::string, rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr> |
| 118 | + transformed_raw_pc_publisher_map_; |
| 119 | + |
| 120 | + /** \brief The maximum number of messages that we can store in the queue. */ |
| 121 | + int maximum_queue_size_ = 3; |
| 122 | + |
| 123 | + double timeout_sec_ = 0.1; |
| 124 | + |
| 125 | + std::set<std::string> not_subscribed_topic_names_; |
| 126 | + |
| 127 | + /** \brief A vector of subscriber. */ |
| 128 | + std::vector<rclcpp::Subscription<PointCloud2>::SharedPtr> filters_; |
| 129 | + |
| 130 | + rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr sub_twist_; |
| 131 | + |
| 132 | + rclcpp::TimerBase::SharedPtr timer_; |
| 133 | + diagnostic_updater::Updater updater_{this}; |
| 134 | + |
| 135 | + /** \brief Output TF frame the concatenated points should be transformed to. */ |
| 136 | + std::string output_frame_; |
| 137 | + |
| 138 | + /** \brief Input point cloud topics. */ |
| 139 | + // XmlRpc::XmlRpcValue input_topics_; |
| 140 | + std::vector<std::string> input_topics_; |
| 141 | + |
| 142 | + /** \brief TF listener object. */ |
| 143 | + std::shared_ptr<tf2_ros::Buffer> tf2_buffer_; |
| 144 | + std::shared_ptr<tf2_ros::TransformListener> tf2_listener_; |
| 145 | + |
| 146 | + std::deque<geometry_msgs::msg::TwistStamped::ConstSharedPtr> twist_ptr_queue_; |
| 147 | + |
| 148 | + std::map<std::string, sensor_msgs::msg::PointCloud2::ConstSharedPtr> cloud_stdmap_; |
| 149 | + std::map<std::string, sensor_msgs::msg::PointCloud2::ConstSharedPtr> cloud_stdmap_tmp_; |
| 150 | + std::mutex mutex_; |
| 151 | + |
| 152 | + std::vector<double> input_offset_; |
| 153 | + std::map<std::string, double> offset_map_; |
| 154 | + |
| 155 | + void transformPointCloud(const PointCloud2::ConstSharedPtr & in, PointCloud2::SharedPtr & out); |
| 156 | + void transformPointCloud( |
| 157 | + const PointCloud2::ConstSharedPtr & in, PointCloud2::SharedPtr & out, |
| 158 | + const std::string & target_frame); |
| 159 | + void checkSyncStatus(); |
| 160 | + void combineClouds(sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr); |
| 161 | + void publish(); |
| 162 | + |
| 163 | + void convertToXYZICloud( |
| 164 | + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, |
| 165 | + sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); |
| 166 | + void setPeriod(const int64_t new_period); |
| 167 | + void cloud_callback( |
| 168 | + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, |
| 169 | + const std::string & topic_name); |
| 170 | + void timer_callback(); |
| 171 | + |
| 172 | + void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); |
| 173 | + |
| 174 | + /** \brief processing time publisher. **/ |
| 175 | + std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_; |
| 176 | + std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_; |
| 177 | +}; |
| 178 | + |
| 179 | +} // namespace pointcloud_preprocessor |
| 180 | + |
| 181 | +#endif // POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ |
0 commit comments