Skip to content

Commit

Permalink
fixed lots of warnings with gcc 9.4.0
Browse files Browse the repository at this point in the history
fixed all warning shown on my system
  • Loading branch information
frankhoeller committed Feb 9, 2024
1 parent f14763b commit 3fde50f
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 29 deletions.
4 changes: 2 additions & 2 deletions include/label_generator/label_generator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void save_ground_label(const std::string abs_dir, const int frame_num,
int num_cloud_raw = cloud_raw.points.size();
std::vector<uint32_t> labels(num_cloud_raw, EST_NON_GROUND); // 0: Non ground points

int N = cloud_est_ground.points.size();
size_t N = cloud_est_ground.points.size();
PointCloud<num_t> cloud;
cloud.pts.resize(N);
for (size_t i = 0; i < N; i++) {
Expand All @@ -69,7 +69,7 @@ void save_ground_label(const std::string abs_dir, const int frame_num,
my_kd_tree_t index(3 /*dim*/, cloud, {10 /* max leaf */});

int num_valid = 0;
for (int j = 0; j < cloud_raw.points.size(); ++j) {
for (size_t j = 0; j < cloud_raw.points.size(); ++j) {
const auto query_pcl = cloud_raw.points[j];
const num_t query_pt[3] = {query_pcl.x, query_pcl.y, query_pcl.z};

Expand Down
39 changes: 18 additions & 21 deletions include/patchwork/patchwork.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ void PatchWork<PointT>::extract_initial_seeds_(
static double lowest_h_margin_in_close_zone = (sensor_height_ == 0.0) ? -0.1 : adaptive_seed_selection_margin_ *
sensor_height_;
if (zone_idx == 0) {
for (int i = 0; i < p_sorted.points.size(); i++) {
for (size_t i = 0; i < p_sorted.points.size(); i++) {
if (p_sorted.points[i].z < lowest_h_margin_in_close_zone) {
++init_idx;
} else {
Expand All @@ -394,14 +394,14 @@ void PatchWork<PointT>::extract_initial_seeds_(
}

// Calculate the mean height value.
for (int i = init_idx; i < p_sorted.points.size() && cnt < num_lpr_; i++) {
for (size_t i = init_idx; i < p_sorted.points.size() && cnt < num_lpr_; i++) {
sum += p_sorted.points[i].z;
cnt++;
}
double lpr_height = cnt != 0 ? sum / cnt : 0;// in case divide by 0

// iterate pointcloud, filter those height is less than lpr.height+th_seeds_
for (int i = 0; i < p_sorted.points.size(); i++) {
for (size_t i = 0; i < p_sorted.points.size(); i++) {
if (p_sorted.points[i].z < lpr_height + th_seeds_) {
init_seeds.points.push_back(p_sorted.points[i]);
}
Expand All @@ -412,16 +412,15 @@ inline
double PatchWork<PointT>::consensus_set_based_height_estimation(const Eigen::RowVectorXd& X,
const Eigen::RowVectorXd& ranges,
const Eigen::RowVectorXd& weights) {
// check input parameters
bool dimension_inconsistent = (X.rows() != ranges.rows()) || (X.cols() != ranges.cols());
// check input parameters - dimension inconsistent test
assert(!( (X.rows() != ranges.rows()) || (X.cols() != ranges.cols()) ));

bool only_one_element = (X.rows() == 1) && (X.cols() == 1);
assert(!dimension_inconsistent);
assert(!only_one_element); // TODO: admit a trivial solution
// check input parameters - only one element test
assert(!( (X.rows() == 1) && (X.cols() == 1) )); // TODO: admit a trivial solution

int N = X.cols();
std::vector<std::pair<double, int>> h;
for (size_t i= 0 ;i < N ;++i){
for (size_t i= 0; (int)i < N ;++i){
h.push_back(std::make_pair(X(i) - ranges(i), i+1));
h.push_back(std::make_pair(X(i) + ranges(i), -i-1));
}
Expand All @@ -440,7 +439,7 @@ double PatchWork<PointT>::consensus_set_based_height_estimation(const Eigen::Row
double sum_xi = 0;
double sum_xi_square = 0;

for (size_t i = 0 ; i < nr_centers ; ++i){
for (size_t i = 0 ; (int)i < nr_centers ; ++i){

int idx = int(std::abs(h.at(i).second)) - 1; // Indices starting at 1
int epsilon = (h.at(i).second > 0) ? 1 : -1;
Expand Down Expand Up @@ -471,7 +470,7 @@ void PatchWork<PointT>::estimate_sensor_height(pcl::PointCloud<PointT> cloud_in)
// ATAT: All-Terrain Automatic HeighT estimator
Ring ring_for_ATAT(num_sectors_for_ATAT_);
for (auto const &pt : cloud_in.points) {
int ring_idx, sector_idx;
int sector_idx;
double r = xy2radius(pt.x, pt.y);

float sector_size_for_ATAT = 2 * M_PI / num_sectors_for_ATAT_;
Expand All @@ -490,7 +489,7 @@ void PatchWork<PointT>::estimate_sensor_height(pcl::PointCloud<PointT> cloud_in)
vector<double> planarities;
for (int i = 0; i < num_sectors_for_ATAT_; ++i) {

if(ring_for_ATAT[i].size() < num_min_pts_ ){ continue; }
if((int)ring_for_ATAT[i].size() < num_min_pts_ ){ continue; }

pcl::PointCloud<PointT> dummy_est_ground;
pcl::PointCloud<PointT> dummy_est_non_ground;
Expand Down Expand Up @@ -549,9 +548,9 @@ void PatchWork<PointT>::estimate_ground(
initialized_ = false;
}

static double start, t0, t1, t2, end;

double t_total_ground = 0.0;
static double start, end;
// static double start, t0, t1, t2;
// double t_total_ground = 0.0;
double t_total_estimate = 0.0;
// 1.Msg to pointcloud
pcl::PointCloud<PointT> cloud_in_tmp = cloud_in;
Expand All @@ -562,7 +561,7 @@ void PatchWork<PointT>::estimate_ground(
// As there are some error mirror reflection under the ground,
// Sort point according to height, here uses z-axis in default
// -2.0 is a rough criteria
int i = 0;
size_t i = 0;
while (i < cloud_in_tmp.points.size()) {
if (cloud_in_tmp.points[i].z < -sensor_height_ - 2.0) {
std::iter_swap(cloud_in_tmp.points.begin() + i, cloud_in_tmp.points.end() - 1);
Expand All @@ -572,7 +571,7 @@ void PatchWork<PointT>::estimate_ground(
}
}

t1 = ros::Time::now().toSec();
// t1 = ros::Time::now().toSec();

for (int k = 0; k < num_zones_; ++k) {
flush_patches_in_zone(ConcentricZoneModel_[k], num_sectors_each_zone_[k], num_rings_each_zone_[k]);
Expand Down Expand Up @@ -606,13 +605,11 @@ void PatchWork<PointT>::estimate_ground(
auto &regionwise_nonground = regionwise_nongrounds_[i];
auto &status = statuses_[i];

if (patch.points.size() > num_min_pts_) {
double t_tmp0 = ros::Time::now().toSec();
if ((int)patch.points.size() > num_min_pts_) {
// 22.05.02 update
// Region-wise sorting is adopted, which is much faster than global sorting!
sort(patch.points.begin(), patch.points.end(), point_z_cmp<PointT>);
extract_piecewiseground(zone_idx, patch, feat, regionwise_ground, regionwise_nonground);
double t_tmp1 = ros::Time::now().toSec();

const double ground_z_vec = abs(feat.normal_(2));
const double ground_z_elevation = feat.mean_(2);
Expand Down Expand Up @@ -641,7 +638,7 @@ void PatchWork<PointT>::estimate_ground(
const int sector_idx = patch_idx.sector_idx_;
const int concentric_idx = patch_idx.concentric_idx_;

const auto &patch = ConcentricZoneModel_[zone_idx][ring_idx][sector_idx];
// const auto &patch = ConcentricZoneModel_[zone_idx][ring_idx][sector_idx];
const auto &feat = features_[i];
const auto &regionwise_ground = regionwise_grounds_[i];
const auto &regionwise_nonground = regionwise_nongrounds_[i];
Expand Down
9 changes: 4 additions & 5 deletions include/patchwork/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZILID,
(float, y, y)
(float, z, z)
(float, intensity, intensity)
(uint16_t, label, label)
(uint16_t, id, id))
(std::uint16_t, label, label)
(std::uint16_t, id, id))


void PointXYZILID2XYZI(pcl::PointCloud<PointXYZILID>& src,
Expand Down Expand Up @@ -106,14 +106,13 @@ int count_num_ground(const pcl::PointCloud<PointXYZILID>& pc){

std::map<int, int> set_initial_gt_counts(std::vector<int>& gt_classes){
map<int, int> gt_counts;
for (int i = 0; i< gt_classes.size(); ++i){
for (size_t i = 0; i< gt_classes.size(); ++i){
gt_counts.insert(pair<int,int>(gt_classes.at(i), 0));
}
return gt_counts;
}

std::map<int, int> count_num_each_class(const pcl::PointCloud<PointXYZILID>& pc){
int num_ground = 0;
auto gt_counts = set_initial_gt_counts(ground_classes);
std::vector<int>::iterator iter;

Expand Down Expand Up @@ -184,7 +183,7 @@ void calculate_precision_recall(const pcl::PointCloud<PointXYZILID>& pc_curr,
}
}

int save_all_labels(const pcl::PointCloud<PointXYZILID>& pc, string ABS_DIR, string seq, int count){
void save_all_labels(const pcl::PointCloud<PointXYZILID>& pc, string ABS_DIR, string seq, int count){

std::string count_str = std::to_string(count);
std::string count_str_padded = std::string(NUM_ZEROS - count_str.length(), '0') + count_str;
Expand Down
2 changes: 1 addition & 1 deletion include/tools/kitti_loader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class KittiLoader {
std::vector<uint32_t> labels(num_points);
label_input.read((char*)&labels[0], num_points * sizeof(uint32_t));

for (int i = 0; i < num_points; i++) {
for (size_t i = 0; i < num_points; i++) {
auto &pt = cloud.at(i);
pt.x = buffer[i * 4];
pt.y = buffer[i * 4 + 1];
Expand Down

0 comments on commit 3fde50f

Please sign in to comment.