Apollo  v5.5.0
Open source self driving car software
segmentation_component.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <memory>
19 #include <string>
20 
21 #include "cyber/cyber.h"
22 #include "modules/drivers/proto/pointcloud.pb.h"
26 #include "modules/perception/onboard/proto/lidar_component_config.pb.h"
28 
29 namespace apollo {
30 namespace perception {
31 namespace onboard {
32 
33 class SegmentationComponent : public cyber::Component<drivers::PointCloud> {
34  public:
35  SegmentationComponent() : segmentor_(nullptr) {}
36 
37  ~SegmentationComponent() = default;
38 
39  bool Init() override;
40  bool Proc(const std::shared_ptr<drivers::PointCloud>& message) override;
41 
42  private:
43  bool InitAlgorithmPlugin();
44  bool InternalProc(
45  const std::shared_ptr<const drivers::PointCloud>& in_message,
46  const std::shared_ptr<LidarFrameMessage>& out_message);
47 
48  private:
49  static std::mutex s_mutex_;
50  static uint32_t s_seq_num_;
51  std::string sensor_name_;
52  bool enable_hdmap_ = true;
53  float lidar_query_tf_offset_ = 20.0f;
54  std::string lidar2novatel_tf2_child_frame_id_;
55  std::string output_channel_name_;
56  base::SensorInfo sensor_info_;
57  TransformWrapper lidar2world_trans_;
58  std::unique_ptr<lidar::LidarObstacleSegmentation> segmentor_;
59  std::shared_ptr<apollo::cyber::Writer<LidarFrameMessage>> writer_;
60 };
61 
63 
64 } // namespace onboard
65 } // namespace perception
66 } // namespace apollo
bool Proc(const std::shared_ptr< drivers::PointCloud > &message) override
Definition: blob.h:72
Definition: transform_wrapper.h:61
SegmentationComponent()
Definition: segmentation_component.h:35
Definition: segmentation_component.h:33
Definition: sensor_meta.h:57
CYBER_REGISTER_COMPONENT(FusionCameraDetectionComponent)