Apollo  6.0
Open source self driving car software
obstacle_camera_perception.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 <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  ~ObstacleCameraPerception() = default;
56  bool Init(const CameraPerceptionInitOptions &options) override;
57  void InitLane(const std::string &work_root,
58  const app::PerceptionParam &perception_param);
59  void InitCalibrationService(const std::string &work_root,
60  const base::BaseCameraModelPtr model,
61  const app::PerceptionParam &perception_param);
63  const std::map<std::string, float> &name_camera_ground_height_map,
64  const std::map<std::string, float> &name_camera_pitch_angle_diff_map,
65  const float &pitch_angle_calibrator_working_sensor);
66  void SetIm2CarHomography(Eigen::Matrix3d homography_im2car);
67  bool GetCalibrationService(BaseCalibrationService **calibration_service);
68  bool Perception(const CameraPerceptionOptions &options,
69  CameraFrame *frame) override;
70  std::string Name() const override { return "ObstacleCameraPerception"; }
71 
72  private:
73  std::map<std::string, Eigen::Matrix3f> name_intrinsic_map_;
74  std::map<std::string, std::shared_ptr<BaseObstacleDetector>>
75  name_detector_map_;
76  std::shared_ptr<BaseObstacleTransformer> transformer_;
77  std::shared_ptr<BaseObstaclePostprocessor> obstacle_postprocessor_;
78  std::shared_ptr<BaseObstacleTracker> tracker_;
79  std::shared_ptr<BaseFeatureExtractor> extractor_;
80  std::shared_ptr<BaseLaneDetector> lane_detector_;
81  std::shared_ptr<BaseLanePostprocessor> lane_postprocessor_;
82  std::shared_ptr<BaseCalibrationService> calibration_service_;
83  app::PerceptionParam perception_param_;
84  std::ofstream out_track_;
85  std::ofstream out_pose_;
86  std::string lane_calibration_working_sensor_name_ = "";
87  bool write_out_lane_file_ = false;
88  bool write_out_calib_file_ = false;
89  std::string out_lane_dir_;
90  std::string out_calib_dir_;
91 
92  protected:
94 };
95 
96 } // namespace camera
97 } // namespace perception
98 } // namespace apollo
bool Perception(const CameraPerceptionOptions &options, CameraFrame *frame) override
void InitLane(const std::string &work_root, const app::PerceptionParam &perception_param)
Definition: camera_frame.h:33
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::string Name() const override
Definition: obstacle_camera_perception.h:70
Definition: base_camera_perception.h:28
bool Init(const CameraPerceptionInitOptions &options) override
Definition: obstacle_camera_perception.h:42
void SetIm2CarHomography(Eigen::Matrix3d homography_im2car)
Definition: base_camera_perception.h:36
bool GetCalibrationService(BaseCalibrationService **calibration_service)
Definition: object_template_manager.h:49
ObstacleCameraPerception & operator=(const ObstacleCameraPerception &)=delete
void InitCalibrationService(const std::string &work_root, const base::BaseCameraModelPtr model, const app::PerceptionParam &perception_param)
ObjectTemplateManager * object_template_manager_
Definition: obstacle_camera_perception.h:93
Definition: base_calibration_service.h:40
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)
std::shared_ptr< BaseCameraModel > BaseCameraModelPtr
Definition: camera.h:75
Eigen::Matrix3d Matrix3d
Definition: base_map_fwd.h:33
Definition: base_camera_perception.h:34
ObstacleCameraPerception()
Definition: obstacle_camera_perception.h:44