|
31 | 31 | #include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
|
32 | 32 | #include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
|
33 | 33 | #include <autoware_planning_msgs/msg/lanelet_route.hpp>
|
34 |
| -#include <autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp> |
35 | 34 | #include <autoware_planning_msgs/msg/mission_remaining_distance_time.hpp>
|
| 35 | +#include <autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp> |
36 | 36 | #include <geometry_msgs/msg/pose.hpp>
|
37 | 37 | #include <nav_msgs/msg/occupancy_grid.hpp>
|
38 | 38 | #include <nav_msgs/msg/odometry.hpp>
|
@@ -63,8 +63,8 @@ using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;
|
63 | 63 | using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand;
|
64 | 64 | using autoware_perception_msgs::msg::TrafficSignalArray;
|
65 | 65 | using autoware_planning_msgs::msg::LaneletRoute;
|
66 |
| -using autoware_planning_msgs::msg::PoseWithUuidStamped; |
67 | 66 | using autoware_planning_msgs::msg::MissionRemainingDistanceTime;
|
| 67 | +using autoware_planning_msgs::msg::PoseWithUuidStamped; |
68 | 68 | using geometry_msgs::msg::Pose;
|
69 | 69 | using nav_msgs::msg::OccupancyGrid;
|
70 | 70 | using nav_msgs::msg::Odometry;
|
@@ -111,7 +111,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
|
111 | 111 | rclcpp::Subscription<LateralOffset>::SharedPtr lateral_offset_subscriber_;
|
112 | 112 | rclcpp::Subscription<OperationModeState>::SharedPtr operation_mode_subscriber_;
|
113 | 113 | rclcpp::Publisher<PathWithLaneId>::SharedPtr path_publisher_;
|
114 |
| - rclcpp::Publisher<MissionRemainingDistanceTime>::SharedPtr mission_remaining_distance_time_publisher_; |
| 114 | + rclcpp::Publisher<MissionRemainingDistanceTime>::SharedPtr |
| 115 | + mission_remaining_distance_time_publisher_; |
115 | 116 | rclcpp::Publisher<TurnIndicatorsCommand>::SharedPtr turn_signal_publisher_;
|
116 | 117 | rclcpp::Publisher<HazardLightsCommand>::SharedPtr hazard_signal_publisher_;
|
117 | 118 | rclcpp::Publisher<MarkerArray>::SharedPtr bound_publisher_;
|
@@ -193,7 +194,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
|
193 | 194 | // debug
|
194 | 195 | rclcpp::Publisher<AvoidanceDebugMsgArray>::SharedPtr debug_avoidance_msg_array_publisher_;
|
195 | 196 | rclcpp::Publisher<MarkerArray>::SharedPtr debug_turn_signal_info_publisher_;
|
196 |
| - |
| 197 | + |
197 | 198 | /**
|
198 | 199 | * @brief compute mission remaining distance and time
|
199 | 200 | */
|
|
0 commit comments