Skip to content

Commit cdd2c77

Browse files
zhouyao4321xiaoxq
authored andcommitted
fix bug
1 parent 80fc1bf commit cdd2c77

File tree

5 files changed

+14
-18
lines changed

5 files changed

+14
-18
lines changed

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -151,7 +151,7 @@ void LoadPosesAndStds(const std::string& file_path,
151151
timestamps->push_back(timestamp);
152152

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

modules/localization/msf/common/util/extract_ground_plane.h

+6-8
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include "pcl/sample_consensus/ransac.h"
2525
#include "pcl/sample_consensus/sac_model_plane.h"
2626

27+
#include "cyber/common/log.h"
2728
#include "modules/localization/msf/common/util/voxel_grid_covariance_hdmap.h"
2829

2930
namespace apollo {
@@ -108,21 +109,18 @@ class FeatureXYPlane {
108109
cloud_tmp += it->second.cloud_;
109110
}
110111
}
111-
std::cerr << "the " << iter << " interation: plane_num = " << plane_num
112-
<< std::endl;
112+
AINFO << "the " << iter << " interation: plane_num = " << plane_num;
113113
total_plane_num += plane_num;
114114
pointcloud_ptr.reset(new PointCloudT);
115115
*pointcloud_ptr = cloud_tmp;
116116
}
117117

118118
*non_xy_plane_cloud_ = *pointcloud_ptr;
119119
plane_time = std::clock() - plane_time;
120-
std::cerr << "plane_patch takes:"
121-
<< static_cast<double>(plane_time) / CLOCKS_PER_SEC << "sec."
122-
<< std::endl;
123-
std::cerr << "total_plane_num = " << total_plane_num << std::endl;
124-
std::cerr << "total_points_num = " << xy_plane_cloud_->points.size()
125-
<< std::endl;
120+
AINFO << "plane_patch takes:"
121+
<< static_cast<double>(plane_time) / CLOCKS_PER_SEC << "sec.";
122+
AINFO << "total_plane_num = " << total_plane_num;
123+
AINFO << "total_points_num = " << xy_plane_cloud_->points.size();
126124
return;
127125
}
128126

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

+4-6
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,7 @@ bool ParseCommandLine(int argc, char* argv[],
8181
}
8282
boost::program_options::notify(*vm);
8383
} catch (std::exception& e) {
84-
AERROR << "Error" << e.what();
85-
AERROR << desc;
84+
AERROR << "Error: " << e.what() << " " << desc;
8685
return false;
8786
} catch (...) {
8887
AERROR << "Unknown error!";
@@ -246,8 +245,7 @@ int main(int argc, char** argv) {
246245
}
247246
fclose(file);
248247
} else {
249-
AERROR << "Can't open file: "
250-
<< "./lossless_map/config.txt";
248+
AERROR << "Can't open file: " << file_buf;
251249
}
252250

253251
LosslessMapNodePool lossless_map_node_pool(25, 8);
@@ -323,14 +321,14 @@ int main(int argc, char** argv) {
323321
std::vector<unsigned int> layer_counts;
324322
map.GetCountSafe(pt3d, zone_id, resolution_id, &layer_counts);
325323
if (layer_counts.empty()) {
326-
AINFO << "No ground layer, skip.";
324+
ADEBUG << "No ground layer, skip.";
327325
continue;
328326
}
329327
if (layer_counts[layer_id] > 0) {
330328
std::vector<float> layer_alts;
331329
map.GetAltSafe(pt3d, zone_id, resolution_id, &layer_alts);
332330
if (layer_alts.empty()) {
333-
AINFO << "No ground points, skip.";
331+
ADEBUG << "No ground points, skip.";
334332
continue;
335333
}
336334
float alt = layer_alts[layer_id];

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

+2-2
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ MapNodeIndex GetMapIndexFromMapFolder(const std::string& map_folder) {
4949
if (zone == "south") {
5050
index.zone_id_ = -index.zone_id_;
5151
}
52-
AINFO << index;
52+
ADEBUG << index;
5353
return index;
5454
}
5555

@@ -185,7 +185,7 @@ int main(int argc, char** argv) {
185185
LosslessMapNode* lossless_node =
186186
static_cast<LosslessMapNode*>(lossless_map.GetMapNodeSafe(*itr));
187187
if (lossless_node == nullptr) {
188-
AINFO << "index: " << index << " is a nullptr pointer!";
188+
AWARN << "index: " << index << " is a nullptr pointer!";
189189
continue;
190190
}
191191
LosslessMapMatrix& lossless_matrix =

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,7 @@ void PosesInterpolation::PoseInterpolationByTime(
160160
AWARN << "[WARN] No more poses. Exit now.";
161161
break;
162162
}
163-
AINFO << "Frame_id: " << i;
163+
ADEBUG << "Frame_id: " << i;
164164
}
165165
}
166166

0 commit comments

Comments
 (0)