diff --git a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp index 56d6526e26272..255288603016b 100644 --- a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -115,7 +115,7 @@ void AbstractPlanningAlgorithm::setMap(const nav_msgs::msg::OccupancyGrid & cost std::vector is_obstacle_table; is_obstacle_table.resize(nb_of_cells); for (uint32_t i = 0; i < nb_of_cells; ++i) { - const int cost = costmap_.data[i]; + const int cost = costmap_.data[i]; // NOLINT if (cost < 0 || planner_common_param_.obstacle_threshold <= cost) { is_obstacle_table[i] = true; } diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 0a17b112eed6f..c9f4b46dab737 100644 --- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -388,7 +388,7 @@ double AstarSearch::getExpansionDistance(const AstarNode & current_node) const double AstarSearch::getSteeringCost(const int steering_index) const { return planner_common_param_.curve_weight * - (abs(steering_index) / planner_common_param_.turning_steps); + (static_cast(abs(steering_index)) / planner_common_param_.turning_steps); } double AstarSearch::getSteeringChangeCost(