Skip to content

Commit 460029a

Browse files
committed
fix include header
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
1 parent 4a2835e commit 460029a

File tree

1 file changed

+1
-1
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common

1 file changed

+1
-1
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828

2929
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
3030
#include <autoware_internal_planning_msgs/msg/path_with_lane_id.hpp>
31+
#include <autoware_internal_planning_msgs/msg/detail/velocity_limit__struct.hpp>
3132
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
3233
#include <autoware_perception_msgs/msg/traffic_light_group_array.hpp>
3334
#include <autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp>
@@ -38,7 +39,6 @@
3839
#include <geometry_msgs/msg/pose_stamped.hpp>
3940
#include <nav_msgs/msg/occupancy_grid.hpp>
4041
#include <nav_msgs/msg/odometry.hpp>
41-
#include <tier4_planning_msgs/msg/detail/velocity_limit__struct.hpp>
4242
#include <tier4_planning_msgs/msg/lateral_offset.hpp>
4343

4444
#include <limits>

0 commit comments

Comments
 (0)