Autoware.Auto
ray_ground_classifier_cloud_node.hpp
Go to the documentation of this file.
1 // Copyright 2017-2020 the Autoware Foundation, Arm Limited
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.
19 
20 #ifndef RAY_GROUND_CLASSIFIER_NODES__RAY_GROUND_CLASSIFIER_CLOUD_NODE_HPP_
21 #define RAY_GROUND_CLASSIFIER_NODES__RAY_GROUND_CLASSIFIER_CLOUD_NODE_HPP_
22 
23 #include <common/types.hpp>
28 #include <rclcpp/rclcpp.hpp>
29 #include <sensor_msgs/msg/point_cloud2.hpp>
30 
31 #include <memory>
32 #include <string>
33 #include <vector>
34 
37 
38 namespace autoware
39 {
40 namespace perception
41 {
42 namespace filters
43 {
44 namespace ray_ground_classifier_nodes
45 {
46 
48 
51 class RAY_GROUND_CLASSIFIER_PUBLIC RayGroundClassifierCloudNode
52  : public rclcpp::Node
53 {
54 public:
58  explicit RayGroundClassifierCloudNode(const rclcpp::NodeOptions & options);
59 
60 private:
62  RAY_GROUND_CLASSIFIER_NODES_LOCAL void reset();
63  // Algorithmic core
66  // preallocated message
67  PointCloud2 m_ground_msg;
68  PointCloud2 m_nonground_msg;
69  const uint32_t m_pcl_size;
70  const std::string m_frame_id;
71  // Basic stateful stuff, will get refactored after we have a proper state machine implementation
72  bool8_t m_has_failed;
73  // publishers and subscribers
74  const std::chrono::nanoseconds m_timeout;
75  const rclcpp::Subscription<PointCloud2>::SharedPtr m_raw_sub_ptr;
76  const std::shared_ptr<rclcpp::Publisher<PointCloud2>> m_ground_pub_ptr;
77  const std::shared_ptr<rclcpp::Publisher<PointCloud2>> m_nonground_pub_ptr;
79  void callback(const PointCloud2::SharedPtr msg);
80 }; // class RayGroundFilterDriverNode
81 } // namespace ray_ground_classifier_nodes
82 } // namespace filters
83 } // namespace perception
84 } // namespace autoware
85 #endif // RAY_GROUND_CLASSIFIER_NODES__RAY_GROUND_CLASSIFIER_CLOUD_NODE_HPP_
autoware::perception::filters::ray_ground_classifier::RayAggregator
Used as a prefiltering step for RayGroundClassifier. Aggregates unstructured blobs into rays of point...
Definition: ray_aggregator.hpp:49
types.hpp
This file includes common type definition.
point_cloud_utils.hpp
This class defines common functions and classes to work with pointclouds.
ray_aggregator.hpp
This file defines the ray aggregator for generic point cloud support.
ray_ground_classifier.hpp
This file defines the ray ground filter algorithm.
autoware::common::types::char8_t
char char8_t
Definition: types.hpp:40
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::perception::filters::ray_ground_classifier_nodes::RayGroundClassifierCloudNode
A node that takes in unstructured point clouds and partitions them into ground and nonground points.
Definition: ray_ground_classifier_cloud_node.hpp:51
autoware::perception::filters::ray_ground_classifier::RayGroundClassifier
Given a ray, partitions into ground and nonground points.
Definition: ray_ground_classifier.hpp:41
autoware::perception::filters::filter_node_base::PointCloud2
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32
visibility_control.hpp