2012-08-17 03:22:43 -03:00
|
|
|
/*
|
|
|
|
* Example of PID library.
|
|
|
|
* 2010 Code by Jason Short. DIYDrones.com
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <PID/PID.h> // ArduPilot Mega RC Library
|
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2012-08-17 03:22:43 -03:00
|
|
|
|
2012-11-30 23:35:01 -04:00
|
|
|
long radio_in;
|
|
|
|
long radio_trim;
|
|
|
|
|
2012-08-17 03:22:43 -03:00
|
|
|
PID pid;
|
|
|
|
|
|
|
|
void setup()
|
|
|
|
{
|
2012-11-30 23:35:01 -04:00
|
|
|
hal.console->println("ArduPilot Mega PID library test");
|
2012-08-17 03:22:43 -03:00
|
|
|
|
2012-11-30 23:35:01 -04:00
|
|
|
hal.scheduler->delay(1000);
|
2012-08-17 03:22:43 -03:00
|
|
|
//rc.trim();
|
2012-11-30 23:35:01 -04:00
|
|
|
radio_trim = hal.rcin->read(0);
|
2012-08-17 03:22:43 -03:00
|
|
|
|
|
|
|
pid.kP(1);
|
|
|
|
pid.kI(0);
|
2015-04-24 02:01:39 -03:00
|
|
|
pid.kD(0.5f);
|
2012-08-17 03:22:43 -03:00
|
|
|
pid.imax(50);
|
|
|
|
pid.save_gains();
|
|
|
|
pid.kP(0);
|
|
|
|
pid.kI(0);
|
|
|
|
pid.kD(0);
|
|
|
|
pid.imax(0);
|
|
|
|
pid.load_gains();
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf(
|
2016-02-18 00:32:09 -04:00
|
|
|
"P %f I %f D %f imax %d\n",
|
2012-11-30 23:35:01 -04:00
|
|
|
pid.kP(), pid.kI(), pid.kD(), pid.imax());
|
2012-08-17 03:22:43 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop()
|
|
|
|
{
|
2012-11-30 23:35:01 -04:00
|
|
|
hal.scheduler->delay(20);
|
2012-08-17 03:22:43 -03:00
|
|
|
//rc.read_pwm();
|
2012-11-30 23:35:01 -04:00
|
|
|
long error = hal.rcin->read(0) - radio_trim;
|
|
|
|
long control= pid.get_pid(error, 1);
|
2012-08-17 03:22:43 -03:00
|
|
|
|
2012-11-30 23:35:01 -04:00
|
|
|
hal.console->print("control: ");
|
2013-09-23 22:57:21 -03:00
|
|
|
hal.console->println(control,BASE_DEC);
|
2012-08-17 03:22:43 -03:00
|
|
|
}
|
2012-11-30 23:35:01 -04:00
|
|
|
|
|
|
|
AP_HAL_MAIN();
|