mirror of https://github.com/ArduPilot/ardupilot
AR_AttitudeControl: add get_stopping_distance
This commit is contained in:
parent
172f9b6a07
commit
784c60f58f
|
@ -461,3 +461,18 @@ float AR_AttitudeControl::get_desired_speed() const
|
|||
}
|
||||
return _desired_speed;
|
||||
}
|
||||
|
||||
// get minimum stopping distance (in meters) given a speed (in m/s)
|
||||
float AR_AttitudeControl::get_stopping_distance(float speed)
|
||||
{
|
||||
// get maximum vehicle deceleration
|
||||
const float accel_max = get_accel_max();
|
||||
|
||||
// avoid divide by zero
|
||||
if ((accel_max <= 0.0f) || is_zero(speed)) {
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
// assume linear deceleration
|
||||
return 0.5f * sq(speed) / accel_max;
|
||||
}
|
||||
|
|
|
@ -92,6 +92,9 @@ public:
|
|||
// get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
|
||||
float get_desired_speed() const;
|
||||
|
||||
// get minimum stopping distance (in meters) given a speed (in m/s)
|
||||
float get_stopping_distance(float speed);
|
||||
|
||||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
|
Loading…
Reference in New Issue