Skip to content

Commit 6bc2afc

Browse files
Fixed includes
Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
1 parent 0262ec2 commit 6bc2afc

File tree

4 files changed

+5
-2
lines changed

4 files changed

+5
-2
lines changed

localization/ndt_scan_matcher/test/stub_initialpose_client.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

20+
#include "tier4_localization_msgs/srv/pose_with_covariance_stamped.hpp"
2021
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
2122

2223
#include <memory>

localization/ndt_scan_matcher/test/stub_pcd_loader.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121

2222
#include "autoware_map_msgs/srv/get_differential_point_cloud_map.hpp"
2323

24+
#include <pcl_conversions/pcl_conversions.h>
25+
2426
class StubPcdLoader : public rclcpp::Node
2527
{
2628
using GetDifferentialPointCloudMap = autoware_map_msgs::srv::GetDifferentialPointCloudMap;

localization/ndt_scan_matcher/test/stub_sensor_pcd_publisher.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

20-
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
20+
#include <sensor_msgs/msg/point_cloud2.hpp>
2121

2222
class StubSensorPcdPublisher : public rclcpp::Node
2323
{

localization/ndt_scan_matcher/test/test_util.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <pcl/point_cloud.h>
1919
#include <pcl/point_types.h>
2020

21-
pcl::PointCloud<pcl::PointXYZ> make_sample_pcd(
21+
inline pcl::PointCloud<pcl::PointXYZ> make_sample_pcd(
2222
const float min_xy, const float max_xy, const float interval)
2323
{
2424
const float range_width = max_xy - min_xy;

0 commit comments

Comments
 (0)