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" 42 typedef std::shared_ptr<apollo::perception::Motion_Service>
46 namespace perception {
62 void OnReceiveImage(
const std::shared_ptr<apollo::drivers::Image>& in_message,
63 const std::string& camera_name);
66 int InitAlgorithmPlugin();
67 int InitCameraFrames();
68 int InitProjectMatrix();
69 int InitCameraListeners();
70 int InitMotionService();
71 void SetCameraHeightAndPitch();
75 const std::shared_ptr<apollo::drivers::Image const>& in_message,
76 const std::string& camera_name, apollo::common::ErrorCode* error_code,
78 apollo::perception::PerceptionObstacles* out_message);
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);
87 apollo::perception::PerceptionObstacle* pb_msg);
89 int ConvertObjectToCameraObstacle(
91 apollo::perception::camera::CameraObstacle* camera_obstacle);
93 int ConvertLaneToCameraLaneline(
95 apollo::perception::camera::CameraLaneLine* camera_laneline);
97 int MakeCameraDebugMsg(
98 double msg_timestamp,
const std::string& camera_name,
100 apollo::perception::camera::CameraDebug* camera_debug_msg);
106 std::vector<std::shared_ptr<cyber::Node>> camera_listener_nodes_;
108 std::vector<std::string> camera_names_;
109 std::vector<std::string> input_camera_channel_names_;
112 std::map<std::string, base::SensorInfo> sensor_info_map_;
115 std::map<std::string, float> camera_height_map_;
119 std::map<std::string, float> name_camera_pitch_angle_diff_map_;
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_;
127 std::map<std::string, std::shared_ptr<camera::DataProvider>>
131 std::map<std::string, Eigen::Matrix4d> extrinsic_map_;
132 std::map<std::string, Eigen::Matrix3f> intrinsic_map_;
133 Eigen::Matrix3d homography_im2car_;
138 std::unique_ptr<camera::ObstacleCameraPerception> camera_obstacle_pipeline_;
141 int frame_capacity_ = 20;
143 std::vector<camera::CameraFrame> camera_frames_;
146 int image_width_ = 1920;
147 int image_height_ = 1080;
148 int image_channel_num_ = 3;
149 int image_data_size_ = -1;
152 float default_camera_pitch_ = 0.f;
153 float default_camera_height_ = 1.6f;
156 bool enable_undistortion_ =
false;
158 double timestamp_offset_ = 0.0;
160 std::string prefused_channel_name_;
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_;
167 bool output_final_obstacles_ =
false;
168 std::string output_obstacles_channel_name_;
170 bool output_camera_debug_msg_ =
false;
171 std::string camera_debug_channel_name_;
173 Eigen::Matrix3d project_matrix_;
174 double pitch_diff_ = 0.0;
176 double last_timestamp_ = 0.0;
177 double ts_diff_ = 1.0;
180 apollo::cyber::Writer<apollo::perception::PerceptionObstacles>>
183 std::shared_ptr<apollo::cyber::Writer<SensorFrameMessage>>
186 std::shared_ptr<apollo::cyber::Writer<CameraPerceptionVizMessage>>
190 apollo::cyber::Writer<apollo::perception::camera::CameraDebug>>
191 camera_debug_writer_;
195 const int motion_buffer_size_ = 100;
198 bool enable_cipv_ =
false;
203 float average_frame_rate_ = kAverageFrameRate;
204 bool image_based_cipv_ =
false;
205 int debug_level_ = 0;
208 bool write_visual_img_;
Definition: lane_struct.h:69
Definition: camera_frame.h:33
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
~FusionCameraDetectionComponent()
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