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