uncrustify libraries/PID/examples/pid/pid.pde

This commit is contained in:
uncrustify 2012-08-16 23:22:43 -07:00 committed by Pat Hickey
parent 098bb9c2ea
commit 84816966ec

View File

@ -1,59 +1,59 @@
/* /*
Example of PID library. * Example of PID library.
2010 Code by Jason Short. DIYDrones.com * 2010 Code by Jason Short. DIYDrones.com
*/ */
#include <FastSerial.h> #include <FastSerial.h>
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_Math.h> #include <AP_Math.h>
#include <APM_RC.h> // ArduPilot RC Library #include <APM_RC.h> // ArduPilot RC Library
#include <PID.h> // ArduPilot Mega RC Library #include <PID.h> // ArduPilot Mega RC Library
#include <Arduino_Mega_ISR_Registry.h> #include <Arduino_Mega_ISR_Registry.h>
long radio_in; long radio_in;
long radio_trim; long radio_trim;
Arduino_Mega_ISR_Registry isr_registry; Arduino_Mega_ISR_Registry isr_registry;
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
APM_RC_APM2 APM_RC; APM_RC_APM2 APM_RC;
#else #else
APM_RC_APM1 APM_RC; APM_RC_APM1 APM_RC;
#endif #endif
PID pid; PID pid;
void setup() void setup()
{ {
Serial.begin(38400); Serial.begin(38400);
Serial.println("ArduPilot Mega PID library test"); Serial.println("ArduPilot Mega PID library test");
APM_RC.Init(&isr_registry); // APM Radio initialization APM_RC.Init(&isr_registry); // APM Radio initialization
delay(1000); delay(1000);
//rc.trim(); //rc.trim();
radio_trim = APM_RC.InputCh(0); radio_trim = APM_RC.InputCh(0);
pid.kP(1); pid.kP(1);
pid.kI(0); pid.kI(0);
pid.kD(0.5); pid.kD(0.5);
pid.imax(50); pid.imax(50);
pid.save_gains(); pid.save_gains();
pid.kP(0); pid.kP(0);
pid.kI(0); pid.kI(0);
pid.kD(0); pid.kD(0);
pid.imax(0); pid.imax(0);
pid.load_gains(); pid.load_gains();
Serial.printf("P %f I %f D %f imax %f\n", pid.kP(), pid.kI(), pid.kD(), pid.imax()); Serial.printf("P %f I %f D %f imax %f\n", pid.kP(), pid.kI(), pid.kD(), pid.imax());
} }
void loop() void loop()
{ {
delay(20); delay(20);
//rc.read_pwm(); //rc.read_pwm();
long error = APM_RC.InputCh(0) - radio_trim; long error = APM_RC.InputCh(0) - radio_trim;
long control = pid.get_pid(error, 1); long control = pid.get_pid(error, 1);
Serial.print("control: "); Serial.print("control: ");
Serial.println(control,DEC); Serial.println(control,DEC);
} }