mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 02:58:31 -04:00
AR_AttitudeControl: disable limits when _ACCEL_MAX is zero
This commit is contained in:
parent
d8a7618e15
commit
b614ca9b75
@ -161,7 +161,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
||||
|
||||
// @Param: _DECEL_MAX
|
||||
// @DisplayName: Speed control deceleration maximum in m/s/s
|
||||
// @Description: Speed control and deceleration maximum in m/s/s. 0 to disable deceleration limiting
|
||||
// @Description: Speed control and deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
|
||||
// @Range: 0.0 10.0
|
||||
// @Increment: 0.1
|
||||
// @Units: m/s/s
|
||||
@ -495,6 +495,13 @@ float AR_AttitudeControl::get_desired_speed() const
|
||||
// get acceleration limited desired speed
|
||||
float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, float dt) const
|
||||
{
|
||||
// return input value if no recent calls to speed controller
|
||||
// apply no limiting when ATC_ACCEL_MAX is set to zero
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
if ((_speed_last_ms == 0) || ((now - _speed_last_ms) > AR_ATTCONTROL_TIMEOUT_MS) || !is_positive(_throttle_accel_max)) {
|
||||
return desired_speed;
|
||||
}
|
||||
|
||||
// sanity check dt
|
||||
dt = constrain_float(dt, 0.0f, 1.0f);
|
||||
|
||||
|
@ -120,7 +120,7 @@ private:
|
||||
AC_PID _steer_rate_pid; // steering rate controller
|
||||
AC_PID _throttle_speed_pid; // throttle speed controller
|
||||
AP_Float _throttle_accel_max; // speed/throttle control acceleration (and deceleration) maximum in m/s/s. 0 to disable limits
|
||||
AP_Float _throttle_decel_max; // speed/throttle control deceleration maximum in m/s/s. 0 to disable limits
|
||||
AP_Float _throttle_decel_max; // speed/throttle control deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
|
||||
AP_Int8 _brake_enable; // speed control brake enable/disable. if set to 1 a reversed output to the motors to slow the vehicle.
|
||||
AP_Float _stop_speed; // speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
|
||||
AP_Float _steer_accel_max; // steering angle acceleration max in deg/s/s
|
||||
|
Loading…
Reference in New Issue
Block a user