Apollo  v5.5.0
Open source self driving car software
fusion_camera_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 <string>
21 #include <vector>
22 
23 #include "cyber/component/component.h"
24 #include "modules/drivers/proto/sensor_image.pb.h"
30 #include "modules/perception/camera/app/perception.pb.h"
36 #include "modules/perception/onboard/proto/fusion_camera_detection_component.pb.h"
38 #include "modules/perception/proto/motion_service.pb.h"
39 #include "modules/perception/proto/perception_camera.pb.h"
40 #include "modules/perception/proto/perception_obstacle.pb.h"
41 
42 typedef std::shared_ptr<apollo::perception::Motion_Service>
44 
45 namespace apollo {
46 namespace perception {
47 namespace onboard {
48 
49 class FusionCameraDetectionComponent : public apollo::cyber::Component<> {
50  public:
51  FusionCameraDetectionComponent() : seq_num_(0) {}
53 
55  delete;
57  const FusionCameraDetectionComponent&) = delete;
58 
59  bool Init() override;
60 
61  private:
62  void OnReceiveImage(const std::shared_ptr<apollo::drivers::Image>& in_message,
63  const std::string& camera_name);
64  int InitConfig();
65  int InitSensorInfo();
66  int InitAlgorithmPlugin();
67  int InitCameraFrames();
68  int InitProjectMatrix();
69  int InitCameraListeners();
70  int InitMotionService();
71  void SetCameraHeightAndPitch();
72  void OnMotionService(const MotionServiceMsgType& message);
73 
74  int InternalProc(
75  const std::shared_ptr<apollo::drivers::Image const>& in_message,
76  const std::string& camera_name, apollo::common::ErrorCode* error_code,
77  SensorFrameMessage* prefused_message,
78  apollo::perception::PerceptionObstacles* out_message);
79 
80  int MakeProtobufMsg(double msg_timestamp, int seq_num,
81  const std::vector<base::ObjectPtr>& objects,
82  const std::vector<base::LaneLine>& lane_objects,
83  const apollo::common::ErrorCode error_code,
84  apollo::perception::PerceptionObstacles* obstacles);
85 
86  int ConvertObjectToPb(const base::ObjectPtr& object_ptr,
87  apollo::perception::PerceptionObstacle* pb_msg);
88 
89  int ConvertObjectToCameraObstacle(
90  const base::ObjectPtr& object_ptr,
91  apollo::perception::camera::CameraObstacle* camera_obstacle);
92 
93  int ConvertLaneToCameraLaneline(
94  const base::LaneLine& lane_line,
95  apollo::perception::camera::CameraLaneLine* camera_laneline);
96 
97  int MakeCameraDebugMsg(
98  double msg_timestamp, const std::string& camera_name,
99  const camera::CameraFrame& camera_frame,
100  apollo::perception::camera::CameraDebug* camera_debug_msg);
101 
102  private:
103  std::mutex mutex_;
104  uint32_t seq_num_;
105 
106  std::vector<std::shared_ptr<cyber::Node>> camera_listener_nodes_;
107 
108  std::vector<std::string> camera_names_; // camera sensor names
109  std::vector<std::string> input_camera_channel_names_;
110 
111  // camera name -> SensorInfo
112  std::map<std::string, base::SensorInfo> sensor_info_map_;
113 
114  // camera_height
115  std::map<std::string, float> camera_height_map_;
116 
117  // camera_pitch_angle_diff
118  // the pitch_diff = pitch_narrow - pitch_obstacle
119  std::map<std::string, float> name_camera_pitch_angle_diff_map_;
120 
121  // TF stuff
122  std::map<std::string, std::string> tf_camera_frame_id_map_;
123  std::map<std::string, std::shared_ptr<TransformWrapper>>
124  camera2world_trans_wrapper_map_;
125 
126  // pre-allocaated-mem data_provider;
127  std::map<std::string, std::shared_ptr<camera::DataProvider>>
128  data_providers_map_;
129 
130  // map for store params
131  std::map<std::string, Eigen::Matrix4d> extrinsic_map_;
132  std::map<std::string, Eigen::Matrix3f> intrinsic_map_;
133  Eigen::Matrix3d homography_im2car_;
134 
135  // camera obstacle pipeline
136  camera::CameraPerceptionInitOptions camera_perception_init_options_;
137  camera::CameraPerceptionOptions camera_perception_options_;
138  std::unique_ptr<camera::ObstacleCameraPerception> camera_obstacle_pipeline_;
139 
140  // fixed size camera frames
141  int frame_capacity_ = 20;
142  int frame_id_ = 0;
143  std::vector<camera::CameraFrame> camera_frames_;
144 
145  // image info.
146  int image_width_ = 1920;
147  int image_height_ = 1080;
148  int image_channel_num_ = 3;
149  int image_data_size_ = -1;
150 
151  // default camera pitch angle & height
152  float default_camera_pitch_ = 0.f;
153  float default_camera_height_ = 1.6f;
154 
155  // options for DataProvider
156  bool enable_undistortion_ = false;
157 
158  double timestamp_offset_ = 0.0;
159 
160  std::string prefused_channel_name_;
161 
162  bool enable_visualization_ = false;
163  std::string camera_perception_viz_message_channel_name_;
164  std::string visual_debug_folder_;
165  std::string visual_camera_;
166 
167  bool output_final_obstacles_ = false;
168  std::string output_obstacles_channel_name_;
169 
170  bool output_camera_debug_msg_ = false;
171  std::string camera_debug_channel_name_;
172 
173  Eigen::Matrix3d project_matrix_;
174  double pitch_diff_ = 0.0;
175 
176  double last_timestamp_ = 0.0;
177  double ts_diff_ = 1.0;
178 
179  std::shared_ptr<
180  apollo::cyber::Writer<apollo::perception::PerceptionObstacles>>
181  writer_;
182 
183  std::shared_ptr<apollo::cyber::Writer<SensorFrameMessage>>
184  sensorframe_writer_;
185 
186  std::shared_ptr<apollo::cyber::Writer<CameraPerceptionVizMessage>>
187  camera_viz_writer_;
188 
189  std::shared_ptr<
190  apollo::cyber::Writer<apollo::perception::camera::CameraDebug>>
191  camera_debug_writer_;
192 
193  // variable for motion service
194  base::MotionBufferPtr motion_buffer_;
195  const int motion_buffer_size_ = 100;
196 
197  // // variables for CIPV
198  bool enable_cipv_ = false;
199  Cipv cipv_;
200  float min_laneline_length_for_cipv_ = kMinLaneLineLengthForCIPV;
201  float average_lane_width_in_meter_ = kAverageLaneWidthInMeter;
202  float max_vehicle_width_in_meter_ = kMaxVehicleWidthInMeter;
203  float average_frame_rate_ = kAverageFrameRate;
204  bool image_based_cipv_ = false;
205  int debug_level_ = 0;
206  // variables for visualization
207  camera::Visualizer visualize_;
208  bool write_visual_img_;
209 };
210 
212 
213 } // namespace onboard
214 } // namespace perception
215 } // namespace apollo
Definition: lane_struct.h:69
Definition: camera_frame.h:33
Definition: blob.h:72
Definition: fusion_camera_detection_component.h:49
Definition: base_camera_perception.h:28
FusionCameraDetectionComponent()
Definition: fusion_camera_detection_component.h:51
Definition: inner_component_messages.h:49
constexpr uint32_t kMinLaneLineLengthForCIPV
Definition: lane_object.h:35
Definition: visualizer.h:34
std::shared_ptr< apollo::perception::Motion_Service > MotionServiceMsgType
Definition: fusion_camera_detection_component.h:43
Definition: cipv_camera.h:56
constexpr float kAverageLaneWidthInMeter
Definition: lane_object.h:37
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:201
CYBER_REGISTER_COMPONENT(FusionCameraDetectionComponent)
Definition: base_camera_perception.h:34
constexpr float kMaxVehicleWidthInMeter
Definition: lane_object.h:39
FusionCameraDetectionComponent & operator=(const FusionCameraDetectionComponent &)=delete
std::shared_ptr< Object > ObjectPtr
Definition: object.h:118