mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
PID: Add a full reset method
This commit is contained in:
parent
615f6dfadb
commit
f8ac4efb1d
@ -119,6 +119,11 @@ PID::reset_I()
|
|||||||
_pid_info.I = 0;
|
_pid_info.I = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PID::reset() {
|
||||||
|
memset(&_pid_info, 0, sizeof(_pid_info));
|
||||||
|
reset_I();
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
PID::load_gains()
|
PID::load_gains()
|
||||||
{
|
{
|
||||||
|
@ -39,6 +39,10 @@ public:
|
|||||||
///
|
///
|
||||||
float get_pid(float error, float scaler = 1.0);
|
float get_pid(float error, float scaler = 1.0);
|
||||||
|
|
||||||
|
/// Reset the whole PID state
|
||||||
|
//
|
||||||
|
void reset();
|
||||||
|
|
||||||
/// Reset the PID integrator
|
/// Reset the PID integrator
|
||||||
///
|
///
|
||||||
void reset_I();
|
void reset_I();
|
||||||
|
Loading…
Reference in New Issue
Block a user