Skip to content

Commit

Permalink
Fix code style issues with clang_format
Browse files Browse the repository at this point in the history
  • Loading branch information
WATonomousAdmin committed Sep 20, 2024
1 parent 7f06596 commit 5915c67
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class OccupancySegmentationCore {
std::vector<float> FLATNESS_THR;
std::vector<float> ELEVATION_THR;
std::vector<double> lmins = {L_MIN, (7 * L_MIN + L_MAX) / 8, (3 * L_MIN + L_MAX) / 4,
(L_MIN + L_MAX) / 2};
(L_MIN + L_MAX) / 2};
std::vector<double> lmaxs = {lmins[1], lmins[2], lmins[3], L_MAX};

int num_patches = -1;
Expand All @@ -95,12 +95,14 @@ class OccupancySegmentationCore {
std::vector<Status> _statuses;

OccupancySegmentationCore();
OccupancySegmentationCore(int num_zones, float l_min, float l_max, float md, float mh, int min_num_points,
int num_seed_points, float th_seeds, float uprightness_thresh,
int num_rings_of_interest, float sensor_height, float global_el_thresh,
OccupancySegmentationCore(int num_zones, float l_min, float l_max, float md, float mh,
int min_num_points, int num_seed_points, float th_seeds,
float uprightness_thresh, int num_rings_of_interest,
float sensor_height, float global_el_thresh,
std::vector<long int, std::allocator<long int>> &zone_rings,
std::vector<long int, std::allocator<long int>> &zone_sectors,
std::vector<double> &flatness_thr, std::vector<double> &elevation_thr, bool adaptive_selection_en);
std::vector<double> &flatness_thr, std::vector<double> &elevation_thr,
bool adaptive_selection_en);

void segment_ground(pcl::PointCloud<PointT> &unfiltered_cloud, pcl::PointCloud<PointT> &ground,
pcl::PointCloud<PointT> &nonground);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,13 @@ template class OccupancySegmentationCore<PointXYZIRT>;

template <typename PointT>
OccupancySegmentationCore<PointT>::OccupancySegmentationCore(
int num_zones, float l_min, float l_max, float md, float mh, int min_num_points, int num_seed_points,
float th_seeds, float uprightness_thresh, int num_rings_of_interest, float sensor_height,
float global_el_thresh, std::vector<long int, std::allocator<long int> > &zone_rings,
int num_zones, float l_min, float l_max, float md, float mh, int min_num_points,
int num_seed_points, float th_seeds, float uprightness_thresh, int num_rings_of_interest,
float sensor_height, float global_el_thresh,
std::vector<long int, std::allocator<long int> > &zone_rings,
std::vector<long int, std::allocator<long int> > &zone_sectors,
std::vector<double> &flatness_thr, std::vector<double> &elevation_thr, bool adaptive_selection_en)
std::vector<double> &flatness_thr, std::vector<double> &elevation_thr,
bool adaptive_selection_en)
: NUM_ZONES{num_zones},
L_MIN{l_min},
L_MAX{l_max},
Expand All @@ -27,7 +29,8 @@ OccupancySegmentationCore<PointT>::OccupancySegmentationCore(
FLATNESS_THR{flatness_thr.begin(), flatness_thr.end()},
ELEVATION_THR{elevation_thr.begin(), elevation_thr.end()},
lmins{L_MIN, (7 * L_MIN + L_MAX) / 8, (3 * L_MIN + L_MAX) / 4, (L_MIN + L_MAX) / 2},
lmaxs{lmins[1], lmins[2], lmins[3], L_MAX}, ADAPTIVE_SELECTION_EN{adaptive_selection_en}{
lmaxs{lmins[1], lmins[2], lmins[3], L_MAX},
ADAPTIVE_SELECTION_EN{adaptive_selection_en} {
init_czm();
}

Expand Down Expand Up @@ -166,7 +169,7 @@ void OccupancySegmentationCore<PointT>::segment_ground(pcl::PointCloud<PointT> &
if (patch.points.size() > MIN_NUM_POINTS) {
std::sort(patch.points.begin(), patch.points.end(), point_z_cmp);
rgpf(patch, p_idx, features);

Status status = ground_likelihood_est(features, p_idx.concentric_idx);
_statuses[p_idx.idx] = status;
} else {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@ OccupancySegmentationNode::OccupancySegmentationNode() : Node("occupancy_segment
std::string nonground_output_topic = this->get_parameter("nonground_output_topic").as_string();

_patchwork = OccupancySegmentationCore<PointXYZIRT>(
num_zones, l_min, l_max, md, mh, min_num_points, num_seed_points, th_seeds, uprightness_thresh,
num_rings_of_interest, sensor_height, global_el_thresh, zone_rings, zone_sectors,
flatness_thr, elevation_thr, adaptive_selection_en);
num_zones, l_min, l_max, md, mh, min_num_points, num_seed_points, th_seeds,
uprightness_thresh, num_rings_of_interest, sensor_height, global_el_thresh, zone_rings,
zone_sectors, flatness_thr, elevation_thr, adaptive_selection_en);

_subscriber = this->create_subscription<sensor_msgs::msg::PointCloud2>(
lidar_input_topic, 10,
Expand Down

0 comments on commit 5915c67

Please sign in to comment.