Skip to content

Commit 44df055

Browse files
pre-commit-ci[bot]liuXinGangChina
authored andcommitted
style(pre-commit): autofix
1 parent dc27db1 commit 44df055

File tree

6 files changed

+106
-137
lines changed

6 files changed

+106
-137
lines changed

sensing/autoware_crop_box_filter/CMakeLists.txt

-2
Original file line numberDiff line numberDiff line change
@@ -34,5 +34,3 @@ ament_auto_package(INSTALL_TO_SHARE
3434
config
3535
test
3636
)
37-
38-

sensing/autoware_crop_box_filter/README.md

+22-23
Original file line numberDiff line numberDiff line change
@@ -12,41 +12,40 @@ The `autoware_crop_box_filter` is implemented as a autoware core node that subsc
1212

1313
### Input
1414

15-
| Name | Type | Description |
16-
| ----------------- | ------------------------------- | ----------------- |
17-
| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points |
15+
| Name | Type | Description |
16+
| ---------------- | ------------------------------- | ---------------- |
17+
| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points |
1818

1919
### Output
2020

21-
| Name | Type | Description |
22-
| ----------------- | ------------------------------- | --------------- |
23-
| `~/output/points` | `sensor_msgs::msg::PointCloud2` | filtered points |
21+
| Name | Type | Description |
22+
| -------------------- | ------------------------------------ | -------------------- |
23+
| `~/output/points` | `sensor_msgs::msg::PointCloud2` | filtered points |
2424
| `~/crop_box_polygon` | `geometry_msgs::msg::PolygonStamped` | bounding box polygon |
2525

2626
## Parameters
2727

2828
### Launch file Parameters
2929

30-
| Name | Type | Default Value | Description |
31-
| ------------------ | ------ | ------------- | ------------------------------------- |
32-
| `input_frame` | string | " " | the frame id in which filtering is performed |
33-
| `output_frame` | string | " " | output frame id of the filtered points |
34-
| `input_pointcloud_frame` | string | " " | frame id of input pointcloud |
35-
| `max_queue_size` | int | 5 | max buffer size of input/output topics |
36-
| `crop_box_filter_param_file` | string | " " | path to the parameter file for the node |
37-
30+
| Name | Type | Default Value | Description |
31+
| ---------------------------- | ------ | ------------- | -------------------------------------------- |
32+
| `input_frame` | string | " " | the frame id in which filtering is performed |
33+
| `output_frame` | string | " " | output frame id of the filtered points |
34+
| `input_pointcloud_frame` | string | " " | frame id of input pointcloud |
35+
| `max_queue_size` | int | 5 | max buffer size of input/output topics |
36+
| `crop_box_filter_param_file` | string | " " | path to the parameter file for the node |
3837

3938
### Node Parameters
4039

41-
| Name | Type | Default Value | Description |
42-
| ------------------ | ------ | ------------- | ------------------------------------- |
43-
| `min_x` | double | -5.0 | minimum x value of the crop box |
44-
| `min_y` | double | -5.0 | minimum y value of the crop box |
45-
| `min_z` | double | -5.0 | minimum z value of the crop box |
46-
| `max_x` | double | 5.0 | maximum x value of the crop box |
47-
| `max_y` | double | 5.0 | maximum y value of the crop box |
48-
| `max_z` | double | 5.0 | maximum z value of the crop box |
49-
| `negative` | bool | true | if true, points inside the box are removed, otherwise points outside the box are removed |
40+
| Name | Type | Default Value | Description |
41+
| ---------- | ------ | ------------- | ---------------------------------------------------------------------------------------- |
42+
| `min_x` | double | -5.0 | minimum x value of the crop box |
43+
| `min_y` | double | -5.0 | minimum y value of the crop box |
44+
| `min_z` | double | -5.0 | minimum z value of the crop box |
45+
| `max_x` | double | 5.0 | maximum x value of the crop box |
46+
| `max_y` | double | 5.0 | maximum y value of the crop box |
47+
| `max_z` | double | 5.0 | maximum z value of the crop box |
48+
| `negative` | bool | true | if true, points inside the box are removed, otherwise points outside the box are removed |
5049

5150
## Usage
5251

sensing/autoware_crop_box_filter/include/autoware/crop_box_filter/crop_box_filter_node.hpp

+11-15
Original file line numberDiff line numberDiff line change
@@ -55,21 +55,20 @@
5555
#ifndef AUTOWARE__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_
5656
#define AUTOWARE__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_
5757

58-
#include <geometry_msgs/msg/polygon_stamped.hpp>
59-
#include <sensor_msgs/msg/point_cloud2.hpp>
60-
#include <sensor_msgs/point_cloud2_iterator.hpp>
61-
58+
#include <autoware/point_types/types.hpp>
6259
#include <autoware_utils/ros/debug_publisher.hpp>
6360
#include <autoware_utils/ros/managed_transform_buffer.hpp>
6461
#include <autoware_utils/ros/published_time_publisher.hpp>
6562
#include <autoware_utils/system/stop_watch.hpp>
6663

67-
#include <autoware/point_types/types.hpp>
64+
#include <geometry_msgs/msg/polygon_stamped.hpp>
65+
#include <sensor_msgs/msg/point_cloud2.hpp>
66+
#include <sensor_msgs/point_cloud2_iterator.hpp>
6867

6968
#include <memory>
70-
#include <vector>
7169
#include <string>
7270
#include <utility>
71+
#include <vector>
7372

7473
using PointCloud2 = sensor_msgs::msg::PointCloud2;
7574
using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr;
@@ -83,9 +82,7 @@ namespace autoware::crop_box_filter
8382

8483
class CropBoxFilter : public rclcpp::Node
8584
{
86-
8785
private:
88-
8986
// member variable declaration & definitions *************************************
9087

9188
/** \brief The managed transform buffer. */
@@ -142,16 +139,16 @@ class CropBoxFilter : public rclcpp::Node
142139
std::unique_ptr<autoware_utils::PublishedTimePublisher> published_time_publisher_;
143140

144141
// function declaration *************************************
145-
142+
146143
void publish_crop_box_polygon();
147-
144+
148145
void pointcloud_callback(const PointCloud2ConstPtr cloud);
149146

150147
/** \brief Parameter service callback */
151148
rcl_interfaces::msg::SetParametersResult param_callback(const std::vector<rclcpp::Parameter> & p);
152149

153-
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to
154-
* say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */
150+
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is
151+
* to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */
155152
bool is_data_layout_compatible_with_point_xyzi(const PointCloud2 & input);
156153

157154
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is
@@ -162,8 +159,8 @@ class CropBoxFilter : public rclcpp::Node
162159
* is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */
163160
bool is_data_layout_compatible_with_point_xyziradrt(const PointCloud2 & input);
164161

165-
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT. That
166-
* is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */
162+
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT.
163+
* That is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */
167164
bool is_data_layout_compatible_with_point_xyzircaedt(const PointCloud2 & input);
168165

169166
bool is_valid(const PointCloud2ConstPtr & cloud);
@@ -181,7 +178,6 @@ class CropBoxFilter : public rclcpp::Node
181178
}
182179
return false;
183180
}
184-
185181

186182
public:
187183
PCL_MAKE_ALIGNED_OPERATOR_NEW

sensing/autoware_crop_box_filter/package.xml

+1-2
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
<maintainer email="lxg19892021@gmail.com">Xingang Liu</maintainer>
1818
<license>Apache License 2.0</license>
1919

20-
2120
<!-- Original authors -->
2221
<author>Open Perception</author>
2322
<author email="julius@kammerl.de">Julius Kammerl</author>
@@ -28,10 +27,10 @@
2827

2928
<depend>autoware_point_types</depend>
3029
<depend>autoware_utils</depend>
30+
<depend>geometry_msgs</depend>
3131
<depend>rclcpp</depend>
3232
<depend>rclcpp_components</depend>
3333
<depend>sensor_msgs</depend>
34-
<depend>geometry_msgs</depend>
3534

3635
<test_depend>ament_lint_auto</test_depend>
3736
<test_depend>autoware_lint_common</test_depend>

sensing/autoware_crop_box_filter/src/crop_box_filter_node.cpp

+38-58
Original file line numberDiff line numberDiff line change
@@ -52,10 +52,11 @@
5252
*/
5353

5454
#include "autoware/crop_box_filter/crop_box_filter_node.hpp"
55+
5556
#include <memory>
56-
#include <vector>
5757
#include <string>
5858
#include <utility>
59+
#include <vector>
5960

6061
namespace autoware::crop_box_filter
6162
{
@@ -78,60 +79,47 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
7879

7980
// get transform info for pointcloud
8081
{
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"));
8384
tf_input_frame_ = static_cast<std::string>(declare_parameter("input_frame", "base_link"));
8485
tf_output_frame_ = static_cast<std::string>(declare_parameter("output_frame", "base_link"));
8586

8687
// Always consider static TF if in & out frames are same
8788
bool has_static_tf_only = false;
8889
if (tf_input_frame_ == tf_output_frame_) {
89-
9090
RCLCPP_INFO(
9191
this->get_logger(),
9292
"Input and output frames are the same. Overriding has_static_tf_only to true.");
93-
93+
9494
has_static_tf_only = true;
9595
}
9696
managed_tf_buffer_ =
9797
std::make_unique<autoware_utils::ManagedTransformBuffer>(this, has_static_tf_only);
9898

99-
100-
if (tf_input_orig_frame_ == tf_input_frame_)
101-
{
99+
if (tf_input_orig_frame_ == tf_input_frame_) {
102100
need_preprocess_transform_ = false;
103101
eigen_transform_preprocess_ = Eigen::Matrix4f::Identity(4, 4);
104-
}
105-
else
106-
{
102+
} else {
107103
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_)) {
110105
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 {
116109
need_preprocess_transform_ = true;
117110
}
118111
}
119112

120-
if (tf_input_frame_ == tf_output_frame_)
121-
{
113+
if (tf_input_frame_ == tf_output_frame_) {
122114
need_postprocess_transform_ = false;
123115
eigen_transform_postprocess_ = Eigen::Matrix4f::Identity(4, 4);
124-
}else
125-
{
116+
} else {
126117
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_)) {
129119
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 {
135123
need_postprocess_transform_ = true;
136124
}
137125
}
@@ -170,18 +158,17 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
170158
// set parameter service callback
171159
{
172160
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));
175163
}
176164

177165
// set input pointcloud callback
178166
{
179167
sub_input_ = this->create_subscription<PointCloud2>(
180-
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_),
168+
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_),
181169
std::bind(&CropBoxFilter::pointcloud_callback, this, std::placeholders::_1));
182170
}
183171

184-
185172
RCLCPP_DEBUG(this->get_logger(), "[Filter Constructor] successfully created.");
186173
}
187174

@@ -198,11 +185,10 @@ void CropBoxFilter::pointcloud_filter(const PointCloud2ConstPtr & cloud, PointCl
198185

199186
// pointcloud processing loop
200187
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) {
203189
// extract point data from point cloud data buffer
204190
Eigen::Vector4f point;
205-
191+
206192
std::memcpy(&point[0], &cloud->data[global_offset + x_offset], sizeof(float));
207193
std::memcpy(&point[1], &cloud->data[global_offset + y_offset], sizeof(float));
208194
std::memcpy(&point[2], &cloud->data[global_offset + z_offset], sizeof(float));
@@ -221,26 +207,23 @@ void CropBoxFilter::pointcloud_filter(const PointCloud2ConstPtr & cloud, PointCl
221207
point_preprocessed = eigen_transform_preprocess_ * point;
222208
}
223209

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;
227214
if ((!param_.negative && point_is_inside) || (param_.negative && !point_is_inside)) {
228-
229215
// 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_) {
234218
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point_preprocessed;
235219

236220
memcpy(&output.data[output_size], &cloud->data[global_offset], cloud->point_step);
237221

238222
std::memcpy(&output.data[output_size + x_offset], &point_postprocessed[0], sizeof(float));
239223
std::memcpy(&output.data[output_size + y_offset], &point_postprocessed[1], sizeof(float));
240224
std::memcpy(&output.data[output_size + z_offset], &point_postprocessed[2], sizeof(float));
241-
242-
}else
243-
{
225+
226+
} else {
244227
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point;
245228

246229
memcpy(&output.data[output_size], &cloud->data[global_offset], cloud->point_step);
@@ -249,9 +232,7 @@ void CropBoxFilter::pointcloud_filter(const PointCloud2ConstPtr & cloud, PointCl
249232
std::memcpy(&output.data[output_size + y_offset], &point_postprocessed[1], sizeof(float));
250233
std::memcpy(&output.data[output_size + z_offset], &point_postprocessed[2], sizeof(float));
251234
}
252-
}
253-
else
254-
{
235+
} else {
255236
memcpy(&output.data[output_size], &cloud->data[global_offset], cloud->point_step);
256237

257238
if (need_preprocess_transform_) {
@@ -300,19 +281,18 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
300281
"received.",
301282
cloud->width * cloud->height, cloud->header.frame_id.c_str());
302283
// pointcloud check finished
303-
284+
304285
// pointcloud processing
305286
auto output = PointCloud2();
306287

307288
std::scoped_lock lock(mutex_);
308289
stop_watch_ptr_->toc("processing_time", true);
309290

310291
// filtering
311-
pointcloud_filter( cloud, output);
292+
pointcloud_filter(cloud, output);
312293

313294
// 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) {
316296
publish_crop_box_polygon();
317297
}
318298

@@ -404,7 +384,8 @@ rcl_interfaces::msg::SetParametersResult CropBoxFilter::param_callback(
404384
new_param.max_x = get_param(p, "max_x", new_param.max_x) ? new_param.max_x : param_.max_x;
405385
new_param.max_y = get_param(p, "max_y", new_param.max_y) ? new_param.max_y : param_.max_y;
406386
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;
408389

409390
param_ = new_param;
410391

@@ -605,13 +586,12 @@ bool CropBoxFilter::is_data_layout_compatible_with_point_xyzircaedt(const PointC
605586
return same_layout;
606587
}
607588

608-
bool CropBoxFilter::is_valid( const PointCloud2ConstPtr & cloud)
589+
bool CropBoxFilter::is_valid(const PointCloud2ConstPtr & cloud)
609590
{
610591
// firstly check the fields of the point cloud
611592
if (
612593
!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)) {
615595
RCLCPP_ERROR(
616596
get_logger(),
617597
"The pointcloud layout is not compatible with PointXYZIRCAEDT or PointXYZIRC. Aborting");

0 commit comments

Comments
 (0)