52
52
*/
53
53
54
54
#include " autoware/crop_box_filter/crop_box_filter_node.hpp"
55
+
55
56
#include < memory>
56
- #include < vector>
57
57
#include < string>
58
58
#include < utility>
59
+ #include < vector>
59
60
60
61
namespace autoware ::crop_box_filter
61
62
{
@@ -78,60 +79,47 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
78
79
79
80
// get transform info for pointcloud
80
81
{
81
-
82
- tf_input_orig_frame_ = static_cast <std::string>(declare_parameter (" input_pointcloud_frame" , " base_link" ));
82
+ tf_input_orig_frame_ =
83
+ static_cast <std::string>(declare_parameter (" input_pointcloud_frame" , " base_link" ));
83
84
tf_input_frame_ = static_cast <std::string>(declare_parameter (" input_frame" , " base_link" ));
84
85
tf_output_frame_ = static_cast <std::string>(declare_parameter (" output_frame" , " base_link" ));
85
86
86
87
// Always consider static TF if in & out frames are same
87
88
bool has_static_tf_only = false ;
88
89
if (tf_input_frame_ == tf_output_frame_) {
89
-
90
90
RCLCPP_INFO (
91
91
this ->get_logger (),
92
92
" Input and output frames are the same. Overriding has_static_tf_only to true." );
93
-
93
+
94
94
has_static_tf_only = true ;
95
95
}
96
96
managed_tf_buffer_ =
97
97
std::make_unique<autoware_utils::ManagedTransformBuffer>(this , has_static_tf_only);
98
98
99
-
100
- if (tf_input_orig_frame_ == tf_input_frame_)
101
- {
99
+ if (tf_input_orig_frame_ == tf_input_frame_) {
102
100
need_preprocess_transform_ = false ;
103
101
eigen_transform_preprocess_ = Eigen::Matrix4f::Identity (4 , 4 );
104
- }
105
- else
106
- {
102
+ } else {
107
103
if (!managed_tf_buffer_->get_transform (
108
- tf_input_frame_, tf_input_orig_frame_, eigen_transform_preprocess_))
109
- {
104
+ tf_input_frame_, tf_input_orig_frame_, eigen_transform_preprocess_)) {
110
105
RCLCPP_ERROR (
111
- this ->get_logger (),
112
- " Cannot get transform from %s to %s. Please check your TF tree." ,tf_input_orig_frame_.c_str () , tf_input_frame_.c_str ());
113
- }
114
- else
115
- {
106
+ this ->get_logger (), " Cannot get transform from %s to %s. Please check your TF tree." ,
107
+ tf_input_orig_frame_.c_str (), tf_input_frame_.c_str ());
108
+ } else {
116
109
need_preprocess_transform_ = true ;
117
110
}
118
111
}
119
112
120
- if (tf_input_frame_ == tf_output_frame_)
121
- {
113
+ if (tf_input_frame_ == tf_output_frame_) {
122
114
need_postprocess_transform_ = false ;
123
115
eigen_transform_postprocess_ = Eigen::Matrix4f::Identity (4 , 4 );
124
- }else
125
- {
116
+ } else {
126
117
if (!managed_tf_buffer_->get_transform (
127
- tf_output_frame_, tf_input_frame_, eigen_transform_postprocess_))
128
- {
118
+ tf_output_frame_, tf_input_frame_, eigen_transform_postprocess_)) {
129
119
RCLCPP_ERROR (
130
- this ->get_logger (),
131
- " Cannot get transform from %s to %s. Please check your TF tree." ,tf_input_frame_.c_str () , tf_output_frame_.c_str ());
132
- }
133
- else
134
- {
120
+ this ->get_logger (), " Cannot get transform from %s to %s. Please check your TF tree." ,
121
+ tf_input_frame_.c_str (), tf_output_frame_.c_str ());
122
+ } else {
135
123
need_postprocess_transform_ = true ;
136
124
}
137
125
}
@@ -170,18 +158,17 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
170
158
// set parameter service callback
171
159
{
172
160
using std::placeholders::_1;
173
- set_param_res_ = this -> add_on_set_parameters_callback (
174
- std::bind (&CropBoxFilter::param_callback, this , _1));
161
+ set_param_res_ =
162
+ this -> add_on_set_parameters_callback ( std::bind (&CropBoxFilter::param_callback, this , _1));
175
163
}
176
164
177
165
// set input pointcloud callback
178
166
{
179
167
sub_input_ = this ->create_subscription <PointCloud2>(
180
- " input" , rclcpp::SensorDataQoS ().keep_last (max_queue_size_),
168
+ " input" , rclcpp::SensorDataQoS ().keep_last (max_queue_size_),
181
169
std::bind (&CropBoxFilter::pointcloud_callback, this , std::placeholders::_1));
182
170
}
183
171
184
-
185
172
RCLCPP_DEBUG (this ->get_logger (), " [Filter Constructor] successfully created." );
186
173
}
187
174
@@ -198,11 +185,10 @@ void CropBoxFilter::pointcloud_filter(const PointCloud2ConstPtr & cloud, PointCl
198
185
199
186
// pointcloud processing loop
200
187
for (size_t global_offset = 0 ; global_offset + cloud->point_step <= cloud->data .size ();
201
- global_offset += cloud->point_step )
202
- {
188
+ global_offset += cloud->point_step ) {
203
189
// extract point data from point cloud data buffer
204
190
Eigen::Vector4f point;
205
-
191
+
206
192
std::memcpy (&point[0 ], &cloud->data [global_offset + x_offset], sizeof (float ));
207
193
std::memcpy (&point[1 ], &cloud->data [global_offset + y_offset], sizeof (float ));
208
194
std::memcpy (&point[2 ], &cloud->data [global_offset + z_offset], sizeof (float ));
@@ -221,26 +207,23 @@ void CropBoxFilter::pointcloud_filter(const PointCloud2ConstPtr & cloud, PointCl
221
207
point_preprocessed = eigen_transform_preprocess_ * point;
222
208
}
223
209
224
- bool point_is_inside = point_preprocessed[2 ] > param_.min_z && point_preprocessed[2 ] < param_.max_z &&
225
- point_preprocessed[1 ] > param_.min_y && point_preprocessed[1 ] < param_.max_y &&
226
- point_preprocessed[0 ] > param_.min_x && point_preprocessed[0 ] < param_.max_x ;
210
+ bool point_is_inside =
211
+ point_preprocessed[2 ] > param_.min_z && point_preprocessed[2 ] < param_.max_z &&
212
+ point_preprocessed[1 ] > param_.min_y && point_preprocessed[1 ] < param_.max_y &&
213
+ point_preprocessed[0 ] > param_.min_x && point_preprocessed[0 ] < param_.max_x ;
227
214
if ((!param_.negative && point_is_inside) || (param_.negative && !point_is_inside)) {
228
-
229
215
// apply post-transform if needed
230
- if (need_postprocess_transform_)
231
- {
232
- if (need_preprocess_transform_)
233
- {
216
+ if (need_postprocess_transform_) {
217
+ if (need_preprocess_transform_) {
234
218
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point_preprocessed;
235
219
236
220
memcpy (&output.data [output_size], &cloud->data [global_offset], cloud->point_step );
237
221
238
222
std::memcpy (&output.data [output_size + x_offset], &point_postprocessed[0 ], sizeof (float ));
239
223
std::memcpy (&output.data [output_size + y_offset], &point_postprocessed[1 ], sizeof (float ));
240
224
std::memcpy (&output.data [output_size + z_offset], &point_postprocessed[2 ], sizeof (float ));
241
-
242
- }else
243
- {
225
+
226
+ } else {
244
227
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point;
245
228
246
229
memcpy (&output.data [output_size], &cloud->data [global_offset], cloud->point_step );
@@ -249,9 +232,7 @@ void CropBoxFilter::pointcloud_filter(const PointCloud2ConstPtr & cloud, PointCl
249
232
std::memcpy (&output.data [output_size + y_offset], &point_postprocessed[1 ], sizeof (float ));
250
233
std::memcpy (&output.data [output_size + z_offset], &point_postprocessed[2 ], sizeof (float ));
251
234
}
252
- }
253
- else
254
- {
235
+ } else {
255
236
memcpy (&output.data [output_size], &cloud->data [global_offset], cloud->point_step );
256
237
257
238
if (need_preprocess_transform_) {
@@ -300,19 +281,18 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
300
281
" received." ,
301
282
cloud->width * cloud->height , cloud->header .frame_id .c_str ());
302
283
// pointcloud check finished
303
-
284
+
304
285
// pointcloud processing
305
286
auto output = PointCloud2 ();
306
287
307
288
std::scoped_lock lock (mutex_);
308
289
stop_watch_ptr_->toc (" processing_time" , true );
309
290
310
291
// filtering
311
- pointcloud_filter ( cloud, output);
292
+ pointcloud_filter (cloud, output);
312
293
313
294
// publish polygon if subscribers exist
314
- if (crop_box_polygon_pub_->get_subscription_count () > 0 )
315
- {
295
+ if (crop_box_polygon_pub_->get_subscription_count () > 0 ) {
316
296
publish_crop_box_polygon ();
317
297
}
318
298
@@ -404,7 +384,8 @@ rcl_interfaces::msg::SetParametersResult CropBoxFilter::param_callback(
404
384
new_param.max_x = get_param (p, " max_x" , new_param.max_x ) ? new_param.max_x : param_.max_x ;
405
385
new_param.max_y = get_param (p, " max_y" , new_param.max_y ) ? new_param.max_y : param_.max_y ;
406
386
new_param.max_z = get_param (p, " max_z" , new_param.max_z ) ? new_param.max_z : param_.max_z ;
407
- new_param.negative = get_param (p, " negative" , new_param.negative ) ? new_param.negative : param_.negative ;
387
+ new_param.negative =
388
+ get_param (p, " negative" , new_param.negative ) ? new_param.negative : param_.negative ;
408
389
409
390
param_ = new_param;
410
391
@@ -605,13 +586,12 @@ bool CropBoxFilter::is_data_layout_compatible_with_point_xyzircaedt(const PointC
605
586
return same_layout;
606
587
}
607
588
608
- bool CropBoxFilter::is_valid ( const PointCloud2ConstPtr & cloud)
589
+ bool CropBoxFilter::is_valid (const PointCloud2ConstPtr & cloud)
609
590
{
610
591
// firstly check the fields of the point cloud
611
592
if (
612
593
!is_data_layout_compatible_with_point_xyzircaedt (*cloud) &&
613
- !is_data_layout_compatible_with_point_xyzirc (*cloud))
614
- {
594
+ !is_data_layout_compatible_with_point_xyzirc (*cloud)) {
615
595
RCLCPP_ERROR (
616
596
get_logger (),
617
597
" The pointcloud layout is not compatible with PointXYZIRCAEDT or PointXYZIRC. Aborting" );
0 commit comments