|
12 | 12 | // See the License for the specific language governing permissions and
|
13 | 13 | // limitations under the License.
|
14 | 14 |
|
15 |
| -#ifndef RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_ |
16 |
| -#define RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_ |
| 15 | +#ifndef LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_ |
| 16 | +#define LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_ |
17 | 17 |
|
| 18 | +#include "autoware/universe_utils/ros/debug_publisher.hpp" |
| 19 | +#include "autoware/universe_utils/system/stop_watch.hpp" |
18 | 20 | #include "detected_object_validation/utils/utils.hpp"
|
19 | 21 |
|
20 |
| -#include <autoware/universe_utils/ros/debug_publisher.hpp> |
21 |
| -#include <autoware/universe_utils/system/stop_watch.hpp> |
| 22 | +#include <Eigen/Eigen> |
22 | 23 | #include <rclcpp/rclcpp.hpp>
|
23 | 24 |
|
24 |
| -#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp> |
| 25 | +#include "tier4_perception_msgs/msg/detected_objects_with_feature.hpp" |
25 | 26 |
|
26 | 27 | #include <tf2_ros/buffer.h>
|
27 | 28 | #include <tf2_ros/transform_listener.h>
|
28 |
| -// #include <tf2_eigen/tf2_eigen.hpp> |
29 |
| -#include <Eigen/Eigen> |
30 | 29 |
|
31 | 30 | #include <memory>
|
32 | 31 | #include <string>
|
33 | 32 |
|
34 |
| -namespace low_intensity_cluster_filter |
| 33 | +namespace autoware::low_intensity_cluster_filter |
35 | 34 | {
|
36 | 35 |
|
37 | 36 | class LowIntensityClusterFilter : public rclcpp::Node
|
@@ -73,6 +72,6 @@ class LowIntensityClusterFilter : public rclcpp::Node
|
73 | 72 | std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_ptr_{nullptr};
|
74 | 73 | };
|
75 | 74 |
|
76 |
| -} // namespace low_intensity_cluster_filter |
| 75 | +} // namespace autoware::low_intensity_cluster_filter |
77 | 76 |
|
78 |
| -#endif // RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_ |
| 77 | +#endif // LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_ |
0 commit comments