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" 43 typedef std::shared_ptr<apollo::perception::Motion_Service>
49 namespace perception {
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
66 void OnReceiveImage(
const std::shared_ptr<apollo::drivers::Image>& in_message,
67 const std::string& camera_name);
72 int InitAlgorithmPlugin();
73 int InitCameraFrames();
74 int InitProjectMatrix();
75 int InitCameraListeners();
76 int InitMotionService();
77 void SetCameraHeightAndPitch();
81 const std::shared_ptr<apollo::drivers::Image const>& in_message,
82 const std::string& camera_name, apollo::common::ErrorCode* error_code,
84 apollo::perception::PerceptionObstacles* out_message);
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);
93 apollo::perception::PerceptionObstacle* pb_msg);
95 int ConvertObjectToCameraObstacle(
97 apollo::perception::camera::CameraObstacle* camera_obstacle);
99 int ConvertLaneToCameraLaneline(
101 apollo::perception::camera::CameraLaneLine* camera_laneline);
103 int MakeCameraDebugMsg(
104 double msg_timestamp,
const std::string& camera_name,
106 apollo::perception::camera::CameraDebug* camera_debug_msg);
112 std::vector<std::shared_ptr<cyber::Node>> camera_listener_nodes_;
114 std::vector<std::string> camera_names_;
115 std::vector<std::string> input_camera_channel_names_;
118 std::map<std::string, base::SensorInfo> sensor_info_map_;
121 std::map<std::string, float> camera_height_map_;
125 std::map<std::string, float> name_camera_pitch_angle_diff_map_;
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_;
133 std::map<std::string, std::shared_ptr<camera::DataProvider>>
137 EigenMap<std::string, Eigen::Matrix4d> extrinsic_map_;
138 EigenMap<std::string, Eigen::Matrix3f> intrinsic_map_;
144 std::unique_ptr<camera::ObstacleCameraPerception> camera_obstacle_pipeline_;
147 int frame_capacity_ = 20;
149 EigenVector<camera::CameraFrame> camera_frames_;
152 int image_width_ = 1920;
153 int image_height_ = 1080;
154 int image_channel_num_ = 3;
155 int image_data_size_ = -1;
158 float default_camera_pitch_ = 0.f;
159 float default_camera_height_ = 1.6f;
162 bool enable_undistortion_ =
false;
164 double timestamp_offset_ = 0.0;
166 std::string prefused_channel_name_;
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_;
173 bool output_final_obstacles_ =
false;
174 std::string output_obstacles_channel_name_;
176 bool output_camera_debug_msg_ =
false;
177 std::string camera_debug_channel_name_;
180 double pitch_diff_ = 0.0;
182 double last_timestamp_ = 0.0;
183 double ts_diff_ = 1.0;
189 std::shared_ptr<apollo::cyber::Writer<SensorFrameMessage>>
192 std::shared_ptr<apollo::cyber::Writer<CameraPerceptionVizMessage>>
197 camera_debug_writer_;
201 const int motion_buffer_size_ = 100;
204 bool enable_cipv_ =
false;
205 std::unique_ptr<camera::BaseCipv> cipv_;
207 std::string cipv_name_;
211 bool write_visual_img_;
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: visualizer.h:39
std::shared_ptr< apollo::perception::Motion_Service > MotionServiceMsgType
Definition: fusion_camera_detection_component.h:44
~FusionCameraDetectionComponent()
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
Definition: base_cipv.h:35
CYBER_REGISTER_COMPONENT(CameraObstacleDetectionComponent)
FusionCameraDetectionComponent & operator=(const FusionCameraDetectionComponent &)=delete
std::shared_ptr< Object > ObjectPtr
Definition: object.h:123