55
55
#ifndef AUTOWARE__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_
56
56
#define AUTOWARE__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_
57
57
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>
62
59
#include < autoware_utils/ros/debug_publisher.hpp>
63
60
#include < autoware_utils/ros/managed_transform_buffer.hpp>
64
61
#include < autoware_utils/ros/published_time_publisher.hpp>
65
62
#include < autoware_utils/system/stop_watch.hpp>
66
63
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>
68
67
69
68
#include < memory>
70
- #include < vector>
71
69
#include < string>
72
70
#include < utility>
71
+ #include < vector>
73
72
74
73
using PointCloud2 = sensor_msgs::msg::PointCloud2;
75
74
using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr;
@@ -83,9 +82,7 @@ namespace autoware::crop_box_filter
83
82
84
83
class CropBoxFilter : public rclcpp ::Node
85
84
{
86
-
87
85
private:
88
-
89
86
// member variable declaration & definitions *************************************
90
87
91
88
/* * \brief The managed transform buffer. */
@@ -142,16 +139,16 @@ class CropBoxFilter : public rclcpp::Node
142
139
std::unique_ptr<autoware_utils::PublishedTimePublisher> published_time_publisher_;
143
140
144
141
// function declaration *************************************
145
-
142
+
146
143
void publish_crop_box_polygon ();
147
-
144
+
148
145
void pointcloud_callback (const PointCloud2ConstPtr cloud);
149
146
150
147
/* * \brief Parameter service callback */
151
148
rcl_interfaces::msg::SetParametersResult param_callback (const std::vector<rclcpp::Parameter> & p);
152
149
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 */
155
152
bool is_data_layout_compatible_with_point_xyzi (const PointCloud2 & input);
156
153
157
154
/* * \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is
@@ -162,8 +159,8 @@ class CropBoxFilter : public rclcpp::Node
162
159
* is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */
163
160
bool is_data_layout_compatible_with_point_xyziradrt (const PointCloud2 & input);
164
161
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 */
167
164
bool is_data_layout_compatible_with_point_xyzircaedt (const PointCloud2 & input);
168
165
169
166
bool is_valid (const PointCloud2ConstPtr & cloud);
@@ -181,12 +178,11 @@ class CropBoxFilter : public rclcpp::Node
181
178
}
182
179
return false ;
183
180
}
184
-
185
181
186
182
public:
187
183
PCL_MAKE_ALIGNED_OPERATOR_NEW
188
184
explicit CropBoxFilter (const rclcpp::NodeOptions & options);
189
- void pointcloud_filter (const PointCloud2ConstPtr & cloud, PointCloud2 & output);
185
+ void filter_pointcloud (const PointCloud2ConstPtr & cloud, PointCloud2 & output);
190
186
};
191
187
} // namespace autoware::crop_box_filter
192
188
0 commit comments