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
namespace autoware ::crop_box_filter
75
74
{
76
75
class CropBoxFilter : public rclcpp ::Node
77
76
{
77
+ using PointCloud2 = sensor_msgs::msg::PointCloud2;
78
+ using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr;
78
79
79
- using PointCloud2 = sensor_msgs::msg::PointCloud2;
80
- using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr;
81
-
82
- using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
83
- using PointCloudPtr = PointCloud::Ptr ;
84
- using PointCloudConstPtr = PointCloud::ConstPtr;
80
+ using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
81
+ using PointCloudPtr = PointCloud::Ptr ;
82
+ using PointCloudConstPtr = PointCloud::ConstPtr;
85
83
86
84
private:
87
-
88
85
// member variable declaration & definitions *************************************
89
86
90
87
/* * \brief The managed transform buffer. */
@@ -141,16 +138,16 @@ using PointCloudConstPtr = PointCloud::ConstPtr;
141
138
std::unique_ptr<autoware_utils::PublishedTimePublisher> published_time_publisher_;
142
139
143
140
// function declaration *************************************
144
-
141
+
145
142
void publish_crop_box_polygon ();
146
-
143
+
147
144
void pointcloud_callback (const PointCloud2ConstPtr cloud);
148
145
149
146
/* * \brief Parameter service callback */
150
147
rcl_interfaces::msg::SetParametersResult param_callback (const std::vector<rclcpp::Parameter> & p);
151
148
152
- /* * \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to
153
- * say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */
149
+ /* * \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is
150
+ * to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */
154
151
bool is_data_layout_compatible_with_point_xyzi (const PointCloud2 & input);
155
152
156
153
/* * \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is
@@ -161,8 +158,8 @@ using PointCloudConstPtr = PointCloud::ConstPtr;
161
158
* is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */
162
159
bool is_data_layout_compatible_with_point_xyziradrt (const PointCloud2 & input);
163
160
164
- /* * \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT. That
165
- * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */
161
+ /* * \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT.
162
+ * That is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */
166
163
bool is_data_layout_compatible_with_point_xyzircaedt (const PointCloud2 & input);
167
164
168
165
bool is_valid (const PointCloud2ConstPtr & cloud);
@@ -180,7 +177,6 @@ using PointCloudConstPtr = PointCloud::ConstPtr;
180
177
}
181
178
return false ;
182
179
}
183
-
184
180
185
181
public:
186
182
PCL_MAKE_ALIGNED_OPERATOR_NEW
0 commit comments