@@ -79,60 +79,47 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
79
79
80
80
// get transform info for pointcloud
81
81
{
82
-
83
- 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" ));
84
84
tf_input_frame_ = static_cast <std::string>(declare_parameter (" input_frame" , " base_link" ));
85
85
tf_output_frame_ = static_cast <std::string>(declare_parameter (" output_frame" , " base_link" ));
86
86
87
87
// Always consider static TF if in & out frames are same
88
88
bool has_static_tf_only = false ;
89
89
if (tf_input_frame_ == tf_output_frame_) {
90
-
91
90
RCLCPP_INFO (
92
91
this ->get_logger (),
93
92
" Input and output frames are the same. Overriding has_static_tf_only to true." );
94
-
93
+
95
94
has_static_tf_only = true ;
96
95
}
97
96
managed_tf_buffer_ =
98
97
std::make_unique<autoware_utils::ManagedTransformBuffer>(this , has_static_tf_only);
99
98
100
-
101
- if (tf_input_orig_frame_ == tf_input_frame_)
102
- {
99
+ if (tf_input_orig_frame_ == tf_input_frame_) {
103
100
need_preprocess_transform_ = false ;
104
101
eigen_transform_preprocess_ = Eigen::Matrix4f::Identity (4 , 4 );
105
- }
106
- else
107
- {
102
+ } else {
108
103
if (!managed_tf_buffer_->get_transform (
109
- tf_input_frame_, tf_input_orig_frame_, eigen_transform_preprocess_))
110
- {
104
+ tf_input_frame_, tf_input_orig_frame_, eigen_transform_preprocess_)) {
111
105
RCLCPP_ERROR (
112
- this ->get_logger (),
113
- " Cannot get transform from %s to %s. Please check your TF tree." ,tf_input_orig_frame_.c_str () , tf_input_frame_.c_str ());
114
- }
115
- else
116
- {
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 {
117
109
need_preprocess_transform_ = true ;
118
110
}
119
111
}
120
112
121
- if (tf_input_frame_ == tf_output_frame_)
122
- {
113
+ if (tf_input_frame_ == tf_output_frame_) {
123
114
need_postprocess_transform_ = false ;
124
115
eigen_transform_postprocess_ = Eigen::Matrix4f::Identity (4 , 4 );
125
- }else
126
- {
116
+ } else {
127
117
if (!managed_tf_buffer_->get_transform (
128
- tf_output_frame_, tf_input_frame_, eigen_transform_postprocess_))
129
- {
118
+ tf_output_frame_, tf_input_frame_, eigen_transform_postprocess_)) {
130
119
RCLCPP_ERROR (
131
- this ->get_logger (),
132
- " Cannot get transform from %s to %s. Please check your TF tree." ,tf_input_frame_.c_str () , tf_output_frame_.c_str ());
133
- }
134
- else
135
- {
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 {
136
123
need_postprocess_transform_ = true ;
137
124
}
138
125
}
@@ -171,31 +158,26 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
171
158
// set parameter service callback
172
159
{
173
160
using std::placeholders::_1;
174
- set_param_res_ = this -> add_on_set_parameters_callback (
175
- 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));
176
163
}
177
164
178
165
// set input pointcloud callback
179
166
{
180
167
sub_input_ = this ->create_subscription <PointCloud2>(
181
- " input" , rclcpp::SensorDataQoS ().keep_last (max_queue_size_),
168
+ " input" , rclcpp::SensorDataQoS ().keep_last (max_queue_size_),
182
169
std::bind (&CropBoxFilter::pointcloud_callback, this , std::placeholders::_1));
183
170
}
184
171
185
-
186
172
RCLCPP_DEBUG (this ->get_logger (), " [Filter Constructor] successfully created." );
187
173
}
188
174
189
-
190
-
191
-
192
175
void CropBoxFilter::pointcloud_callback (const PointCloud2ConstPtr cloud)
193
176
{
194
177
// chechk if the pointcloud is valid
195
178
if (
196
179
!is_data_layout_compatible_with_point_xyzircaedt (*cloud) &&
197
- !is_data_layout_compatible_with_point_xyzirc (*cloud))
198
- {
180
+ !is_data_layout_compatible_with_point_xyzirc (*cloud)) {
199
181
RCLCPP_ERROR (
200
182
get_logger (),
201
183
" The pointcloud layout is not compatible with PointXYZIRCAEDT or PointXYZIRC. Aborting" );
@@ -228,14 +210,13 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
228
210
" received." ,
229
211
cloud->width * cloud->height , cloud->header .frame_id .c_str ());
230
212
// pointcloud check finished
231
-
213
+
232
214
// pointcloud processing
233
215
auto output = PointCloud2 ();
234
216
235
217
std::scoped_lock lock (mutex_);
236
218
stop_watch_ptr_->toc (" processing_time" , true );
237
219
238
-
239
220
int x_offset = cloud->fields [pcl::getFieldIndex (*cloud, " x" )].offset ;
240
221
int y_offset = cloud->fields [pcl::getFieldIndex (*cloud, " y" )].offset ;
241
222
int z_offset = cloud->fields [pcl::getFieldIndex (*cloud, " z" )].offset ;
@@ -247,8 +228,7 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
247
228
248
229
// pointcloud processing loop
249
230
for (size_t global_offset = 0 ; global_offset + cloud->point_step <= cloud->data .size ();
250
- global_offset += cloud->point_step )
251
- {
231
+ global_offset += cloud->point_step ) {
252
232
Eigen::Vector4f point;
253
233
Eigen::Vector4f point_preprocessed;
254
234
std::memcpy (&point[0 ], &cloud->data [global_offset + x_offset], sizeof (float ));
@@ -271,22 +251,18 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
271
251
point[1 ] > param_.min_y && point[1 ] < param_.max_y &&
272
252
point[0 ] > param_.min_x && point[0 ] < param_.max_x ;
273
253
if ((!param_.negative && point_is_inside) || (param_.negative && !point_is_inside)) {
274
-
275
254
// apply post-transform if needed
276
- if (need_postprocess_transform_)
277
- {
278
- if (need_preprocess_transform_)
279
- {
255
+ if (need_postprocess_transform_) {
256
+ if (need_preprocess_transform_) {
280
257
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point_preprocessed;
281
258
282
259
memcpy (&output.data [output_size], &cloud->data [global_offset], cloud->point_step );
283
260
284
261
std::memcpy (&output.data [output_size + x_offset], &point_postprocessed[0 ], sizeof (float ));
285
262
std::memcpy (&output.data [output_size + y_offset], &point_postprocessed[1 ], sizeof (float ));
286
263
std::memcpy (&output.data [output_size + z_offset], &point_postprocessed[2 ], sizeof (float ));
287
-
288
- }else
289
- {
264
+
265
+ } else {
290
266
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point;
291
267
292
268
memcpy (&output.data [output_size], &cloud->data [global_offset], cloud->point_step );
@@ -295,9 +271,7 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
295
271
std::memcpy (&output.data [output_size + y_offset], &point_postprocessed[1 ], sizeof (float ));
296
272
std::memcpy (&output.data [output_size + z_offset], &point_postprocessed[2 ], sizeof (float ));
297
273
}
298
- }
299
- else
300
- {
274
+ } else {
301
275
memcpy (&output.data [output_size], &cloud->data [global_offset], cloud->point_step );
302
276
303
277
if (need_preprocess_transform_) {
@@ -330,8 +304,7 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
330
304
output.row_step = static_cast <uint32_t >(output.data .size () / output.height );
331
305
332
306
// publish polygon if subscribers exist
333
- if (crop_box_polygon_pub_->get_subscription_count () > 0 )
334
- {
307
+ if (crop_box_polygon_pub_->get_subscription_count () > 0 ) {
335
308
publish_crop_box_polygon ();
336
309
}
337
310
@@ -424,7 +397,8 @@ rcl_interfaces::msg::SetParametersResult CropBoxFilter::param_callback(
424
397
new_param.max_x = get_param (p, " max_x" , new_param.max_x ) ? new_param.max_x : param_.max_x ;
425
398
new_param.max_y = get_param (p, " max_y" , new_param.max_y ) ? new_param.max_y : param_.max_y ;
426
399
new_param.max_z = get_param (p, " max_z" , new_param.max_z ) ? new_param.max_z : param_.max_z ;
427
- new_param.negative = get_param (p, " negative" , new_param.negative ) ? new_param.negative : param_.negative ;
400
+ new_param.negative =
401
+ get_param (p, " negative" , new_param.negative ) ? new_param.negative : param_.negative ;
428
402
429
403
param_ = new_param;
430
404
@@ -625,7 +599,7 @@ bool CropBoxFilter::is_data_layout_compatible_with_point_xyzircaedt(const PointC
625
599
return same_layout;
626
600
}
627
601
628
- bool CropBoxFilter::is_valid ( const PointCloud2ConstPtr & cloud)
602
+ bool CropBoxFilter::is_valid (const PointCloud2ConstPtr & cloud)
629
603
{
630
604
if (cloud->width * cloud->height * cloud->point_step != cloud->data .size ()) {
631
605
RCLCPP_WARN (
0 commit comments