Skip to content

Commit fd55475

Browse files
style(pre-commit): autofix
1 parent 3a62c18 commit fd55475

File tree

4 files changed

+45
-78
lines changed

4 files changed

+45
-78
lines changed

sensing/autoware_crop_box_filter/CMakeLists.txt

-2
Original file line numberDiff line numberDiff line change
@@ -26,5 +26,3 @@ ament_auto_package(INSTALL_TO_SHARE
2626
launch
2727
config
2828
)
29-
30-

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

+14-18
Original file line numberDiff line numberDiff line change
@@ -55,32 +55,29 @@
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-
58+
#include <autoware/point_types/types.hpp>
6159
#include <autoware_utils/ros/debug_publisher.hpp>
6260
#include <autoware_utils/ros/managed_transform_buffer.hpp>
6361
#include <autoware_utils/ros/published_time_publisher.hpp>
6462
#include <autoware_utils/system/stop_watch.hpp>
6563

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

6867
#include <vector>
6968

7069
namespace autoware::crop_box_filter
7170
{
7271
class CropBoxFilter : public rclcpp::Node
7372
{
73+
using PointCloud2 = sensor_msgs::msg::PointCloud2;
74+
using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr;
7475

75-
using PointCloud2 = sensor_msgs::msg::PointCloud2;
76-
using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr;
77-
78-
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
79-
using PointCloudPtr = PointCloud::Ptr;
80-
using PointCloudConstPtr = PointCloud::ConstPtr;
76+
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
77+
using PointCloudPtr = PointCloud::Ptr;
78+
using PointCloudConstPtr = PointCloud::ConstPtr;
8179

8280
private:
83-
8481
// member variable declearation & definitions *************************************
8582

8683
/** \brief The managed transform buffer. */
@@ -137,16 +134,16 @@ using PointCloudConstPtr = PointCloud::ConstPtr;
137134
std::unique_ptr<autoware_utils::PublishedTimePublisher> published_time_publisher_;
138135

139136
// function declaration *************************************
140-
137+
141138
void publish_crop_box_polygon();
142-
139+
143140
void pointcloud_callback(const PointCloud2ConstPtr cloud);
144141

145142
/** \brief Parameter service callback */
146143
rcl_interfaces::msg::SetParametersResult param_callback(const std::vector<rclcpp::Parameter> & p);
147144

148-
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to
149-
* say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */
145+
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is
146+
* to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */
150147
bool is_data_layout_compatible_with_point_xyzi(const PointCloud2 & input);
151148

152149
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is
@@ -157,8 +154,8 @@ using PointCloudConstPtr = PointCloud::ConstPtr;
157154
* is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */
158155
bool is_data_layout_compatible_with_point_xyziradrt(const PointCloud2 & input);
159156

160-
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT. That
161-
* is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */
157+
/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT.
158+
* That is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */
162159
bool is_data_layout_compatible_with_point_xyzircaedt(const PointCloud2 & input);
163160

164161
bool is_valid(const PointCloud2ConstPtr & cloud);
@@ -176,7 +173,6 @@ using PointCloudConstPtr = PointCloud::ConstPtr;
176173
}
177174
return false;
178175
}
179-
180176

181177
public:
182178
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

+30-56
Original file line numberDiff line numberDiff line change
@@ -79,60 +79,47 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
7979

8080
// get transform info for pointcloud
8181
{
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"));
8484
tf_input_frame_ = static_cast<std::string>(declare_parameter("input_frame", "base_link"));
8585
tf_output_frame_ = static_cast<std::string>(declare_parameter("output_frame", "base_link"));
8686

8787
// Always consider static TF if in & out frames are same
8888
bool has_static_tf_only = false;
8989
if (tf_input_frame_ == tf_output_frame_) {
90-
9190
RCLCPP_INFO(
9291
this->get_logger(),
9392
"Input and output frames are the same. Overriding has_static_tf_only to true.");
94-
93+
9594
has_static_tf_only = true;
9695
}
9796
managed_tf_buffer_ =
9897
std::make_unique<autoware_utils::ManagedTransformBuffer>(this, has_static_tf_only);
9998

100-
101-
if (tf_input_orig_frame_ == tf_input_frame_)
102-
{
99+
if (tf_input_orig_frame_ == tf_input_frame_) {
103100
need_preprocess_transform_ = false;
104101
eigen_transform_preprocess_ = Eigen::Matrix4f::Identity(4, 4);
105-
}
106-
else
107-
{
102+
} else {
108103
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_)) {
111105
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 {
117109
need_preprocess_transform_ = true;
118110
}
119111
}
120112

121-
if (tf_input_frame_ == tf_output_frame_)
122-
{
113+
if (tf_input_frame_ == tf_output_frame_) {
123114
need_postprocess_transform_ = false;
124115
eigen_transform_postprocess_ = Eigen::Matrix4f::Identity(4, 4);
125-
}else
126-
{
116+
} else {
127117
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_)) {
130119
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 {
136123
need_postprocess_transform_ = true;
137124
}
138125
}
@@ -171,31 +158,26 @@ CropBoxFilter::CropBoxFilter(const rclcpp::NodeOptions & node_options)
171158
// set parameter service callback
172159
{
173160
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));
176163
}
177164

178165
// set input pointcloud callback
179166
{
180167
sub_input_ = this->create_subscription<PointCloud2>(
181-
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_),
168+
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_),
182169
std::bind(&CropBoxFilter::pointcloud_callback, this, std::placeholders::_1));
183170
}
184171

185-
186172
RCLCPP_DEBUG(this->get_logger(), "[Filter Constructor] successfully created.");
187173
}
188174

189-
190-
191-
192175
void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
193176
{
194177
// chechk if the pointcloud is valid
195178
if (
196179
!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)) {
199181
RCLCPP_ERROR(
200182
get_logger(),
201183
"The pointcloud layout is not compatible with PointXYZIRCAEDT or PointXYZIRC. Aborting");
@@ -228,14 +210,13 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
228210
"received.",
229211
cloud->width * cloud->height, cloud->header.frame_id.c_str());
230212
// pointcloud check finished
231-
213+
232214
// pointcloud processing
233215
auto output = PointCloud2();
234216

235217
std::scoped_lock lock(mutex_);
236218
stop_watch_ptr_->toc("processing_time", true);
237219

238-
239220
int x_offset = cloud->fields[pcl::getFieldIndex(*cloud, "x")].offset;
240221
int y_offset = cloud->fields[pcl::getFieldIndex(*cloud, "y")].offset;
241222
int z_offset = cloud->fields[pcl::getFieldIndex(*cloud, "z")].offset;
@@ -247,8 +228,7 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
247228

248229
// pointcloud processing loop
249230
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) {
252232
Eigen::Vector4f point;
253233
Eigen::Vector4f point_preprocessed;
254234
std::memcpy(&point[0], &cloud->data[global_offset + x_offset], sizeof(float));
@@ -271,22 +251,18 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
271251
point[1] > param_.min_y && point[1] < param_.max_y &&
272252
point[0] > param_.min_x && point[0] < param_.max_x;
273253
if ((!param_.negative && point_is_inside) || (param_.negative && !point_is_inside)) {
274-
275254
// 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_) {
280257
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point_preprocessed;
281258

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

284261
std::memcpy(&output.data[output_size + x_offset], &point_postprocessed[0], sizeof(float));
285262
std::memcpy(&output.data[output_size + y_offset], &point_postprocessed[1], sizeof(float));
286263
std::memcpy(&output.data[output_size + z_offset], &point_postprocessed[2], sizeof(float));
287-
288-
}else
289-
{
264+
265+
} else {
290266
Eigen::Vector4f point_postprocessed = eigen_transform_postprocess_ * point;
291267

292268
memcpy(&output.data[output_size], &cloud->data[global_offset], cloud->point_step);
@@ -295,9 +271,7 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
295271
std::memcpy(&output.data[output_size + y_offset], &point_postprocessed[1], sizeof(float));
296272
std::memcpy(&output.data[output_size + z_offset], &point_postprocessed[2], sizeof(float));
297273
}
298-
}
299-
else
300-
{
274+
} else {
301275
memcpy(&output.data[output_size], &cloud->data[global_offset], cloud->point_step);
302276

303277
if (need_preprocess_transform_) {
@@ -330,8 +304,7 @@ void CropBoxFilter::pointcloud_callback(const PointCloud2ConstPtr cloud)
330304
output.row_step = static_cast<uint32_t>(output.data.size() / output.height);
331305

332306
// 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) {
335308
publish_crop_box_polygon();
336309
}
337310

@@ -424,7 +397,8 @@ rcl_interfaces::msg::SetParametersResult CropBoxFilter::param_callback(
424397
new_param.max_x = get_param(p, "max_x", new_param.max_x) ? new_param.max_x : param_.max_x;
425398
new_param.max_y = get_param(p, "max_y", new_param.max_y) ? new_param.max_y : param_.max_y;
426399
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;
428402

429403
param_ = new_param;
430404

@@ -625,7 +599,7 @@ bool CropBoxFilter::is_data_layout_compatible_with_point_xyzircaedt(const PointC
625599
return same_layout;
626600
}
627601

628-
bool CropBoxFilter::is_valid( const PointCloud2ConstPtr & cloud)
602+
bool CropBoxFilter::is_valid(const PointCloud2ConstPtr & cloud)
629603
{
630604
if (cloud->width * cloud->height * cloud->point_step != cloud->data.size()) {
631605
RCLCPP_WARN(

0 commit comments

Comments
 (0)