Autoware.Auto
velodyne_cloud_node.hpp
Go to the documentation of this file.
1 // Copyright 2018 the Autoware Foundation
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 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 
22 
23 #ifndef VELODYNE_NODES__VELODYNE_CLOUD_NODE_HPP_
24 #define VELODYNE_NODES__VELODYNE_CLOUD_NODE_HPP_
25 
26 #include <string>
27 #include <vector>
28 #include "common/types.hpp"
30 #include "udp_driver/udp_driver_node.hpp"
33 #include "sensor_msgs/msg/point_cloud2.hpp"
34 
36 
37 namespace autoware
38 {
39 namespace drivers
40 {
42 namespace velodyne_nodes
43 {
44 
48 template<typename SensorData>
49 class VELODYNE_NODES_PUBLIC VelodyneCloudNode
50  : public udp_driver::UdpDriverNode<
51  typename velodyne_driver::VelodyneTranslator<SensorData>::Packet,
52  sensor_msgs::msg::PointCloud2>
53 {
54 public:
58  using UdpDriverNode = udp_driver::UdpDriverNode<Packet, sensor_msgs::msg::PointCloud2>;
59 
70  const std::string & node_name,
71  const std::string & ip,
72  const uint16_t port,
73  const std::string & frame_id,
74  const std::size_t cloud_size,
75  const Config & config);
76 
81  const std::string & node_name,
82  const std::string & node_namespace = "");
83 
84 protected:
85  void init_output(sensor_msgs::msg::PointCloud2 & output) override;
87  const Packet & pkt,
88  sensor_msgs::msg::PointCloud2 & output) override;
89  bool8_t get_output_remainder(sensor_msgs::msg::PointCloud2 & output) override;
90 
91 private:
92  VelodyneTranslatorT m_translator;
93  std::vector<autoware::common::types::PointXYZIF> m_point_block;
94 
95  // These next two variables are a minor hack to maintain stateful information across convert()
96  // calls. Specifically, it signals to reset any stateful information on the data vector at the top
97  // of the convert function
98  bool8_t m_published_cloud;
99  // Keeps track of where you left off on the converted point block in case you needed to publish
100  // a point cloud in the middle of processing it
101  uint32_t m_remainder_start_idx;
102  // keeps track of the constructed point cloud to continue growing it with new data
103  uint32_t m_point_cloud_idx;
105  const std::string m_frame_id;
106  const std::size_t m_cloud_size;
107 }; // class VelodyneCloudNode
108 
112 } // namespace velodyne_nodes
113 } // namespace drivers
114 } // namespace autoware
115 
116 #endif // VELODYNE_NODES__VELODYNE_CLOUD_NODE_HPP_
autoware::drivers::velodyne_nodes::VelodyneCloudNode
Definition: velodyne_cloud_node.hpp:49
output
Definition: output_type_trait.hpp:30
velodyne_translator.hpp
This file defines a driver for Velodyne LiDARs.
autoware::drivers::velodyne_nodes::VelodyneCloudNode::Packet
typename VelodyneTranslatorT::Packet Packet
Definition: velodyne_cloud_node.hpp:57
types.hpp
This file includes common type definition.
point_cloud_utils.hpp
This class defines common functions and classes to work with pointclouds.
autoware::common::lidar_utils::PointCloudIts
Definition: point_cloud_utils.hpp:61
autoware::drivers::velodyne_driver::VelodyneTranslator::Config
Definition: velodyne_translator.hpp:54
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::drivers::velodyne_nodes::VelodyneCloudNode::Config
typename VelodyneTranslatorT::Config Config
Definition: velodyne_cloud_node.hpp:56
autoware::drivers::velodyne_nodes::VelodyneCloudNode::UdpDriverNode
udp_driver::UdpDriverNode< Packet, sensor_msgs::msg::PointCloud2 > UdpDriverNode
Definition: velodyne_cloud_node.hpp:58
autoware::drivers::velodyne_driver::VelodyneTranslator::Packet
stores a Velodyne data packet
Definition: velodyne_translator.hpp:90
visibility_control.hpp
autoware::covariance_insertion_nodes::convert
constexpr output< InputT >::type convert(const InputT &input_msg) noexcept
Definition: convert.hpp:29
autoware::drivers::velodyne_driver::VelodyneTranslator
This class handles converting packets from a velodyne lidar into cartesian points.
Definition: velodyne_translator.hpp:48