Apollo  6.0
Open source self driving car software
detection_component.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2020 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 <atomic>
19 #include <memory>
20 #include <string>
21 
22 #include "cyber/cyber.h"
23 #include "modules/drivers/proto/pointcloud.pb.h"
27 #include "modules/perception/onboard/proto/lidar_component_config.pb.h"
29 
30 namespace apollo {
31 namespace perception {
32 namespace onboard {
33 
34 class DetectionComponent : public cyber::Component<drivers::PointCloud> {
35  public:
36  DetectionComponent() = default;
37  virtual ~DetectionComponent() = 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::atomic<uint32_t> seq_num_;
50  std::string sensor_name_;
51  std::string detector_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::BaseLidarObstacleDetection> detector_;
59  std::shared_ptr<apollo::cyber::Writer<LidarFrameMessage>> writer_;
60 };
61 
63 
64 } // namespace onboard
65 } // namespace perception
66 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: transform_wrapper.h:62
bool Proc(const std::shared_ptr< drivers::PointCloud > &message) override
Definition: detection_component.h:34
Definition: sensor_meta.h:57
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58
CYBER_REGISTER_COMPONENT(CameraObstacleDetectionComponent)