mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
PID: change to float input/output
this makes the PID library a bit more flexible for smaller range numbers. Note that this library is used on ArduPlane and Rover, not Copter
This commit is contained in:
parent
6cf4d11e33
commit
fe964fcda0
@ -19,7 +19,7 @@ const AP_Param::GroupInfo PID::var_info[] PROGMEM = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
int32_t PID::get_pid(int32_t error, float scaler)
|
||||
float PID::get_pid(float error, float scaler)
|
||||
{
|
||||
uint32_t tnow = hal.scheduler->millis();
|
||||
uint32_t dt = tnow - _last_t;
|
||||
|
@ -36,15 +36,11 @@ public:
|
||||
/// Positive error produces positive output.
|
||||
///
|
||||
/// @param error The measured error value
|
||||
/// @param dt The time delta in milliseconds (note
|
||||
/// that update interval cannot be more
|
||||
/// than 65.535 seconds due to limited range
|
||||
/// of the data type).
|
||||
/// @param scaler An arbitrary scale factor
|
||||
///
|
||||
/// @returns The updated control output.
|
||||
///
|
||||
int32_t get_pid(int32_t error, float scaler = 1.0);
|
||||
float get_pid(float error, float scaler = 1.0);
|
||||
|
||||
/// Reset the PID integrator
|
||||
///
|
||||
@ -108,11 +104,11 @@ private:
|
||||
AP_Int16 _imax;
|
||||
|
||||
float _integrator;///< integrator value
|
||||
int32_t _last_error;///< last error for derivative
|
||||
float _last_error;///< last error for derivative
|
||||
float _last_derivative;///< last derivative for low-pass filter
|
||||
uint32_t _last_t;///< last time get_pid() was called in millis
|
||||
|
||||
int32_t _get_pid(int32_t error, uint16_t dt, float scaler);
|
||||
float _get_pid(float error, uint16_t dt, float scaler);
|
||||
|
||||
/// Low pass filter cut frequency for derivative calculation.
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user