169 bool Init(
const std::string &map_folder,
const std::string &map_visual_folder,
170 const VisualMapParam &map_param,
const unsigned int resolution_id,
171 const int zone_id,
const Eigen::Affine3d &extrinsic,
172 const unsigned int loc_info_num = 1);
174 const ::apollo::common::EigenVector3dVec &cloud);
177 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
180 void Preprocess(
const std::string &map_folder,
181 const std::string &map_visual_folder);
183 void DrawLoc(
const cv::Point &bias);
184 void DrawStd(
const cv::Point &bias);
185 void DrawCloud(
const cv::Point &bias);
186 void DrawTrajectory(
const cv::Point &bias);
193 void GenerateMutiResolutionImages(
const std::vector<std::string> &src_files,
194 const int base_path_length,
195 const std::string &dst_folder);
196 void InitOtherParams(
const int x_min,
const int y_min,
const int x_max,
197 const int y_max,
const int level,
198 const std::string &path);
199 bool InitOtherParams(
const std::string ¶ms_file);
202 void CloudToMat(
const Eigen::Affine3d &cur_pose,
203 const Eigen::Affine3d &velodyne_extrinsic,
204 const ::apollo::common::EigenVector3dVec &cloud,
205 cv::Mat *cloud_img, cv::Mat *cloud_img_mask);
206 void CoordToImageKey(
const Eigen::Vector2d &coord,
MapImageKey *key);
208 cv::Point CoordToMapGridIndex(
const Eigen::Vector2d &coord,
209 const unsigned int resolution_id,
212 cv::Point MapGridIndexToNodeGridIndex(
const cv::Point &p);
216 void RotateImg(
const cv::Mat &in_img, cv::Mat *out_img,
double angle);
218 void SetViewCenter(
const double center_x,
const double center_y);
219 void UpdateViewCenter(
const double move_x,
const double move_y);
220 void SetScale(
const double scale);
221 void UpdateScale(
const double factor);
222 bool UpdateCarLocId();
223 bool UpdateCarLocId(
const unsigned int car_loc_id);
224 bool UpdateTrajectoryGroups();
225 void ProcessKey(
int key);
227 inline void QuaternionToEuler(
const double quaternion[4],
double att[3]) {
229 2 * (quaternion[2] * quaternion[3] + quaternion[0] * quaternion[1]);
231 2 * (quaternion[1] * quaternion[3] - quaternion[0] * quaternion[2]);
233 quaternion[0] * quaternion[0] - quaternion[1] * quaternion[1] -
234 quaternion[2] * quaternion[2] + quaternion[3] * quaternion[3];
236 2 * (quaternion[1] * quaternion[2] - quaternion[0] * quaternion[3]);
238 quaternion[0] * quaternion[0] - quaternion[1] * quaternion[1] +
239 quaternion[2] * quaternion[2] - quaternion[3] * quaternion[3];
241 att[0] = asin(dcm21);
242 att[1] = atan2(-dcm20, dcm22);
243 att[2] = atan2(dcm01, dcm11);
249 std::string map_folder_;
250 std::string map_visual_folder_;
252 unsigned int zone_id_ = 50;
253 unsigned int resolution_id_ = 0;
255 std::string image_visual_resolution_path_;
256 std::string image_visual_leaf_path_;
259 cv::Point lt_node_index_;
260 cv::Point lt_node_grid_index_;
262 std::string window_name_ =
"Local Visualizer";
263 cv::Mat image_window_;
265 cv::Mat subMat_[3][3];
266 cv::Mat tips_window_;
268 Eigen::Vector2d _view_center;
269 double cur_scale_ = 1.0;
275 bool is_init_ =
false;
276 bool follow_car_ =
true;
277 bool auto_play_ =
false;
279 Eigen::Affine3d car_pose_;
282 cv::Mat cloud_img_mask_;
283 Eigen::Vector2d cloud_img_lt_coord_;
284 Eigen::Affine3d velodyne_extrinsic_;
286 unsigned int loc_info_num_ = 1;
287 unsigned int car_loc_id_ = 0;
288 unsigned int expected_car_loc_id_ = 0;
290 std::vector<std::map<double, Eigen::Vector2d>> trajectory_groups_;
292 bool is_draw_car_ =
true;
293 bool is_draw_trajectory_ =
true;
294 bool is_draw_std_ =
true;
295 std::vector<cv::Mat> car_img_mats_;
bool Init(const std::string &map_folder, const std::string &map_visual_folder, const VisualMapParam &map_param, const unsigned int resolution_id, const int zone_id, const Eigen::Affine3d &extrinsic, const unsigned int loc_info_num=1)
void set(const std::vector< float > &map_resolutions, const unsigned int map_node_size_x, const unsigned int map_node_size_y, const double map_min_x, const double map_min_y, const double map_max_x, const double map_max_y)