22 #include "opencv2/opencv.hpp" 28 #include "modules/perception/proto/motion_service.pb.h" 31 namespace perception {
36 bool Init(
const std::vector<std::string> &camera_names,
39 const std::vector<std::string> &camera_names,
40 const std::string &visual_camera,
41 const std::map<std::string, Eigen::Matrix3f> &intrinsic_map,
42 const std::map<std::string, Eigen::Matrix4d> &extrinsic_map,
43 const Eigen::Matrix4d &ex_lidar2imu,
44 const double pitch_adj,
46 const double roll_adj,
47 const int image_height,
48 const int image_width);
49 bool adjust_angles(
const std::string &camera_name,
const double pitch_adj,
50 const double yaw_adj,
const double roll_adj);
58 const Eigen::Affine3d &world2camera);
60 const std::string &camera_name,
63 const Eigen::Matrix3d &intrinsic,
64 const Eigen::Matrix4d &extrinsic,
65 const Eigen::Affine3d &world2camera,
73 Eigen::Vector2d p_ground);
80 void Set_ROI(
int input_offset_y,
int crop_height,
int crop_width) {
81 roi_start_ = input_offset_y;
82 roi_height_ = crop_height;
83 roi_width_ = crop_width;
86 const double pitch_radian,
const double yaw_radian,
87 const double roll_radian);
89 const double pitch_adj_degree,
90 const double yaw_adj_degree,
91 const double roll_adj_degree);
93 const Eigen::Matrix4d &extrinsic,
94 const Eigen::Vector4d &quaternion,
95 const double pitch_radian,
96 const double yaw_radian,
97 const double roll_radian);
100 bool key_handler(
const std::string &camera_name,
const int key);
113 std::map<std::string, cv::Mat> camera_image_;
114 cv::Mat world_image_;
117 double last_timestamp_ = 0.0;
118 int image_width_ = 1920;
119 int image_height_ = 1080;
120 int wide_pixel_ = 800;
121 double scale_ratio_ = 0.6;
126 double fov_cut_ratio_ = 0.55;
127 double degree_to_radian_factor_ = M_PI / 180.0;
128 double radian_to_degree_factor_ = 180.0 / M_PI;
130 std::map<std::string, double> pitch_adj_degree_;
131 std::map<std::string, double> yaw_adj_degree_;
132 std::map<std::string, double> roll_adj_degree_;
134 double max_pitch_degree_ = 5.0;
135 double min_pitch_degree_ = -5.0;
136 double max_yaw_degree_ = 5.0;
137 double min_yaw_degree_ = -5.0;
138 double max_roll_degree_ = 5.0;
139 double min_roll_degree_ = -5.0;
145 int roi_height_ = 768;
146 int roi_start_ = 312;
147 int roi_width_ = 1920;
149 std::map<std::string, Eigen::Vector2d> vp1_;
150 std::map<std::string, Eigen::Vector2d> vp2_;
152 std::vector<std::string> camera_names_;
153 std::string visual_camera_ =
"front_6mm";
155 std::map<std::string, Eigen::Matrix3f> intrinsic_map_;
156 std::map<std::string, Eigen::Matrix4d> extrinsic_map_;
157 Eigen::Matrix4d ex_lidar2imu_;
158 std::map<std::string, Eigen::Matrix4d> ex_camera2lidar_;
159 Eigen::Matrix4d ex_camera2imu_;
160 Eigen::Matrix4d ex_imu2camera_;
161 Eigen::Matrix4d ex_car2camera_;
162 Eigen::Matrix4d ex_camera2car_;
163 Eigen::Matrix4d ex_imu2car_;
164 Eigen::Matrix4d adjusted_camera2car_ = Eigen::Matrix4d::Identity();
166 Eigen::Matrix4d projection_matrix_;
167 std::map<std::string, Eigen::Matrix3d> K_;
170 bool use_class_color_ =
true;
171 bool capture_screen_ =
false;
172 bool capture_video_ =
false;
173 bool show_camera_box2d_ =
true;
174 bool show_camera_box3d_ =
true;
175 bool show_camera_bdv_ =
true;
176 bool show_virtual_egolane_ =
true;
177 bool show_radar_pc_ =
true;
178 bool show_fusion_ =
false;
179 bool show_associate_color_ =
false;
180 bool show_type_id_label_ =
true;
181 bool show_verbose_ =
false;
182 bool show_trajectory_ =
true;
183 bool show_vp_grid_ =
true;
184 bool draw_lane_objects_ =
true;
185 bool show_box_ =
true;
186 bool show_velocity_ =
false;
187 bool show_polygon_ =
true;
188 bool show_text_ =
false;
189 bool show_help_text_ =
false;
190 bool manual_calibration_mode_ =
false;
191 bool show_homography_object_ =
false;
192 unsigned int show_lane_count_ = 1;
193 std::string help_str_;
195 cv::Scalar color_cipv_ = cv::Scalar(255, 255, 255);
196 cv::Scalar virtual_lane_color_ = cv::Scalar(0, 0, 255);
197 int line_thickness_ = 2;
198 int cipv_line_thickness_ = 6;
199 int trajectory_line_thickness_ = 1;
200 double speed_limit_ = 1.0;
201 unsigned int lane_step_num_ = 20;
203 unsigned int all_camera_recieved_ = 0;
bool write_out_img_
Definition: visualizer.h:106
void draw_selected_image_boundary(const int width, int const height, cv::Mat *image)
Definition: camera_frame.h:33
void Draw2Dand3D_all_info_single_camera(const std::string &camera_name, const cv::Mat &img, const CameraFrame &frame, const Eigen::Matrix3d &intrinsic, const Eigen::Matrix4d &extrinsic, const Eigen::Affine3d &world2camera, const base::MotionBufferPtr motion_buffer)
bool euler_to_quaternion(Eigen::Vector4d *quaternion, const double pitch_radian, const double yaw_radian, const double roll_radian)
std::string type_to_string(const apollo::perception::base::ObjectType type)
Eigen::Vector2d image2ground(const std::string &camera_name, cv::Point p_img)
bool Init(const std::vector< std::string > &camera_names, TransformServer *tf_server)
std::map< std::string, Eigen::Matrix3d > homography_ground2image_
Definition: visualizer.h:110
bool SetDirectory(const std::string &path)
bool key_handler(const std::string &camera_name, const int key)
bool DrawTrajectories(const base::ObjectPtr &object, const base::MotionBufferPtr motion_buffer)
cv::Point ground2image(const std::string &camera_name, Eigen::Vector2d p_ground)
cv::Point world_point_to_bigimg(const Eigen::Vector2d &p)
Definition: visualizer.h:34
bool save_extrinsic_in_yaml(const std::string &camera_name, const Eigen::Matrix4d &extrinsic, const Eigen::Vector4d &quaternion, const double pitch_radian, const double yaw_radian, const double roll_radian)
double regularize_angle(const double angle)
void Set_ROI(int input_offset_y, int crop_height, int crop_width)
Definition: visualizer.h:80
void ShowResult_all_info_single_camera(const cv::Mat &img, const CameraFrame &frame, const base::MotionBufferPtr motion_buffer, const Eigen::Affine3d &world2camera)
std::map< std::string, Eigen::Matrix3d > homography_image2ground_
Definition: visualizer.h:109
bool cv_imshow_img_
Definition: visualizer.h:107
Definition: cipv_camera.h:56
std::string sub_type_to_string(const apollo::perception::base::ObjectSubType type)
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:201
bool save_manual_calibration_parameter(const std::string &camera_name, const double pitch_adj_degree, const double yaw_adj_degree, const double roll_adj_degree)
PointXYZIL Point
Definition: types.h:61
void ShowResult(const cv::Mat &img, const CameraFrame &frame)
Eigen::Matrix3d homography_im2car(std::string camera_name)
Definition: visualizer.h:77
bool Init_all_info_single_camera(const std::vector< std::string > &camera_names, const std::string &visual_camera, const std::map< std::string, Eigen::Matrix3f > &intrinsic_map, const std::map< std::string, Eigen::Matrix4d > &extrinsic_map, const Eigen::Matrix4d &ex_lidar2imu, const double pitch_adj, const double yaw_adj, const double roll_adj, const int image_height, const int image_width)
bool adjust_angles(const std::string &camera_name, const double pitch_adj, const double yaw_adj, const double roll_adj)
ObjectType
Definition: object_types.h:26
ObjectSubType
Definition: object_types.h:63
void Draw2Dand3D(const cv::Mat &img, const CameraFrame &frame)
bool copy_backup_file(const std::string &filename)
std::shared_ptr< Object > ObjectPtr
Definition: object.h:118