17
17
#include " boost/filesystem.hpp"
18
18
#include " boost/program_options.hpp"
19
19
20
+ #include " cyber/common/log.h"
20
21
#include " modules/localization/msf/common/io/velodyne_utility.h"
21
22
#include " modules/localization/msf/common/util/extract_ground_plane.h"
22
23
#include " modules/localization/msf/common/util/system_utility.h"
@@ -75,16 +76,16 @@ bool ParseCommandLine(int argc, char* argv[],
75
76
boost::program_options::store (
76
77
boost::program_options::parse_command_line (argc, argv, desc), *vm);
77
78
if (vm->count (" help" )) {
78
- std::cerr << desc << std::endl ;
79
+ AERROR << desc;
79
80
return false ;
80
81
}
81
82
boost::program_options::notify (*vm);
82
83
} 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;
85
86
return false ;
86
87
} catch (...) {
87
- std::cerr << " Unknown error!" << std::endl ;
88
+ AERROR << " Unknown error!" ;
88
89
return false ;
89
90
}
90
91
return true ;
@@ -104,7 +105,7 @@ int main(int argc, char** argv) {
104
105
105
106
boost::program_options::variables_map boost_args;
106
107
if (!ParseCommandLine (argc, argv, &boost_args)) {
107
- std::cerr << " Parse input command line failed." << std::endl ;
108
+ AERROR << " Parse input command line failed." ;
108
109
return -1 ;
109
110
}
110
111
@@ -113,8 +114,7 @@ int main(int argc, char** argv) {
113
114
const std::vector<std::string> pose_files =
114
115
boost_args[" pose_files" ].as <std::vector<std::string>>();
115
116
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" ;
118
118
return -1 ;
119
119
}
120
120
@@ -128,14 +128,14 @@ int main(int argc, char** argv) {
128
128
boost_args[" coordinate_type" ].as <std::string>();
129
129
if (strcasecmp (coordinate_type.c_str (), " UTM" ) != 0 &&
130
130
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)" ;
132
132
return -1 ;
133
133
}
134
134
const std::string map_resolution_type =
135
135
boost_args[" map_resolution_type" ].as <std::string>();
136
136
if (strcasecmp (map_resolution_type.c_str (), " single" ) != 0 &&
137
137
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)" ;
139
139
return -1 ;
140
140
}
141
141
@@ -150,17 +150,17 @@ int main(int argc, char** argv) {
150
150
fabs (single_resolution_map - 4.0 ) < 1e-8 &&
151
151
fabs (single_resolution_map - 8.0 ) < 1e-8 &&
152
152
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." ;
156
156
}
157
157
158
158
const size_t num_trials = pcd_folder_paths.size ();
159
159
160
160
// load all poses
161
- std::cerr << " Pcd folders are as follows:" << std::endl ;
161
+ AINFO << " Pcd folders are as follows:" ;
162
162
for (size_t i = 0 ; i < num_trials; ++i) {
163
- std::cerr << pcd_folder_paths[i] << std::endl ;
163
+ AINFO << pcd_folder_paths[i];
164
164
}
165
165
std::vector<std::vector<Eigen::Affine3d>> ieout_poses (num_trials);
166
166
std::vector<std::vector<double >> time_stamps (num_trials);
@@ -246,8 +246,8 @@ int main(int argc, char** argv) {
246
246
}
247
247
fclose (file);
248
248
} 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" ;
251
251
}
252
252
253
253
LosslessMapNodePool lossless_map_node_pool (25 , 8 );
@@ -268,9 +268,9 @@ int main(int argc, char** argv) {
268
268
const Eigen::Affine3d& pcd_pose = poses[trial_frame_idx];
269
269
apollo::localization::msf::velodyne::LoadPcds (
270
270
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
+ << " ." ;
274
274
275
275
for (size_t i = 0 ; i < velodyne_frame.pt3ds .size (); ++i) {
276
276
Eigen::Vector3d& pt3d_local = velodyne_frame.pt3ds [i];
@@ -323,14 +323,14 @@ int main(int argc, char** argv) {
323
323
std::vector<unsigned int > layer_counts;
324
324
map.GetCountSafe (pt3d, zone_id, resolution_id, &layer_counts);
325
325
if (layer_counts.empty ()) {
326
- AERROR << " No ground layer, skip." ;
326
+ AINFO << " No ground layer, skip." ;
327
327
continue ;
328
328
}
329
329
if (layer_counts[layer_id] > 0 ) {
330
330
std::vector<float > layer_alts;
331
331
map.GetAltSafe (pt3d, zone_id, resolution_id, &layer_alts);
332
332
if (layer_alts.empty ()) {
333
- AERROR << " No ground points, skip." ;
333
+ AINFO << " No ground points, skip." ;
334
334
continue ;
335
335
}
336
336
float alt = layer_alts[layer_id];
@@ -355,6 +355,6 @@ int main(int argc, char** argv) {
355
355
static_cast <float >(mean_height_diff);
356
356
std::string config_path = map.GetConfig ().map_folder_path_ + " /config.xml" ;
357
357
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 << " ." ;
359
359
return 0 ;
360
360
}
0 commit comments