Browse Source

PID: fix compile warnings re float constants

mission-4.1.18
Tom Pittenger 10 years ago committed by Randy Mackay
parent
commit
f3d13656ba
  1. 6
      libraries/PID/PID.h
  2. 2
      libraries/PID/examples/pid/pid.pde

6
libraries/PID/PID.h

@ -16,9 +16,9 @@ @@ -16,9 +16,9 @@
class PID {
public:
PID(const float & initial_p = 0.0,
const float & initial_i = 0.0,
const float & initial_d = 0.0,
PID(const float & initial_p = 0.0f,
const float & initial_i = 0.0f,
const float & initial_d = 0.0f,
const int16_t & initial_imax = 0)
{
AP_Param::setup_object_defaults(this, var_info);

2
libraries/PID/examples/pid/pid.pde

@ -32,7 +32,7 @@ void setup() @@ -32,7 +32,7 @@ void setup()
pid.kP(1);
pid.kI(0);
pid.kD(0.5);
pid.kD(0.5f);
pid.imax(50);
pid.save_gains();
pid.kP(0);

Loading…
Cancel
Save