31
31
#include " tier4_planning_msgs/msg/detail/lane_change_debug_msg_array__struct.hpp"
32
32
#include < autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
33
33
#include < autoware_auto_perception_msgs/msg/predicted_objects.hpp>
34
- #include < autoware_auto_planning_msgs/msg/had_map_route.hpp>
35
34
#include < autoware_auto_planning_msgs/msg/path.hpp>
36
35
#include < autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
37
36
#include < autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
38
37
#include < autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
38
+ #include < autoware_planning_msgs/msg/lanelet_route.hpp>
39
39
#include < nav_msgs/msg/occupancy_grid.hpp>
40
40
#include < nav_msgs/msg/odometry.hpp>
41
41
#include < tier4_planning_msgs/msg/approval.hpp>
@@ -66,11 +66,11 @@ namespace behavior_path_planner
66
66
using ApprovalMsg = tier4_planning_msgs::msg::Approval;
67
67
using autoware_auto_mapping_msgs::msg::HADMapBin;
68
68
using autoware_auto_perception_msgs::msg::PredictedObjects;
69
- using autoware_auto_planning_msgs::msg::HADMapRoute;
70
69
using autoware_auto_planning_msgs::msg::Path;
71
70
using autoware_auto_planning_msgs::msg::PathWithLaneId;
72
71
using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;
73
72
using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand;
73
+ using autoware_planning_msgs::msg::LaneletRoute;
74
74
using geometry_msgs::msg::TwistStamped;
75
75
using nav_msgs::msg::OccupancyGrid;
76
76
using nav_msgs::msg::Odometry;
@@ -88,7 +88,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
88
88
explicit BehaviorPathPlannerNode (const rclcpp::NodeOptions & node_options);
89
89
90
90
private:
91
- rclcpp::Subscription<HADMapRoute >::SharedPtr route_subscriber_;
91
+ rclcpp::Subscription<LaneletRoute >::SharedPtr route_subscriber_;
92
92
rclcpp::Subscription<HADMapBin>::SharedPtr vector_map_subscriber_;
93
93
rclcpp::Subscription<Odometry>::SharedPtr velocity_subscriber_;
94
94
rclcpp::Subscription<AccelWithCovarianceStamped>::SharedPtr acceleration_subscriber_;
@@ -136,7 +136,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
136
136
void onExternalApproval (const ApprovalMsg::ConstSharedPtr msg);
137
137
void onForceApproval (const PathChangeModule::ConstSharedPtr msg);
138
138
void onMap (const HADMapBin::ConstSharedPtr map_msg);
139
- void onRoute (const HADMapRoute ::ConstSharedPtr route_msg);
139
+ void onRoute (const LaneletRoute ::ConstSharedPtr route_msg);
140
140
SetParametersResult onSetParam (const std::vector<rclcpp::Parameter> & parameters);
141
141
142
142
/* *
0 commit comments