diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 9f1a9d206e376..0c2cb98ffbb35 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -48,6 +48,8 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) override; bool ready() const override; LaneletRoute plan(const RoutePoints & points) override; + void updateRoute(const PlannerPlugin::LaneletRoute & route) override; + void clearRoute() override; MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint(tier4_autoware_utils::LinearRing2d goal_footprint_) const; vehicle_info_util::VehicleInfo vehicle_info_; @@ -102,9 +104,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin * route_sections) and return the z-aligned goal position */ Pose refine_goal_height(const Pose & goal, const RouteSections & route_sections); - - void updateRoute(const PlannerPlugin::LaneletRoute & route); - void clearRoute(); }; } // namespace mission_planner::lanelet2