ardupilot/libraries/PID/examples/pid/pid.cpp

60 lines
1.1 KiB
C++
Raw Normal View History

/*
* Example of PID library.
* 2010 Code by Jason Short. DIYDrones.com
*/
2012-11-30 23:35:01 -04:00
#include <AP_HAL.h>
#include <AP_Common.h>
2012-11-30 23:35:01 -04:00
#include <AP_Progmem.h>
#include <AP_Param.h>
2014-08-13 09:12:24 -03:00
#include <StorageManager.h>
#include <AP_Math.h>
#include <PID.h> // ArduPilot Mega RC Library
2012-11-30 23:35:01 -04:00
#include <AP_HAL_AVR.h>
2015-05-04 03:17:51 -03:00
#include <AP_HAL_SITL.h>
2012-12-18 20:04:04 -04:00
#include <AP_HAL_Empty.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
2012-11-30 23:35:01 -04:00
long radio_in;
long radio_trim;
PID pid;
void setup()
{
2012-11-30 23:35:01 -04:00
hal.console->println("ArduPilot Mega PID library test");
2012-11-30 23:35:01 -04:00
hal.scheduler->delay(1000);
//rc.trim();
2012-11-30 23:35:01 -04:00
radio_trim = hal.rcin->read(0);
pid.kP(1);
pid.kI(0);
pid.kD(0.5f);
pid.imax(50);
pid.save_gains();
pid.kP(0);
pid.kI(0);
pid.kD(0);
pid.imax(0);
pid.load_gains();
2012-11-30 23:35:01 -04:00
hal.console->printf_P(
PSTR("P %f I %f D %f imax %f\n"),
pid.kP(), pid.kI(), pid.kD(), pid.imax());
}
void loop()
{
2012-11-30 23:35:01 -04:00
hal.scheduler->delay(20);
//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-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-11-30 23:35:01 -04:00
AP_HAL_MAIN();