Apollo  6.0
Open source self driving car software
obstacle_detection_camera.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2021 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 <fstream>
19 #include <map>
20 #include <memory>
21 #include <string>
22 
23 #include "modules/perception/camera/app/proto/perception.pb.h"
37 
38 namespace apollo {
39 namespace perception {
40 namespace camera {
41 
43  public:
45  : transformer_(nullptr),
46  tracker_(nullptr),
47  extractor_(nullptr),
48  lane_detector_(nullptr),
49  lane_postprocessor_(nullptr),
50  calibration_service_(nullptr),
51  object_template_manager_(nullptr) {}
54  delete;
55  ~ObstacleDetectionCamera() = default;
56  bool Init(const CameraPerceptionInitOptions &options) override;
58  const std::map<std::string, float> &name_camera_ground_height_map,
59  const std::map<std::string, float> &name_camera_pitch_angle_diff_map,
60  const float &pitch_angle_calibrator_working_sensor);
61  void SetIm2CarHomography(Eigen::Matrix3d homography_im2car);
62  bool GetCalibrationService(BaseCalibrationService **calibration_service);
63  bool Perception(const CameraPerceptionOptions &options,
64  CameraFrame *frame) override;
65  std::string Name() const override { return "ObstacleDetectionCamera"; }
66 
67  private:
68  std::map<std::string, Eigen::Matrix3f> name_intrinsic_map_;
69  std::map<std::string, std::shared_ptr<BaseObstacleDetector>>
70  name_detector_map_;
71  std::shared_ptr<BaseObstacleTransformer> transformer_;
72  std::shared_ptr<BaseObstaclePostprocessor> obstacle_postprocessor_;
73  std::shared_ptr<BaseObstacleTracker> tracker_;
74  std::shared_ptr<BaseFeatureExtractor> extractor_;
75  std::shared_ptr<BaseLaneDetector> lane_detector_;
76  std::shared_ptr<BaseLanePostprocessor> lane_postprocessor_;
77  std::shared_ptr<BaseCalibrationService> calibration_service_;
78  app::PerceptionParam perception_param_;
79  std::ofstream out_track_;
80  std::ofstream out_pose_;
81  std::string lane_calibration_working_sensor_name_ = "";
82  bool write_out_lane_file_ = false;
83  bool write_out_calib_file_ = false;
84  std::string out_lane_dir_;
85  std::string out_calib_dir_;
86 
87  protected:
89 };
90 
91 } // namespace camera
92 } // namespace perception
93 } // namespace apollo
ObjectTemplateManager * object_template_manager_
Definition: obstacle_detection_camera.h:88
Definition: camera_frame.h:33
bool Perception(const CameraPerceptionOptions &options, CameraFrame *frame) override
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_camera_perception.h:28
std::string Name() const override
Definition: obstacle_detection_camera.h:65
Definition: base_camera_perception.h:36
bool GetCalibrationService(BaseCalibrationService **calibration_service)
Definition: object_template_manager.h:49
ObstacleDetectionCamera & operator=(const ObstacleDetectionCamera &)=delete
Definition: base_calibration_service.h:40
Definition: obstacle_detection_camera.h:42
void SetCameraHeightAndPitch(const std::map< std::string, float > &name_camera_ground_height_map, const std::map< std::string, float > &name_camera_pitch_angle_diff_map, const float &pitch_angle_calibrator_working_sensor)
bool Init(const CameraPerceptionInitOptions &options) override
ObstacleDetectionCamera()
Definition: obstacle_detection_camera.h:44
Eigen::Matrix3d Matrix3d
Definition: base_map_fwd.h:33
Definition: base_camera_perception.h:34
void SetIm2CarHomography(Eigen::Matrix3d homography_im2car)