Apollo  v5.5.0
Open source self driving car software
lane_detection_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 <map>
19 #include <memory>
20 #include <mutex>
21 #include <string>
22 #include <vector>
23 
24 #include "Eigen/Core"
25 #include "Eigen/Dense"
26 
27 #include "cyber/component/component.h"
28 #include "modules/common/util/util.h"
29 #include "modules/drivers/proto/sensor_image.pb.h"
34 #include "modules/perception/camera/app/perception.pb.h"
41 #include "modules/perception/onboard/proto/lane_perception_component.pb.h"
43 #include "modules/perception/proto/motion_service.pb.h"
44 #include "modules/perception/proto/perception_lane.pb.h"
45 
46 typedef std::shared_ptr<apollo::perception::Motion_Service>
48 
49 namespace apollo {
50 namespace perception {
51 namespace onboard {
52 
53 typedef Eigen::Matrix4d MotionType;
54 
56 typedef FunctionInfo<LaneDetectionComponent> FunInfoType;
57 class LaneDetectionComponent : public apollo::cyber::Component<> {
58  public:
59  LaneDetectionComponent() : seq_num_(0) {}
61 
64 
65  bool Init() override;
66 
67  template <typename T>
68  friend class FunctionInfo;
69 
70  private:
71  void OnReceiveImage(const std::shared_ptr<apollo::drivers::Image>& in_message,
72  const std::string& camera_name);
73  void OnMotionService(const MotionServiceMsgType& in_message);
74  int InitConfig();
75  int InitSensorInfo();
76  int InitAlgorithmPlugin();
77  int InitCameraFrames();
78  int InitProjectMatrix();
79  int InitMotionService();
80  int InitCameraListeners();
81  void SetCameraHeightAndPitch();
82 
83  int InternalProc(
84  const std::shared_ptr<apollo::drivers::Image const>& in_message,
85  const std::string& camera_name, apollo::common::ErrorCode* error_code,
86  SensorFrameMessage* prefused_message,
87  apollo::perception::PerceptionLanes* out_message);
88 
89  int ConvertLaneToCameraLaneline(
90  const base::LaneLine& lane_line,
91  apollo::perception::camera::CameraLaneLine* camera_laneline);
92 
93  int MakeProtobufMsg(double msg_timestamp, const std::string& camera_name,
94  const camera::CameraFrame& camera_frame,
95  apollo::perception::PerceptionLanes* lanes_msg);
96 
97  private:
98  std::mutex mutex_;
99  uint32_t seq_num_;
100 
101  std::vector<std::shared_ptr<cyber::Node>> camera_listener_nodes_;
102 
103  std::vector<std::string> camera_names_; // camera sensor names
104  std::vector<std::string> input_camera_channel_names_;
105 
106  // camera name -> SensorInfo
107  std::map<std::string, base::SensorInfo> sensor_info_map_;
108 
109  // camera_height
110  std::map<std::string, float> camera_height_map_;
111 
112  // camera_pitch_angle_diff
113  std::map<std::string, float> name_camera_pitch_angle_diff_map_;
114 
115  // TF stuff
116  std::map<std::string, std::string> tf_camera_frame_id_map_;
117  std::map<std::string, std::shared_ptr<TransformWrapper>>
118  camera2world_trans_wrapper_map_;
119 
120  // pre-allocaated-mem data_provider;
121  std::map<std::string, std::shared_ptr<camera::DataProvider>>
122  data_providers_map_;
123 
124  // map for store params
125  std::map<std::string, Eigen::Matrix4d> extrinsic_map_;
126  std::map<std::string, Eigen::Matrix3f> intrinsic_map_;
127  Eigen::Matrix3d homography_image2ground_;
128 
129  // camera lane pipeline
130  camera::CameraPerceptionInitOptions camera_perception_init_options_;
131  camera::CameraPerceptionOptions camera_perception_options_;
132  std::unique_ptr<camera::LaneCameraPerception> camera_lane_pipeline_;
133 
134  // fixed size camera frames
135  int frame_capacity_ = 20;
136  int frame_id_ = 0;
137  std::vector<camera::CameraFrame> camera_frames_;
138 
139  // image info.
140  int image_width_ = 1920;
141  int image_height_ = 1080;
142  int image_channel_num_ = 3;
143  int image_data_size_ = -1;
144 
145  // default camera pitch angle & height
146  float default_camera_pitch_ = 0.f;
147  float default_camera_height_ = 1.6f;
148 
149  // options for DataProvider
150  bool enable_undistortion_ = false;
151 
152  double timestamp_offset_ = 0.0;
153 
154  bool enable_visualization_ = false;
155  std::string visual_debug_folder_;
156  std::string visual_camera_;
157 
158  std::string output_lanes_channel_name_;
159 
160  Eigen::Matrix3d project_matrix_;
161  double pitch_diff_ = 0.0;
162 
163  double last_timestamp_ = 0.0;
164  double ts_diff_ = 1.0;
165 
166  std::shared_ptr<apollo::cyber::Writer<apollo::perception::PerceptionLanes>>
167  writer_;
168 
169  base::MotionBufferPtr mot_buffer_;
170  const int motion_buffer_size_ = 100;
171 
172  camera::Visualizer visualize_;
173  bool write_visual_img_;
174  static FunInfoType init_func_arry_[];
175 };
176 
178 
179 } // namespace onboard
180 } // namespace perception
181 } // namespace apollo
Definition: lane_struct.h:69
Definition: camera_frame.h:33
LaneDetectionComponent()
Definition: lane_detection_component.h:59
Definition: blob.h:72
Definition: base_camera_perception.h:28
Definition: inner_component_messages.h:49
Definition: visualizer.h:34
Definition: lane_detection_component.h:57
std::shared_ptr< apollo::perception::Motion_Service > MotionServiceMsgType
Definition: fusion_camera_detection_component.h:43
Eigen::Matrix4d MotionType
Definition: lane_detection_component.h:53
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:201
FunctionInfo< LaneDetectionComponent > FunInfoType
Definition: lane_detection_component.h:55
CYBER_REGISTER_COMPONENT(FusionCameraDetectionComponent)
Definition: base_camera_perception.h:34
friend class FunctionInfo
Definition: lane_detection_component.h:68
LaneDetectionComponent & operator=(const LaneDetectionComponent &)=delete
std::shared_ptr< apollo::perception::Motion_Service > MotionServiceMsgType
Definition: lane_detection_component.h:47