Skip to content

Commit

Permalink
clear warnings in lidar (ApolloAuto#2222)
Browse files Browse the repository at this point in the history
  • Loading branch information
KaWaiTsoiBaidu authored and Jiangtao Hu committed Dec 13, 2018
1 parent 7c706db commit 57ec58e
Show file tree
Hide file tree
Showing 8 changed files with 34 additions and 26 deletions.
25 changes: 14 additions & 11 deletions modules/perception/lidar/common/feature_descriptor.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,25 +40,28 @@ class FeatureDescriptor {
int zstep = bin_size;
int stat_len = xstep + ystep + zstep;
std::vector<int> stat_feat(stat_len, 0);
float xsize = (max_pt_.x - min_pt_.x) / xstep + 0.000001;
float ysize = (max_pt_.y - min_pt_.y) / ystep + 0.000001;
float zsize = (max_pt_.z - min_pt_.z) / zstep + 0.000001;
float xsize = (max_pt_.x - min_pt_.x) /
static_cast<float>(xstep) + 0.000001f;
float ysize = (max_pt_.y - min_pt_.y) /
static_cast<float>(ystep) + 0.000001f;
float zsize = (max_pt_.z - min_pt_.z) /
static_cast<float>(zstep) + 0.000001f;

int pt_num = cloud_->size();
int pt_num = static_cast<int>(cloud_->size());
for (int i = 0; i < pt_num; ++i) {
base::PointF& pt = cloud_->at(i);
++stat_feat[static_cast<int>((pt.x - min_pt_.x) / xsize)];
++stat_feat[static_cast<int>(xstep + (pt.y - min_pt_.y) / ysize)];
++stat_feat[static_cast<int>(xstep + ystep + (pt.z - min_pt_.z) / zsize)];
++stat_feat[xstep + static_cast<int>((pt.y - min_pt_.y) / ysize)];
++stat_feat[xstep + ystep + static_cast<int>((pt.z - min_pt_.z) / zsize)];
}

feature[0] = center_pt_.x / 10.0;
feature[1] = center_pt_.y / 10.0;
feature[0] = center_pt_.x / 10.0f;
feature[1] = center_pt_.y / 10.0f;
feature[2] = center_pt_.z;
feature[3] = xsize;
feature[4] = ysize;
feature[5] = zsize;
feature[6] = pt_num;
feature[6] = static_cast<float>(pt_num);
for (size_t i = 0; i < stat_feat.size(); ++i) {
feature[i + 7] =
static_cast<float>(stat_feat[i]) / static_cast<float>(pt_num);
Expand All @@ -73,8 +76,8 @@ class FeatureDescriptor {
min_pt_.x = min_pt_.y = min_pt_.z = FLT_MAX;
max_pt_.x = max_pt_.y = max_pt_.z = -FLT_MAX;

int pt_num = cloud_->size();
for (int i = 0; i < pt_num; ++i) {
float pt_num = static_cast<float>(cloud_->size());
for (int i = 0; i < static_cast<int>(pt_num); ++i) {
base::PointF& pt = cloud_->at(i);
xsum += pt.x;
ysum += pt.y;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,8 @@ bool DrawPolygonMask(const typename PolygonScanCvter<T>::Polygon& polygon,
std::vector<std::vector<IntervalOut>> scans_intervals;
if (no_edge_table) {
size_t scans_size =
(valid_range.second - valid_range.first) / cell_size[major_dir];
static_cast<size_t>((valid_range.second - valid_range.first) /
cell_size[major_dir]);
scans_intervals.resize(scans_size);
for (size_t i = 0; i < scans_size; ++i) {
double scan_loc = valid_range.first + i * cell_size[major_dir];
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ void PolygonScanCvter<T>::ScansCvt(

bottom_x_ = scans_interval.first;
double top_x = scans_interval.second;
scans_size_ = (top_x - bottom_x_) / step_;
scans_size_ = static_cast<size_t>((top_x - bottom_x_) / step_);

top_segments_.clear();
top_segments_.reserve(2);
Expand Down Expand Up @@ -270,7 +270,7 @@ void PolygonScanCvter<T>::DisturbPolygon(const DirectionMajor dir_major) {
for (auto& pt : polygon_disturbed_) {
double& x = pt[dir_major];
double d_x = (x - bottom_x_) / step_;
int int_d_x = std::round(d_x);
int int_d_x = static_cast<int>(std::round(d_x));
double delta_x = d_x - int_d_x;
if (std::abs(delta_x) < s_epsilon_) {
if (delta_x > 0) {
Expand Down Expand Up @@ -455,7 +455,7 @@ bool PolygonScanCvter<T>::ConvertSegment(const size_t seg_id,
const Point& min_vertex = segment.first;
double min_x = min_vertex[dir_major_] - bottom_x_;
double min_y = min_vertex[op_dir_major_];
x_id = std::ceil(min_x / step_);
x_id = static_cast<int>(std::ceil(min_x / step_));
double min_x_ceil = x_id * step_;

edge.x = min_x_ceil;
Expand Down
2 changes: 1 addition & 1 deletion modules/perception/lidar/lib/scene_manager/scene_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class SceneManager {
const SceneManagerInitOptions& options = SceneManagerInitOptions());

int GetServiceNum() const {
return services_.size();
return static_cast<int>(services_.size());
}

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class FeatureGenerator {
if (count < static_cast<int>(log_table_.size())) {
return log_table_[count];
}
return log(static_cast<float>(1 + count));
return logf(static_cast<float>(1 + count));
}

// log table for CPU, with std::vector type
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ class SppLabelImage {
// @param [in]: pixel x
// @param [in]: pixel y
void AddPixelSample(size_t id, uint16_t x, uint16_t y) {
return AddPixelSample(id, y * width_ + x);
return AddPixelSample(id, y * static_cast<uint32_t>(width_) + x);
}
// @brief: add a pixel to labeled cluster
// @param [in]: label id
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,10 +91,14 @@ class SppCCDetector {
status &= 63488;
status |= node_rank;
}
inline uint16_t get_traversed() { return (status & 14336) >> 11; }
inline uint16_t get_traversed() {
uint16_t pattern = 14336;
return static_cast<uint16_t>((status & pattern) >> 11);
}
inline void set_traversed(uint16_t traversed) {
status &= 51199;
status |= (traversed & 7) << 11;
uint16_t pattern = 7;
status |= static_cast<uint16_t>((traversed & pattern) << 11);
}
inline bool is_center() { return static_cast<bool>(status & 32768); }
inline void set_is_center(bool is_center) {
Expand Down
12 changes: 6 additions & 6 deletions modules/perception/lidar/lib/segmentation/cnnseg/util.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,20 +39,20 @@ inline int F2I(float val, float ori, float scale) {
// for axis rotated case
inline void GroupPc2Pixel(float pc_x, float pc_y, float scale, float range,
int* x, int* y) {
float fx = (range - (0.707107 * (pc_x + pc_y))) * scale;
float fy = (range - (0.707107 * (pc_x - pc_y))) * scale;
*x = fx < 0 ? -1.f : static_cast<int>(fx);
*y = fy < 0 ? -1.f : static_cast<int>(fy);
float fx = (range - (0.707107f * (pc_x + pc_y))) * scale;
float fy = (range - (0.707107f * (pc_x - pc_y))) * scale;
*x = fx < 0 ? -1 : static_cast<int>(fx);
*y = fy < 0 ? -1 : static_cast<int>(fy);
}

// for axis aligned case
inline int Pc2Pixel(float in_pc, float in_range, float out_size) {
float inv_res = 0.5 * out_size / in_range;
float inv_res = 0.5f * out_size / in_range;
return static_cast<int>(std::floor((in_range - in_pc) * inv_res));
}

inline float Pixel2Pc(int in_pixel, float in_size, float out_range) {
float res = 2.0 * out_range / in_size;
float res = 2.0f * out_range / in_size;
return out_range - (static_cast<float>(in_pixel) + 0.5f) * res;
}

Expand Down

0 comments on commit 57ec58e

Please sign in to comment.