From e321949a5711a0b78e2d55f044e22daf55088a76 Mon Sep 17 00:00:00 2001 From: kosuke55 Date: Wed, 28 Aug 2024 01:22:44 +0900 Subject: [PATCH] add prefix to new change Signed-off-by: kosuke55 --- .../vehicle_model/sim_model_actuation_cmd.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp index 58d43b619c231..069cb9e569580 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp @@ -62,7 +62,8 @@ std::optional AccelMap::getThrottle(const double acc, double vel) const // (throttle, vel, acc) map => (throttle, acc) map by fixing vel for (std::vector accelerations : accel_map) { - interpolated_acc_vec.push_back(interpolation::lerp(vel_indices, accelerations, clamped_vel)); + interpolated_acc_vec.push_back( + autoware::interpolation::lerp(vel_indices, accelerations, clamped_vel)); } // calculate throttle @@ -74,7 +75,7 @@ std::optional AccelMap::getThrottle(const double acc, double vel) const return throttle_indices.back(); } - return interpolation::lerp(interpolated_acc_vec, throttle_indices, acc); + return autoware::interpolation::lerp(interpolated_acc_vec, throttle_indices, acc); } double BrakeMap::getBrake(const double acc, double vel) const @@ -88,7 +89,8 @@ double BrakeMap::getBrake(const double acc, double vel) const // (brake, vel, acc) map => (brake, acc) map by fixing vel for (std::vector accelerations : brake_map) { - interpolated_acc_vec.push_back(interpolation::lerp(vel_indices, accelerations, clamped_vel)); + interpolated_acc_vec.push_back( + autoware::interpolation::lerp(vel_indices, accelerations, clamped_vel)); } // calculate brake @@ -101,7 +103,7 @@ double BrakeMap::getBrake(const double acc, double vel) const } std::reverse(std::begin(interpolated_acc_vec), std::end(interpolated_acc_vec)); - return interpolation::lerp(interpolated_acc_vec, brake_indices, acc); + return autoware::interpolation::lerp(interpolated_acc_vec, brake_indices, acc); } // steer map sim model