Apollo 11.0
自动驾驶开放平台
lane_camera_perception.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2019 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/lane_detection/proto/perception.pb.h"
24
25#include "cyber/common/macros.h"
35
36namespace apollo {
37namespace perception {
38namespace camera {
39
41 public:
42 template <typename T, class EigenType>
44
45 public:
48
49 bool Init(const CameraPerceptionInitOptions &options) override;
51 const app::PerceptionParam &perception_param);
53 const app::PerceptionParam &perception_param);
55 const std::map<std::string, float> name_camera_ground_height_map,
56 const std::map<std::string, float> name_camera_pitch_angle_diff_map,
57 const float &pitch_angle_calibrator_working_sensor);
58 void SetIm2CarHomography(const Eigen::Matrix3d &homography_im2car);
59 bool GetCalibrationService(BaseCalibrationService **calibration_service);
60 bool Perception(const CameraPerceptionOptions &options,
61 CameraFrame *frame) override;
62
63 std::string Name() const override { return "LaneCameraPerception"; }
64
65 private:
66 EigenMap<std::string, Eigen::Matrix3f> name_intrinsic_map_;
67 EigenMap<std::string, Eigen::Matrix4d> name_extrinsic_map_;
68 std::shared_ptr<BaseLaneDetector> lane_detector_;
69 std::shared_ptr<BaseLanePostprocessor> lane_postprocessor_;
70 std::shared_ptr<BaseCalibrationService> calibration_service_;
71 app::PerceptionParam perception_param_;
72 std::string lane_calibration_working_sensor_name_ = "";
73 bool write_out_lane_file_ = false;
74 bool write_out_calib_file_ = false;
75 std::string out_lane_dir_;
76 std::string out_calib_dir_;
77
79};
80
81} // namespace camera
82} // namespace perception
83} // namespace apollo
void SetIm2CarHomography(const Eigen::Matrix3d &homography_im2car)
apollo::common::EigenMap< T, EigenType > EigenMap
bool Init(const CameraPerceptionInitOptions &options) override
void InitCalibrationService(const base::BaseCameraModelPtr model, const app::PerceptionParam &perception_param)
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)
void InitLane(base::BaseCameraModelPtr &model, const app::PerceptionParam &perception_param)
bool GetCalibrationService(BaseCalibrationService **calibration_service)
bool Perception(const CameraPerceptionOptions &options, CameraFrame *frame) override
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition macros.h:48
std::map< T, EigenType, std::less< T >, Eigen::aligned_allocator< std::pair< const T, EigenType > > > EigenMap
Definition eigen_defs.h:40
std::shared_ptr< BaseCameraModel > BaseCameraModelPtr
Definition camera.h:75
class register implement
Definition arena_queue.h:37