25 #include "Eigen/Dense" 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" 46 typedef std::shared_ptr<apollo::perception::Motion_Service>
50 namespace perception {
56 typedef FunctionInfo<LaneDetectionComponent>
FunInfoType;
71 void OnReceiveImage(
const std::shared_ptr<apollo::drivers::Image>& in_message,
72 const std::string& camera_name);
76 int InitAlgorithmPlugin();
77 int InitCameraFrames();
78 int InitProjectMatrix();
79 int InitMotionService();
80 int InitCameraListeners();
81 void SetCameraHeightAndPitch();
84 const std::shared_ptr<apollo::drivers::Image const>& in_message,
85 const std::string& camera_name, apollo::common::ErrorCode* error_code,
87 apollo::perception::PerceptionLanes* out_message);
89 int ConvertLaneToCameraLaneline(
91 apollo::perception::camera::CameraLaneLine* camera_laneline);
93 int MakeProtobufMsg(
double msg_timestamp,
const std::string& camera_name,
95 apollo::perception::PerceptionLanes* lanes_msg);
101 std::vector<std::shared_ptr<cyber::Node>> camera_listener_nodes_;
103 std::vector<std::string> camera_names_;
104 std::vector<std::string> input_camera_channel_names_;
107 std::map<std::string, base::SensorInfo> sensor_info_map_;
110 std::map<std::string, float> camera_height_map_;
113 std::map<std::string, float> name_camera_pitch_angle_diff_map_;
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_;
121 std::map<std::string, std::shared_ptr<camera::DataProvider>>
125 std::map<std::string, Eigen::Matrix4d> extrinsic_map_;
126 std::map<std::string, Eigen::Matrix3f> intrinsic_map_;
127 Eigen::Matrix3d homography_image2ground_;
132 std::unique_ptr<camera::LaneCameraPerception> camera_lane_pipeline_;
135 int frame_capacity_ = 20;
137 std::vector<camera::CameraFrame> camera_frames_;
140 int image_width_ = 1920;
141 int image_height_ = 1080;
142 int image_channel_num_ = 3;
143 int image_data_size_ = -1;
146 float default_camera_pitch_ = 0.f;
147 float default_camera_height_ = 1.6f;
150 bool enable_undistortion_ =
false;
152 double timestamp_offset_ = 0.0;
154 bool enable_visualization_ =
false;
155 std::string visual_debug_folder_;
156 std::string visual_camera_;
158 std::string output_lanes_channel_name_;
160 Eigen::Matrix3d project_matrix_;
161 double pitch_diff_ = 0.0;
163 double last_timestamp_ = 0.0;
164 double ts_diff_ = 1.0;
166 std::shared_ptr<apollo::cyber::Writer<apollo::perception::PerceptionLanes>>
170 const int motion_buffer_size_ = 100;
173 bool write_visual_img_;
174 static FunInfoType init_func_arry_[];
Definition: lane_struct.h:69
Definition: camera_frame.h:33
LaneDetectionComponent()
Definition: lane_detection_component.h:59
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
~LaneDetectionComponent()
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