Skip to content

Commit

Permalink
fix: bugprone-error
Browse files Browse the repository at this point in the history
Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>
  • Loading branch information
kobayu858 committed Dec 23, 2024
1 parent a88e90e commit 842984f
Showing 1 changed file with 3 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp"

#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>:

#include <lanelet2_routing/RoutingGraph.h>
#include <lanelet2_traffic_rules/TrafficRulesFactory.h>
Expand Down Expand Up @@ -585,9 +585,7 @@ void SimplePlanningSimulator::set_input(const InputCommand & cmd, const double a
std::visit(
[this, acc_by_slope](auto && arg) {
using T = std::decay_t<decltype(arg)>;
if constexpr (std::is_same_v<T, Control>) {
set_input(arg, acc_by_slope);
} else if constexpr (std::is_same_v<T, ActuationCommandStamped>) {
if constexpr (std::is_same_v<T, Control> || std::is_same_v<T, ActuationCommandStamped>) {
set_input(arg, acc_by_slope);
} else {
throw std::invalid_argument("Invalid input command type");
Expand Down Expand Up @@ -640,7 +638,7 @@ void SimplePlanningSimulator::set_input(const Control & cmd, const double acc_by
input << vel, steer;
} else if ( // NOLINT
vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC ||
vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) {
vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) { // NOLINT
input << combined_acc, steer;
} else if ( // NOLINT
vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC_GEARED ||
Expand Down

0 comments on commit 842984f

Please sign in to comment.