diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp index 60845788adcf5..a18571144792a 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp @@ -40,48 +40,6 @@ bool VehicleCmdFilter::setParameterWithValidation(const VehicleCmdFilterParam & param_ = p; return true; } -void VehicleCmdFilter::setSteerLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.steer_lim = v; - setParameterWithValidation(tmp); -} -void VehicleCmdFilter::setSteerRateLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.steer_rate_lim = v; - setParameterWithValidation(tmp); -} -void VehicleCmdFilter::setLonAccLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.lon_acc_lim = v; - setParameterWithValidation(tmp); -} -void VehicleCmdFilter::setLonJerkLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.lon_jerk_lim = v; - setParameterWithValidation(tmp); -} -void VehicleCmdFilter::setLatAccLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.lat_acc_lim = v; - setParameterWithValidation(tmp); -} -void VehicleCmdFilter::setLatJerkLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.lat_jerk_lim = v; - setParameterWithValidation(tmp); -} -void VehicleCmdFilter::setActualSteerDiffLim(const LimitArray & v) -{ - auto tmp = param_; - tmp.actual_steer_diff_lim = v; - setParameterWithValidation(tmp); -} void VehicleCmdFilter::setParam(const VehicleCmdFilterParam & p) { diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp index a4877692b6dac..086d45cf1fc46 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp @@ -48,14 +48,6 @@ class VehicleCmdFilter ~VehicleCmdFilter() = default; void setWheelBase(double v) { param_.wheel_base = v; } - void setVelLim(double v) { param_.vel_lim = v; } - void setSteerLim(const LimitArray & v); - void setSteerRateLim(const LimitArray & v); - void setLonAccLim(const LimitArray & v); - void setLonJerkLim(const LimitArray & v); - void setLatAccLim(const LimitArray & v); - void setLatJerkLim(const LimitArray & v); - void setActualSteerDiffLim(const LimitArray & v); void setCurrentSpeed(double v) { current_speed_ = v; } void setParam(const VehicleCmdFilterParam & p); VehicleCmdFilterParam getParam() const; @@ -75,8 +67,6 @@ class VehicleCmdFilter static IsFilterActivated checkIsActivated( const Control & c1, const Control & c2, const double tol = 1.0e-3); - Control getPrevCmd() const { return prev_cmd_; } - private: VehicleCmdFilterParam param_; Control prev_cmd_;