Skip to content

Commit c9b6473

Browse files
committedMar 25, 2025·
style(pre-commit): autofix
1 parent 3580420 commit c9b6473

File tree

5 files changed

+94
-68
lines changed

5 files changed

+94
-68
lines changed
 

‎pointcloud_filter/README.md

+3-3
Original file line numberDiff line numberDiff line change
@@ -8,9 +8,9 @@ The `autoware_pointcloud_filter` is a node that remove the ground points from th
88

99
Detail description of each ground segmentation algorithm is in the following links.
1010

11-
| Filter Name | Description | Detail |
12-
| -------------------- | ---------------------------------------------------------------------------------------------------------- | ------------------------------------ |
13-
| scan_ground_filter | A method of removing the ground based on the geometrical relationship between points lined up on radiation | [link](docs/scan-ground-filter.md) |
11+
| Filter Name | Description | Detail |
12+
| ------------------ | ---------------------------------------------------------------------------------------------------------- | ---------------------------------- |
13+
| scan_ground_filter | A method of removing the ground based on the geometrical relationship between points lined up on radiation | [link](docs/scan-ground-filter.md) |
1414

1515
## Inputs / Outputs
1616

‎pointcloud_filter/package.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -20,16 +20,16 @@
2020
<buildtool_depend>autoware_cmake</buildtool_depend>
2121

2222
<depend>ament_index_cpp</depend>
23+
<depend>autoware_point_types</depend>
2324
<depend>autoware_utils</depend>
2425
<depend>autoware_vehicle_info_utils</depend>
25-
<depend>autoware_point_types</depend>
26+
<depend>message_filters</depend>
2627
<depend>pcl_conversions</depend>
2728
<depend>pcl_ros</depend>
2829
<depend>rclcpp</depend>
2930
<depend>rclcpp_components</depend>
3031
<depend>sensor_msgs</depend>
3132
<depend>std_msgs</depend>
32-
<depend>message_filters</depend>
3333
<depend>tf2</depend>
3434
<depend>tf2_eigen</depend>
3535
<depend>tf2_ros</depend>

‎pointcloud_filter/src/scan_ground_filter/node.cpp

+64-43
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,9 @@
1313
// limitations under the License.
1414

1515
#include "node.hpp"
16-
#include "rclcpp/rclcpp.hpp"
1716

1817
#include "grid_ground_filter.hpp"
18+
#include "rclcpp/rclcpp.hpp"
1919
#include "sanity_check.hpp"
2020

2121
#include <autoware_utils/geometry/geometry.hpp>
@@ -27,7 +27,8 @@
2727
#include <string>
2828
#include <vector>
2929

30-
namespace {
30+
namespace
31+
{
3132
/** \brief For parameter service callback */
3233
template <typename T>
3334
bool get_param(const std::vector<rclcpp::Parameter> & p, const std::string & name, T & value)
@@ -41,7 +42,7 @@ bool get_param(const std::vector<rclcpp::Parameter> & p, const std::string & nam
4142
}
4243
return false;
4344
}
44-
}
45+
} // namespace
4546

4647
namespace autoware::pointcloud_filter
4748
{
@@ -65,33 +66,38 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
6566
elevation_grid_mode_ = rclcpp::Node::declare_parameter<bool>("elevation_grid_mode");
6667

6768
// common parameters
68-
radial_divider_angle_rad_ =
69-
static_cast<float>(deg2rad(rclcpp::Node::declare_parameter<double>("radial_divider_angle_deg")));
69+
radial_divider_angle_rad_ = static_cast<float>(
70+
deg2rad(rclcpp::Node::declare_parameter<double>("radial_divider_angle_deg")));
7071
radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_);
7172

7273
// common thresholds
73-
global_slope_max_angle_rad_ =
74-
static_cast<float>(deg2rad(rclcpp::Node::declare_parameter<double>("global_slope_max_angle_deg")));
75-
local_slope_max_angle_rad_ =
76-
static_cast<float>(deg2rad(rclcpp::Node::declare_parameter<double>("local_slope_max_angle_deg")));
74+
global_slope_max_angle_rad_ = static_cast<float>(
75+
deg2rad(rclcpp::Node::declare_parameter<double>("global_slope_max_angle_deg")));
76+
local_slope_max_angle_rad_ = static_cast<float>(
77+
deg2rad(rclcpp::Node::declare_parameter<double>("local_slope_max_angle_deg")));
7778
global_slope_max_ratio_ = std::tan(global_slope_max_angle_rad_);
7879
local_slope_max_ratio_ = std::tan(local_slope_max_angle_rad_);
79-
split_points_distance_tolerance_ =
80-
static_cast<float>(rclcpp::Node::declare_parameter<double>("split_points_distance_tolerance"));
80+
split_points_distance_tolerance_ = static_cast<float>(
81+
rclcpp::Node::declare_parameter<double>("split_points_distance_tolerance"));
8182

8283
// vehicle info
8384
vehicle_info_ = VehicleInfoUtils(*this).getVehicleInfo();
8485

8586
// non-grid parameters
8687
use_virtual_ground_point_ = rclcpp::Node::declare_parameter<bool>("use_virtual_ground_point");
87-
split_height_distance_ = static_cast<float>(rclcpp::Node::declare_parameter<double>("split_height_distance"));
88+
split_height_distance_ =
89+
static_cast<float>(rclcpp::Node::declare_parameter<double>("split_height_distance"));
8890

8991
// grid mode parameters
90-
use_recheck_ground_cluster_ = rclcpp::Node::declare_parameter<bool>("use_recheck_ground_cluster");
92+
use_recheck_ground_cluster_ =
93+
rclcpp::Node::declare_parameter<bool>("use_recheck_ground_cluster");
9194
use_lowest_point_ = rclcpp::Node::declare_parameter<bool>("use_lowest_point");
92-
detection_range_z_max_ = static_cast<float>(rclcpp::Node::declare_parameter<double>("detection_range_z_max"));
93-
low_priority_region_x_ = static_cast<float>(rclcpp::Node::declare_parameter<double>("low_priority_region_x"));
94-
center_pcl_shift_ = static_cast<float>(rclcpp::Node::declare_parameter<double>("center_pcl_shift"));
95+
detection_range_z_max_ =
96+
static_cast<float>(rclcpp::Node::declare_parameter<double>("detection_range_z_max"));
97+
low_priority_region_x_ =
98+
static_cast<float>(rclcpp::Node::declare_parameter<double>("low_priority_region_x"));
99+
center_pcl_shift_ =
100+
static_cast<float>(rclcpp::Node::declare_parameter<double>("center_pcl_shift"));
95101
non_ground_height_threshold_ =
96102
static_cast<float>(rclcpp::Node::declare_parameter<double>("non_ground_height_threshold"));
97103

@@ -132,7 +138,8 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
132138
// initialize debug tool
133139
{
134140
stop_watch_ptr_ = std::make_unique<autoware_utils::StopWatch<std::chrono::milliseconds>>();
135-
debug_publisher_ptr_ = std::make_unique<autoware_utils::DebugPublisher>(this, "scan_ground_filter");
141+
debug_publisher_ptr_ =
142+
std::make_unique<autoware_utils::DebugPublisher>(this, "scan_ground_filter");
136143
stop_watch_ptr_->tic("cyclic_time");
137144
stop_watch_ptr_->tic("processing_time");
138145

@@ -182,7 +189,6 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
182189

183190
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this);
184191
RCLCPP_DEBUG(this->get_logger(), "[Filter Constructor] successfully created.");
185-
186192
}
187193

188194
void ScanGroundFilterComponent::setupTF()
@@ -210,19 +216,26 @@ void ScanGroundFilterComponent::subscribe()
210216
this, "indices", rclcpp::SensorDataQoS().keep_last(max_queue_size_).get_rmw_qos_profile());
211217

212218
if (approximate_sync_) {
213-
sync_input_indices_a_ = std::make_shared<message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::PointCloud2, pcl_msgs::msg::PointIndices>>>(max_queue_size_);
219+
sync_input_indices_a_ = std::make_shared<
220+
message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<
221+
sensor_msgs::msg::PointCloud2, pcl_msgs::msg::PointIndices>>>(max_queue_size_);
214222
sync_input_indices_a_->connectInput(sub_input_filter_, sub_indices_filter_);
215-
sync_input_indices_a_->registerCallback(
216-
std::bind(&ScanGroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1, std::placeholders::_2));
223+
sync_input_indices_a_->registerCallback(std::bind(
224+
&ScanGroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
225+
std::placeholders::_2));
217226
} else {
218-
sync_input_indices_e_ = std::make_shared<message_filters::Synchronizer<message_filters::sync_policies::ExactTime<sensor_msgs::msg::PointCloud2, pcl_msgs::msg::PointIndices>>>(max_queue_size_);
227+
sync_input_indices_e_ =
228+
std::make_shared<message_filters::Synchronizer<message_filters::sync_policies::ExactTime<
229+
sensor_msgs::msg::PointCloud2, pcl_msgs::msg::PointIndices>>>(max_queue_size_);
219230
sync_input_indices_e_->connectInput(sub_input_filter_, sub_indices_filter_);
220-
sync_input_indices_e_->registerCallback(
221-
std::bind(&ScanGroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1, std::placeholders::_2));
231+
sync_input_indices_e_->registerCallback(std::bind(
232+
&ScanGroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
233+
std::placeholders::_2));
222234
}
223235
} else {
224-
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)> cb =
225-
std::bind(&ScanGroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1, pcl_msgs::msg::PointIndices::ConstSharedPtr());
236+
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)> cb = std::bind(
237+
&ScanGroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
238+
pcl_msgs::msg::PointIndices::ConstSharedPtr());
226239
sub_input_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
227240
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_), cb);
228241
}
@@ -294,7 +307,8 @@ bool ScanGroundFilterComponent::convert_output_costly(
294307
}
295308

296309
void ScanGroundFilterComponent::faster_input_indices_callback(
297-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloud, const pcl_msgs::msg::PointIndices::ConstSharedPtr indices)
310+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloud,
311+
const pcl_msgs::msg::PointIndices::ConstSharedPtr indices)
298312
{
299313
if (
300314
!is_data_layout_compatible_with_point_xyzircaedt(*cloud) &&
@@ -378,7 +392,8 @@ void ScanGroundFilterComponent::convertPointcloud(
378392
std::vector<PointCloudVector> & out_radial_ordered_points) const
379393
{
380394
std::unique_ptr<autoware_utils::ScopedTimeTrack> st_ptr;
381-
if (time_keeper_) st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
395+
if (time_keeper_)
396+
st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
382397

383398
out_radial_ordered_points.resize(radial_dividers_num_);
384399
PointData current_point;
@@ -391,7 +406,8 @@ void ScanGroundFilterComponent::convertPointcloud(
391406
{ // grouping pointcloud by its azimuth angle
392407
std::unique_ptr<autoware_utils::ScopedTimeTrack> inner_st_ptr;
393408
if (time_keeper_)
394-
inner_st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>("azimuth_angle_grouping", *time_keeper_);
409+
inner_st_ptr =
410+
std::make_unique<autoware_utils::ScopedTimeTrack>("azimuth_angle_grouping", *time_keeper_);
395411

396412
pcl::PointXYZ input_point;
397413
for (size_t data_index = 0; data_index + in_cloud_point_step <= in_cloud_data_size;
@@ -415,7 +431,8 @@ void ScanGroundFilterComponent::convertPointcloud(
415431

416432
{ // sorting pointcloud by distance, on each azimuth angle group
417433
std::unique_ptr<autoware_utils::ScopedTimeTrack> inner_st_ptr;
418-
if (time_keeper_) inner_st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>("sort", *time_keeper_);
434+
if (time_keeper_)
435+
inner_st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>("sort", *time_keeper_);
419436

420437
for (size_t i = 0; i < radial_dividers_num_; ++i) {
421438
std::sort(
@@ -438,7 +455,8 @@ void ScanGroundFilterComponent::classifyPointCloud(
438455
pcl::PointIndices & out_no_ground_indices) const
439456
{
440457
std::unique_ptr<autoware_utils::ScopedTimeTrack> st_ptr;
441-
if (time_keeper_) st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
458+
if (time_keeper_)
459+
st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
442460

443461
out_no_ground_indices.indices.clear();
444462

@@ -556,11 +574,12 @@ void ScanGroundFilterComponent::classifyPointCloud(
556574
}
557575

558576
void ScanGroundFilterComponent::extractObjectPoints(
559-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_cloud_ptr, const pcl::PointIndices & in_indices,
560-
sensor_msgs::msg::PointCloud2 & out_object_cloud) const
577+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_cloud_ptr,
578+
const pcl::PointIndices & in_indices, sensor_msgs::msg::PointCloud2 & out_object_cloud) const
561579
{
562580
std::unique_ptr<autoware_utils::ScopedTimeTrack> st_ptr;
563-
if (time_keeper_) st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
581+
if (time_keeper_)
582+
st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
564583

565584
size_t output_data_size = 0;
566585

@@ -573,12 +592,13 @@ void ScanGroundFilterComponent::extractObjectPoints(
573592
}
574593

575594
void ScanGroundFilterComponent::faster_filter(
576-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const pcl::IndicesPtr & indices,
577-
sensor_msgs::msg::PointCloud2 & output,
595+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input,
596+
[[maybe_unused]] const pcl::IndicesPtr & indices, sensor_msgs::msg::PointCloud2 & output,
578597
[[maybe_unused]] const TransformInfo & transform_info)
579598
{
580599
std::unique_ptr<autoware_utils::ScopedTimeTrack> st_ptr;
581-
if (time_keeper_) st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
600+
if (time_keeper_)
601+
st_ptr = std::make_unique<autoware_utils::ScopedTimeTrack>(__func__, *time_keeper_);
582602

583603
std::scoped_lock lock(mutex_);
584604

@@ -622,8 +642,8 @@ void ScanGroundFilterComponent::faster_filter(
622642
// TODO(taisa1): Temporary Implementation: Delete this function definition when all the filter
623643
// nodes conform to new API.
624644
void ScanGroundFilterComponent::filter(
625-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const pcl::IndicesPtr & indices,
626-
sensor_msgs::msg::PointCloud2 & output)
645+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input,
646+
[[maybe_unused]] const pcl::IndicesPtr & indices, sensor_msgs::msg::PointCloud2 & output)
627647
{
628648
(void)input;
629649
(void)indices;
@@ -644,7 +664,8 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter(
644664
global_slope_max_angle_rad_ = deg2rad(global_slope_max_angle_deg);
645665
global_slope_max_ratio_ = std::tan(global_slope_max_angle_rad_);
646666
RCLCPP_DEBUG(
647-
this->get_logger(), "Setting global_slope_max_angle_rad to: %f.", global_slope_max_angle_rad_);
667+
this->get_logger(), "Setting global_slope_max_angle_rad to: %f.",
668+
global_slope_max_angle_rad_);
648669
RCLCPP_DEBUG(
649670
this->get_logger(), "Setting global_slope_max_ratio to: %f.", global_slope_max_ratio_);
650671
}
@@ -664,8 +685,7 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter(
664685
// grid_ptr_->initialize(grid_size_m_, radial_divider_angle_rad_, grid_mode_switch_radius_);
665686
RCLCPP_DEBUG(
666687
this->get_logger(), "Setting radial_divider_angle_rad to: %f.", radial_divider_angle_rad_);
667-
RCLCPP_DEBUG(
668-
this->get_logger(), "Setting radial_dividers_num to: %zu.", radial_dividers_num_);
688+
RCLCPP_DEBUG(this->get_logger(), "Setting radial_dividers_num to: %zu.", radial_dividers_num_);
669689
}
670690
if (get_param(param, "split_points_distance_tolerance", split_points_distance_tolerance_)) {
671691
RCLCPP_DEBUG(
@@ -694,7 +714,8 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter(
694714
RCLCPP_DEBUG(this->get_logger(), "Setting the input TF frame to: %s.", tf_input_frame_.c_str());
695715
}
696716
if (get_param(param, "output_frame", tf_output_frame_)) {
697-
RCLCPP_DEBUG(this->get_logger(), "Setting the output TF frame to: %s.", tf_output_frame_.c_str());
717+
RCLCPP_DEBUG(
718+
this->get_logger(), "Setting the output TF frame to: %s.", tf_output_frame_.c_str());
698719
}
699720

700721
// Finally return the result

0 commit comments

Comments
 (0)