mirror of https://github.com/ArduPilot/ardupilot
AP_PID, AP_RC_Channel, FastSerial - small changes to make example sketches compile again
This commit is contained in:
parent
2e1e34fb9c
commit
8bcc567406
|
@ -3,21 +3,26 @@
|
||||||
2010 Code by Jason Short. DIYDrones.com
|
2010 Code by Jason Short. DIYDrones.com
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <Arduino_Mega_ISR_Registry.h>
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <APM_RC.h> // ArduPilot RC Library
|
#include <APM_RC.h> // ArduPilot RC Library
|
||||||
#include <PID.h> // ArduPilot Mega RC Library
|
#include <AP_PID.h> // ArduPilot Mega RC Library
|
||||||
|
|
||||||
long radio_in;
|
long radio_in;
|
||||||
long radio_trim;
|
long radio_trim;
|
||||||
|
|
||||||
PID pid();
|
Arduino_Mega_ISR_Registry isr_registry;
|
||||||
|
AP_PID pid;
|
||||||
|
APM_RC_APM1 APM_RC;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
Serial.begin(38400);
|
Serial.begin(115200);
|
||||||
Serial.println("ArduPilot Mega PID library test");
|
Serial.println("ArduPilot Mega AP_PID library test");
|
||||||
APM_RC.Init(); // APM Radio initialization
|
|
||||||
|
isr_registry.init();
|
||||||
|
APM_RC.Init(&isr_registry); // APM Radio initialization
|
||||||
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
//rc.trim();
|
//rc.trim();
|
||||||
|
@ -27,12 +32,10 @@ void setup()
|
||||||
pid.kI(0);
|
pid.kI(0);
|
||||||
pid.kD(0.5);
|
pid.kD(0.5);
|
||||||
pid.imax(50);
|
pid.imax(50);
|
||||||
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();
|
|
||||||
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());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -88,11 +88,14 @@ AP_RC_Channel::set_pwm(int pwm)
|
||||||
control_in = pwm_to_angle();
|
control_in = pwm_to_angle();
|
||||||
control_in = (abs(control_in) < dead_zone) ? 0 : control_in;
|
control_in = (abs(control_in) < dead_zone) ? 0 : control_in;
|
||||||
|
|
||||||
|
/*
|
||||||
|
// coming soon ??
|
||||||
if(expo) {
|
if(expo) {
|
||||||
long temp = control_in;
|
long temp = control_in;
|
||||||
temp = (temp * temp) / (long)_high;
|
temp = (temp * temp) / (long)_high;
|
||||||
control_in = (int)((control_in >= 0) ? temp : -temp);
|
control_in = (int)((control_in >= 0) ? temp : -temp);
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,6 @@ AP_RC rc;
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
//Serial.begin(38400);
|
|
||||||
|
|
||||||
Serial.println("ArduPilot RC Channel test");
|
Serial.println("ArduPilot RC Channel test");
|
||||||
rc.init(); // APM Radio initialization
|
rc.init(); // APM Radio initialization
|
||||||
|
|
|
@ -17,8 +17,9 @@
|
||||||
#undef PROGMEM
|
#undef PROGMEM
|
||||||
#define PROGMEM __attribute__(( section(".progmem.data") ))
|
#define PROGMEM __attribute__(( section(".progmem.data") ))
|
||||||
|
|
||||||
#undef PSTR
|
# undef PSTR
|
||||||
#define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];}))
|
# define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); \
|
||||||
|
(prog_char_t *)&__c[0];}))
|
||||||
|
|
||||||
//
|
//
|
||||||
// Create a FastSerial driver that looks just like the stock Arduino
|
// Create a FastSerial driver that looks just like the stock Arduino
|
||||||
|
@ -38,7 +39,7 @@ void setup(void)
|
||||||
//
|
//
|
||||||
// Set the speed for our replacement serial port.
|
// Set the speed for our replacement serial port.
|
||||||
//
|
//
|
||||||
Serial.begin(38400);
|
Serial.begin(115200);
|
||||||
|
|
||||||
//
|
//
|
||||||
// Test printing things
|
// Test printing things
|
||||||
|
|
Loading…
Reference in New Issue