mirror of https://github.com/ArduPilot/ardupilot
APM_Control: SteerController: add active method
This commit is contained in:
parent
eefda1130c
commit
c6e0ba7360
|
@ -249,3 +249,9 @@ void AP_SteerController::reset_I()
|
||||||
_pid_info.I = 0;
|
_pid_info.I = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Returns true if controller has been run recently
|
||||||
|
bool AP_SteerController::active() const
|
||||||
|
{
|
||||||
|
return (AP_HAL::millis() - _last_t) < 1000;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -50,6 +50,9 @@ public:
|
||||||
_reverse = reverse;
|
_reverse = reverse;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Returns true if controller has been run recently
|
||||||
|
bool active() const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Float _tau;
|
AP_Float _tau;
|
||||||
AP_Float _K_FF;
|
AP_Float _K_FF;
|
||||||
|
|
Loading…
Reference in New Issue