Browse Source

AR_AttitudeControl: add get_stopping_distance

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
d139f0e28e
  1. 15
      libraries/APM_Control/AR_AttitudeControl.cpp
  2. 3
      libraries/APM_Control/AR_AttitudeControl.h

15
libraries/APM_Control/AR_AttitudeControl.cpp

@ -461,3 +461,18 @@ float AR_AttitudeControl::get_desired_speed() const @@ -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;
}

3
libraries/APM_Control/AR_AttitudeControl.h

@ -92,6 +92,9 @@ public: @@ -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…
Cancel
Save