diff --git a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp index 2f59543e2442c..b4a98d90c74e4 100644 --- a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp +++ b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp @@ -45,7 +45,7 @@ struct Output class GoalDistanceCalculator { public: - Output update(const Input & input); + static Output update(const Input & input); void setParam(const Param & param) { param_ = param; } diff --git a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp index 10aba5872b66a..50051d928b6c1 100644 --- a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp +++ b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp @@ -33,8 +33,8 @@ namespace goal_distance_calculator { struct NodeParam { - double update_rate; - bool oneshot; + double update_rate{0.0}; + bool oneshot{false}; }; class GoalDistanceCalculatorNode : public rclcpp::Node