2010-10-28 01:59:24 -03:00
|
|
|
/*
|
|
|
|
Example of PID library.
|
|
|
|
2010 Code by Jason Short. DIYDrones.com
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <PID.h> // ArduPilot Mega RC Library
|
|
|
|
#include <APM_RC.h> // ArduPilot RC Library
|
|
|
|
|
|
|
|
long radio_in;
|
|
|
|
long radio_trim;
|
|
|
|
|
2010-12-25 21:17:04 -04:00
|
|
|
PID pid(0x16);
|
|
|
|
|
2010-10-28 01:59:24 -03:00
|
|
|
void setup()
|
|
|
|
{
|
|
|
|
Serial.begin(38400);
|
|
|
|
Serial.println("ArduPilot Mega PID library test");
|
|
|
|
APM_RC.Init(); // APM Radio initialization
|
|
|
|
|
|
|
|
delay(1000);
|
|
|
|
//rc.trim();
|
|
|
|
radio_trim = APM_RC.InputCh(0);
|
|
|
|
|
2010-11-25 21:53:12 -04:00
|
|
|
pid.kP(1);
|
|
|
|
pid.kI(0);
|
|
|
|
pid.kD(0.5);
|
|
|
|
pid.imax(50);
|
2010-10-28 01:59:24 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop()
|
|
|
|
{
|
|
|
|
delay(20);
|
|
|
|
//rc.read_pwm();
|
|
|
|
long error = APM_RC.InputCh(0) - radio_trim;
|
|
|
|
long control = pid.get_pid(error, 20, 1);
|
|
|
|
|
|
|
|
Serial.print("control: ");
|
|
|
|
Serial.println(control,DEC);
|
|
|
|
}
|