AC_PID: minor format fixes

This commit is contained in:
Leonard Hall 2021-05-12 12:51:35 +09:00 committed by Andrew Tridgell
parent c323ee4f56
commit eb07bfee2b
3 changed files with 3 additions and 3 deletions

View File

@ -84,7 +84,7 @@ AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, floa
void AC_HELI_PID::update_leaky_i(float leak_rate)
{
if(!is_zero(_ki) && !is_zero(_dt)){
if (!is_zero(_ki) && !is_zero(_dt)){
// integrator does not leak down below Leak Min
if (_integrator > _leak_min){

View File

@ -69,7 +69,7 @@ public:
// integrator setting functions
void set_integrator(const Vector2f& target, const Vector2f& measurement, const Vector2f& i);
void set_integrator(const Vector2f& error, const Vector2f& i);
void set_integrator(const Vector3f& i) { set_integrator(Vector2f(i.x, i.y)); }
void set_integrator(const Vector3f& i) { set_integrator(Vector2f{i.x, i.y}); }
void set_integrator(const Vector2f& i);
const AP_Logger::PID_Info& get_pid_info_x(void) const { return _pid_info_x; }

View File

@ -26,7 +26,7 @@ public:
// input is filtered before the PI controllers are run
// this should be called before any other calls to get_p, get_i or get_d
void set_input(const Vector2f &input);
void set_input(const Vector3f &input) { set_input(Vector2f(input.x, input.y)); }
void set_input(const Vector3f &input) { set_input(Vector2f{input.x, input.y}); }
// get_pi - get results from pid controller
Vector2f get_pi();