mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
Don't zero fields in the ctor that can be zeroed by reset_I; the code gets replicated for every static instance of the class, which is obscene.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@941 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
0f9ac71e6a
commit
e699812af4
@ -20,10 +20,7 @@ public:
|
||||
///
|
||||
PID(uint16_t address = 0) :
|
||||
_gain_array(0),
|
||||
_address(address),
|
||||
_integrator(0),
|
||||
_last_error(0),
|
||||
_last_derivative(0)
|
||||
_address(address)
|
||||
{}
|
||||
|
||||
/// Constructor
|
||||
@ -34,10 +31,7 @@ public:
|
||||
///
|
||||
PID(float *gain_array) :
|
||||
_gain_array(gain_array),
|
||||
_address(0),
|
||||
_integrator(0),
|
||||
_last_error(0),
|
||||
_last_derivative(0)
|
||||
_address(0)
|
||||
{}
|
||||
|
||||
/// Iterate the PID, return the new control value
|
||||
|
Loading…
Reference in New Issue
Block a user