13
13
// limitations under the License.
14
14
15
15
#include " node.hpp"
16
- #include " rclcpp/rclcpp.hpp"
17
16
18
17
#include " grid_ground_filter.hpp"
18
+ #include " rclcpp/rclcpp.hpp"
19
19
#include " sanity_check.hpp"
20
20
21
21
#include < autoware_utils/geometry/geometry.hpp>
27
27
#include < string>
28
28
#include < vector>
29
29
30
- namespace {
30
+ namespace
31
+ {
31
32
/* * \brief For parameter service callback */
32
33
template <typename T>
33
34
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
41
42
}
42
43
return false ;
43
44
}
44
- }
45
+ } // namespace
45
46
46
47
namespace autoware ::pointcloud_filter
47
48
{
@@ -65,33 +66,38 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
65
66
elevation_grid_mode_ = rclcpp::Node::declare_parameter<bool >(" elevation_grid_mode" );
66
67
67
68
// 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" )));
70
71
radial_dividers_num_ = std::ceil (2.0 * M_PI / radial_divider_angle_rad_);
71
72
72
73
// 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" )));
77
78
global_slope_max_ratio_ = std::tan (global_slope_max_angle_rad_);
78
79
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" ));
81
82
82
83
// vehicle info
83
84
vehicle_info_ = VehicleInfoUtils (*this ).getVehicleInfo ();
84
85
85
86
// non-grid parameters
86
87
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" ));
88
90
89
91
// 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" );
91
94
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" ));
95
101
non_ground_height_threshold_ =
96
102
static_cast <float >(rclcpp::Node::declare_parameter<double >(" non_ground_height_threshold" ));
97
103
@@ -132,7 +138,8 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
132
138
// initialize debug tool
133
139
{
134
140
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" );
136
143
stop_watch_ptr_->tic (" cyclic_time" );
137
144
stop_watch_ptr_->tic (" processing_time" );
138
145
@@ -182,7 +189,6 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
182
189
183
190
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this );
184
191
RCLCPP_DEBUG (this ->get_logger (), " [Filter Constructor] successfully created." );
185
-
186
192
}
187
193
188
194
void ScanGroundFilterComponent::setupTF ()
@@ -210,19 +216,26 @@ void ScanGroundFilterComponent::subscribe()
210
216
this , " indices" , rclcpp::SensorDataQoS ().keep_last (max_queue_size_).get_rmw_qos_profile ());
211
217
212
218
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_);
214
222
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));
217
226
} 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_);
219
230
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));
222
234
}
223
235
} 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 ());
226
239
sub_input_ = this ->create_subscription <sensor_msgs::msg::PointCloud2>(
227
240
" input" , rclcpp::SensorDataQoS ().keep_last (max_queue_size_), cb);
228
241
}
@@ -294,7 +307,8 @@ bool ScanGroundFilterComponent::convert_output_costly(
294
307
}
295
308
296
309
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)
298
312
{
299
313
if (
300
314
!is_data_layout_compatible_with_point_xyzircaedt (*cloud) &&
@@ -378,7 +392,8 @@ void ScanGroundFilterComponent::convertPointcloud(
378
392
std::vector<PointCloudVector> & out_radial_ordered_points) const
379
393
{
380
394
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_);
382
397
383
398
out_radial_ordered_points.resize (radial_dividers_num_);
384
399
PointData current_point;
@@ -391,7 +406,8 @@ void ScanGroundFilterComponent::convertPointcloud(
391
406
{ // grouping pointcloud by its azimuth angle
392
407
std::unique_ptr<autoware_utils::ScopedTimeTrack> inner_st_ptr;
393
408
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_);
395
411
396
412
pcl::PointXYZ input_point;
397
413
for (size_t data_index = 0 ; data_index + in_cloud_point_step <= in_cloud_data_size;
@@ -415,7 +431,8 @@ void ScanGroundFilterComponent::convertPointcloud(
415
431
416
432
{ // sorting pointcloud by distance, on each azimuth angle group
417
433
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_);
419
436
420
437
for (size_t i = 0 ; i < radial_dividers_num_; ++i) {
421
438
std::sort (
@@ -438,7 +455,8 @@ void ScanGroundFilterComponent::classifyPointCloud(
438
455
pcl::PointIndices & out_no_ground_indices) const
439
456
{
440
457
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_);
442
460
443
461
out_no_ground_indices.indices .clear ();
444
462
@@ -556,11 +574,12 @@ void ScanGroundFilterComponent::classifyPointCloud(
556
574
}
557
575
558
576
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
561
579
{
562
580
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_);
564
583
565
584
size_t output_data_size = 0 ;
566
585
@@ -573,12 +592,13 @@ void ScanGroundFilterComponent::extractObjectPoints(
573
592
}
574
593
575
594
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,
578
597
[[maybe_unused]] const TransformInfo & transform_info)
579
598
{
580
599
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_);
582
602
583
603
std::scoped_lock lock (mutex_);
584
604
@@ -622,8 +642,8 @@ void ScanGroundFilterComponent::faster_filter(
622
642
// TODO(taisa1): Temporary Implementation: Delete this function definition when all the filter
623
643
// nodes conform to new API.
624
644
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)
627
647
{
628
648
(void )input;
629
649
(void )indices;
@@ -644,7 +664,8 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter(
644
664
global_slope_max_angle_rad_ = deg2rad (global_slope_max_angle_deg);
645
665
global_slope_max_ratio_ = std::tan (global_slope_max_angle_rad_);
646
666
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_);
648
669
RCLCPP_DEBUG (
649
670
this ->get_logger (), " Setting global_slope_max_ratio to: %f." , global_slope_max_ratio_);
650
671
}
@@ -664,8 +685,7 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter(
664
685
// grid_ptr_->initialize(grid_size_m_, radial_divider_angle_rad_, grid_mode_switch_radius_);
665
686
RCLCPP_DEBUG (
666
687
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_);
669
689
}
670
690
if (get_param (param, " split_points_distance_tolerance" , split_points_distance_tolerance_)) {
671
691
RCLCPP_DEBUG (
@@ -694,7 +714,8 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter(
694
714
RCLCPP_DEBUG (this ->get_logger (), " Setting the input TF frame to: %s." , tf_input_frame_.c_str ());
695
715
}
696
716
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 ());
698
719
}
699
720
700
721
// Finally return the result
0 commit comments