Skip to content

Commit 80fc1bf

Browse files
zhouyao4321xiaoxq
authored andcommitted
update logs in map creation
1 parent 8b64e05 commit 80fc1bf

File tree

5 files changed

+40
-37
lines changed

5 files changed

+40
-37
lines changed

modules/localization/msf/common/io/velodyne_utility.cc

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ void LoadPcds(const std::string& file_path, const unsigned int frame_index,
4343
pcl::PointCloud<PointXYZIT>::Ptr cloud(new pcl::PointCloud<PointXYZIT>);
4444
if (pcl::io::loadPCDFile(file_path, *cloud) >= 0) {
4545
if (cloud->height == 1 || cloud->width == 1) {
46-
AERROR << "Un-organized-point-cloud";
46+
AINFO << "Un-organized-point-cloud";
4747
for (unsigned int i = 0; i < cloud->size(); ++i) {
4848
Eigen::Vector3d pt3d;
4949
pt3d[0] = (*cloud)[i].x;
@@ -151,7 +151,7 @@ void LoadPosesAndStds(const std::string& file_path,
151151
timestamps->push_back(timestamp);
152152

153153
Eigen::Vector3d std;
154-
std << std_x, std_y, std_z;
154+
AINFO << std_x, std_y, std_z;
155155
stds->push_back(std);
156156
}
157157
fclose(file);

modules/localization/msf/local_tool/map_creation/lossless_map_creator.cc

Lines changed: 22 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "boost/filesystem.hpp"
1818
#include "boost/program_options.hpp"
1919

20+
#include "cyber/common/log.h"
2021
#include "modules/localization/msf/common/io/velodyne_utility.h"
2122
#include "modules/localization/msf/common/util/extract_ground_plane.h"
2223
#include "modules/localization/msf/common/util/system_utility.h"
@@ -75,16 +76,16 @@ bool ParseCommandLine(int argc, char* argv[],
7576
boost::program_options::store(
7677
boost::program_options::parse_command_line(argc, argv, desc), *vm);
7778
if (vm->count("help")) {
78-
std::cerr << desc << std::endl;
79+
AERROR << desc;
7980
return false;
8081
}
8182
boost::program_options::notify(*vm);
8283
} catch (std::exception& e) {
83-
std::cerr << "Error" << e.what() << std::endl;
84-
std::cerr << desc << std::endl;
84+
AERROR << "Error" << e.what();
85+
AERROR << desc;
8586
return false;
8687
} catch (...) {
87-
std::cerr << "Unknown error!" << std::endl;
88+
AERROR << "Unknown error!";
8889
return false;
8990
}
9091
return true;
@@ -104,7 +105,7 @@ int main(int argc, char** argv) {
104105

105106
boost::program_options::variables_map boost_args;
106107
if (!ParseCommandLine(argc, argv, &boost_args)) {
107-
std::cerr << "Parse input command line failed." << std::endl;
108+
AERROR << "Parse input command line failed.";
108109
return -1;
109110
}
110111

@@ -113,8 +114,7 @@ int main(int argc, char** argv) {
113114
const std::vector<std::string> pose_files =
114115
boost_args["pose_files"].as<std::vector<std::string>>();
115116
if (pcd_folder_paths.size() != pose_files.size()) {
116-
std::cerr << "The count of pcd folders is not equal pose files"
117-
<< std::endl;
117+
AERROR << "The count of pcd folders is not equal pose files";
118118
return -1;
119119
}
120120

@@ -128,14 +128,14 @@ int main(int argc, char** argv) {
128128
boost_args["coordinate_type"].as<std::string>();
129129
if (strcasecmp(coordinate_type.c_str(), "UTM") != 0 &&
130130
strcasecmp(coordinate_type.c_str(), "LTM") != 0) {
131-
std::cerr << "Coordinate type invalid. (UTM or LTM)" << std::endl;
131+
AERROR << "Coordinate type invalid. (UTM or LTM)";
132132
return -1;
133133
}
134134
const std::string map_resolution_type =
135135
boost_args["map_resolution_type"].as<std::string>();
136136
if (strcasecmp(map_resolution_type.c_str(), "single") != 0 &&
137137
strcasecmp(map_resolution_type.c_str(), "multi") != 0) {
138-
std::cerr << "Map resolution type invalid. (single or multi)" << std::endl;
138+
AERROR << "Map resolution type invalid. (single or multi)";
139139
return -1;
140140
}
141141

@@ -150,17 +150,17 @@ int main(int argc, char** argv) {
150150
fabs(single_resolution_map - 4.0) < 1e-8 &&
151151
fabs(single_resolution_map - 8.0) < 1e-8 &&
152152
fabs(single_resolution_map - 16.0) < 1e-8) {
153-
std::cerr << "Map resolution can only be: 0.03125, "
154-
<< "0.0625, 0.125, 0.25, 0.5, 1.0, 2.0, "
155-
<< "4.0, 8.0 or 16.0." << std::endl;
153+
AWARN << "Map resolution can only be: 0.03125, "
154+
<< "0.0625, 0.125, 0.25, 0.5, 1.0, 2.0, "
155+
<< "4.0, 8.0 or 16.0.";
156156
}
157157

158158
const size_t num_trials = pcd_folder_paths.size();
159159

160160
// load all poses
161-
std::cerr << "Pcd folders are as follows:" << std::endl;
161+
AINFO << "Pcd folders are as follows:";
162162
for (size_t i = 0; i < num_trials; ++i) {
163-
std::cerr << pcd_folder_paths[i] << std::endl;
163+
AINFO << pcd_folder_paths[i];
164164
}
165165
std::vector<std::vector<Eigen::Affine3d>> ieout_poses(num_trials);
166166
std::vector<std::vector<double>> time_stamps(num_trials);
@@ -246,8 +246,8 @@ int main(int argc, char** argv) {
246246
}
247247
fclose(file);
248248
} else {
249-
std::cerr << "Can't open file: "
250-
<< "./lossless_map/config.txt" << std::endl;
249+
AERROR << "Can't open file: "
250+
<< "./lossless_map/config.txt";
251251
}
252252

253253
LosslessMapNodePool lossless_map_node_pool(25, 8);
@@ -268,9 +268,9 @@ int main(int argc, char** argv) {
268268
const Eigen::Affine3d& pcd_pose = poses[trial_frame_idx];
269269
apollo::localization::msf::velodyne::LoadPcds(
270270
pcd_file_path, trial_frame_idx, pcd_pose, &velodyne_frame, false);
271-
AERROR << "Loaded " << velodyne_frame.pt3ds.size()
272-
<< "3D Points at Trial: " << trial << " Frame: " << trial_frame_idx
273-
<< ".";
271+
AINFO << "Loaded " << velodyne_frame.pt3ds.size()
272+
<< "3D Points at Trial: " << trial << " Frame: " << trial_frame_idx
273+
<< ".";
274274

275275
for (size_t i = 0; i < velodyne_frame.pt3ds.size(); ++i) {
276276
Eigen::Vector3d& pt3d_local = velodyne_frame.pt3ds[i];
@@ -323,14 +323,14 @@ int main(int argc, char** argv) {
323323
std::vector<unsigned int> layer_counts;
324324
map.GetCountSafe(pt3d, zone_id, resolution_id, &layer_counts);
325325
if (layer_counts.empty()) {
326-
AERROR << "No ground layer, skip.";
326+
AINFO << "No ground layer, skip.";
327327
continue;
328328
}
329329
if (layer_counts[layer_id] > 0) {
330330
std::vector<float> layer_alts;
331331
map.GetAltSafe(pt3d, zone_id, resolution_id, &layer_alts);
332332
if (layer_alts.empty()) {
333-
AERROR << "No ground points, skip.";
333+
AINFO << "No ground points, skip.";
334334
continue;
335335
}
336336
float alt = layer_alts[layer_id];
@@ -355,6 +355,6 @@ int main(int argc, char** argv) {
355355
static_cast<float>(mean_height_diff);
356356
std::string config_path = map.GetConfig().map_folder_path_ + "/config.xml";
357357
map.GetConfig().Save(config_path);
358-
ADEBUG << "Mean: " << mean_height_diff << ", Var: " << var_height_diff << ".";
358+
AINFO << "Mean: " << mean_height_diff << ", Var: " << var_height_diff << ".";
359359
return 0;
360360
}

modules/localization/msf/local_tool/map_creation/lossless_map_to_lossy_map.cc

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <boost/filesystem.hpp>
1818
#include <boost/program_options.hpp>
1919

20+
#include "cyber/common/log.h"
2021
#include "modules/localization/msf/local_map/lossless_map/lossless_map.h"
2122
#include "modules/localization/msf/local_map/lossless_map/lossless_map_config.h"
2223
#include "modules/localization/msf/local_map/lossless_map/lossless_map_matrix.h"
@@ -48,7 +49,7 @@ MapNodeIndex GetMapIndexFromMapFolder(const std::string& map_folder) {
4849
if (zone == "south") {
4950
index.zone_id_ = -index.zone_id_;
5051
}
51-
std::cout << index << std::endl;
52+
AINFO << index;
5253
return index;
5354
}
5455

@@ -123,7 +124,7 @@ int main(int argc, char** argv) {
123124

124125
if (boost_args.count("help") || !boost_args.count("srcdir") ||
125126
!boost_args.count("dstdir")) {
126-
std::cout << boost_desc << std::endl;
127+
AERROR << boost_desc;
127128
return 0;
128129
}
129130

@@ -139,7 +140,7 @@ int main(int argc, char** argv) {
139140
lossless_map.InitMapNodeCaches(12, 24);
140141
lossless_map.AttachMapNodePool(&lossless_map_node_pool);
141142
if (!lossless_map.SetMapFolderPath(src_map_folder)) {
142-
std::cerr << "Reflectance map folder is invalid!" << std::endl;
143+
AERROR << "Reflectance map folder is invalid!";
143144
return -1;
144145
}
145146

@@ -151,14 +152,14 @@ int main(int argc, char** argv) {
151152

152153
std::list<MapNodeIndex> buf;
153154
GetAllMapIndex(src_map_folder, dst_map_folder, &buf);
154-
std::cout << "index size: " << buf.size() << std::endl;
155+
AINFO << "index size: " << buf.size();
155156

156157
LosslessMapConfig config_transform_lossy("lossless_map");
157158
config_transform_lossy.Load(src_map_folder + "config.xml");
158159
config_transform_lossy.map_version_ = "lossy_map";
159160
config_transform_lossy.Save(dst_map_folder + "config.xml");
160161

161-
std::cout << "lossy map directory structure has built." << std::endl;
162+
AINFO << "lossy map directory structure has built.";
162163

163164
LossyMapConfig lossy_config("lossy_map");
164165
LossyMapNodePool lossy_map_node_pool(25, 8);
@@ -167,7 +168,7 @@ int main(int argc, char** argv) {
167168
lossy_map.InitMapNodeCaches(12, 24);
168169
lossy_map.AttachMapNodePool(&lossy_map_node_pool);
169170
if (!lossy_map.SetMapFolderPath(dst_map_folder)) {
170-
std::cout << "lossy_map config xml not exist" << std::endl;
171+
AINFO << "lossy_map config xml not exist";
171172
}
172173

173174
int index = 0;
@@ -184,7 +185,7 @@ int main(int argc, char** argv) {
184185
LosslessMapNode* lossless_node =
185186
static_cast<LosslessMapNode*>(lossless_map.GetMapNodeSafe(*itr));
186187
if (lossless_node == nullptr) {
187-
std::cerr << "index: " << index << " is a nullptr pointer!" << std::endl;
188+
AINFO << "index: " << index << " is a nullptr pointer!";
188189
continue;
189190
}
190191
LosslessMapMatrix& lossless_matrix =

modules/localization/msf/local_tool/map_creation/poses_interpolation/poses_interpolation.cc

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <fstream>
1818

19+
#include "cyber/common/log.h"
1920
#include "modules/localization/msf/common/io/velodyne_utility.h"
2021
#include "modules/localization/msf/local_tool/map_creation/poses_interpolation/poses_interpolation.h"
2122

@@ -35,7 +36,7 @@ bool PosesInterpolation::Init(const std::string &input_poses_path,
3536

3637
bool success = velodyne::LoadExtrinsic(extrinsic_path_, &velodyne_extrinsic_);
3738
if (!success) {
38-
std::cerr << "Load lidar extrinsic failed." << std::endl;
39+
AERROR << "Load lidar extrinsic failed.";
3940
return false;
4041
}
4142

@@ -72,7 +73,7 @@ void PosesInterpolation::LoadPCDTimestamp() {
7273
}
7374
fclose(file);
7475
} else {
75-
std::cerr << "Can't open file to read: " << ref_timestamps_path_;
76+
AINFO << "Can't open file to read: " << ref_timestamps_path_;
7677
}
7778
}
7879

@@ -101,7 +102,7 @@ void PosesInterpolation::WritePCDPoses() {
101102

102103
fout.close();
103104
} else {
104-
std::cerr << "Can't open file to write: " << out_poses_path_ << std::endl;
105+
AERROR << "Can't open file to write: " << out_poses_path_ << std::endl;
105106
}
106107
} // namespace msf
107108

@@ -156,10 +157,10 @@ void PosesInterpolation::PoseInterpolationByTime(
156157
out_timestamps->push_back(ref_timestamp);
157158
}
158159
} else {
159-
std::cerr << "[ERROR] No more poses. Exit now." << std::endl;
160+
AWARN << "[WARN] No more poses. Exit now.";
160161
break;
161162
}
162-
std::cout << "Frame_id: " << i << std::endl;
163+
AINFO << "Frame_id: " << i;
163164
}
164165
}
165166

modules/localization/msf/local_tool/map_creation/poses_interpolator.cc

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <boost/program_options.hpp>
1818

19+
#include "cyber/common/log.h"
1920
#include "modules/localization/msf/local_tool/map_creation/poses_interpolation/poses_interpolation.h"
2021

2122
int main(int argc, char **argv) {
@@ -40,7 +41,7 @@ int main(int argc, char **argv) {
4041
!boost_args.count("ref_timestamps_path") ||
4142
!boost_args.count("extrinsic_path") ||
4243
!boost_args.count("output_poses_path")) {
43-
std::cout << boost_desc << std::endl;
44+
AERROR << boost_desc;
4445
return 0;
4546
}
4647

0 commit comments

Comments
 (0)