AR_AttitudeControl: const get_decel_max and get_stopping_distance

This commit is contained in:
Randy Mackay 2018-05-28 15:22:21 +09:00
parent 3ecc0ea6c8
commit 3b71d0360a
2 changed files with 4 additions and 4 deletions

View File

@ -462,7 +462,7 @@ bool AR_AttitudeControl::get_forward_speed(float &speed) const
return true; return true;
} }
float AR_AttitudeControl::get_decel_max() float AR_AttitudeControl::get_decel_max() const
{ {
if (is_positive(_throttle_decel_max)) { if (is_positive(_throttle_decel_max)) {
return _throttle_decel_max; return _throttle_decel_max;
@ -507,7 +507,7 @@ float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, f
} }
// get minimum stopping distance (in meters) given a speed (in m/s) // get minimum stopping distance (in meters) given a speed (in m/s)
float AR_AttitudeControl::get_stopping_distance(float speed) float AR_AttitudeControl::get_stopping_distance(float speed) const
{ {
// get maximum vehicle deceleration // get maximum vehicle deceleration
const float accel_max = get_accel_max(); const float accel_max = get_accel_max();

View File

@ -93,7 +93,7 @@ public:
float get_accel_max() const { return MAX(_throttle_accel_max, 0.0f); } float get_accel_max() const { return MAX(_throttle_accel_max, 0.0f); }
// get throttle/speed controller maximum deceleration // get throttle/speed controller maximum deceleration
float get_decel_max(); float get_decel_max() const;
// get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only // get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
float get_desired_speed() const; float get_desired_speed() const;
@ -102,7 +102,7 @@ public:
float get_desired_speed_accel_limited(float desired_speed, float dt) const; float get_desired_speed_accel_limited(float desired_speed, float dt) const;
// get minimum stopping distance (in meters) given a speed (in m/s) // get minimum stopping distance (in meters) given a speed (in m/s)
float get_stopping_distance(float speed); float get_stopping_distance(float speed) const;
// parameter var table // parameter var table
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];