mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_SpdHgt_Control: Remove hgt_afe from update_50hz()
This commit is contained in:
parent
ef348473eb
commit
475e731e34
@ -20,7 +20,7 @@ public:
|
|||||||
// Update the internal state of the height and height rate estimator
|
// Update the internal state of the height and height rate estimator
|
||||||
// Update of the inertial speed rate estimate internal state
|
// Update of the inertial speed rate estimate internal state
|
||||||
// Should be called at 50Hz or faster
|
// Should be called at 50Hz or faster
|
||||||
virtual void update_50hz(float height_above_field) = 0;
|
virtual void update_50hz(void) = 0;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
stages of flight so the altitude controller can choose to
|
stages of flight so the altitude controller can choose to
|
||||||
|
Loading…
Reference in New Issue
Block a user