diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 5225a6dd4abd9..fc0cd4ac539ca 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -30,6 +30,7 @@ #include #include +#include #include #include @@ -58,17 +59,17 @@ class OutOfLaneModule : public PluginModuleInterface out_of_lane::EgoData & ego_data, const PlannerData & planner_data, std::optional & previous_slowdown_pose_, const double slow_velocity); - out_of_lane::PlannerParam params_; + out_of_lane::PlannerParam params_{}; inline static const std::string ns_ = "out_of_lane"; - std::string module_name_; - rclcpp::Clock::SharedPtr clock_; - std::optional previous_slowdown_pose_; - rclcpp::Time previous_slowdown_time_; + std::string module_name_{"uninitialized"}; + rclcpp::Clock::SharedPtr clock_{nullptr}; + std::optional previous_slowdown_pose_{std::nullopt}; + rclcpp::Time previous_slowdown_time_{0}; protected: // Debug - mutable out_of_lane::DebugData debug_data_; + mutable out_of_lane::DebugData debug_data_{}; }; } // namespace autoware::motion_velocity_planner