AP_Param: #include <AP_Param.h> fixups for libraries & sketches

* I mostly went through with grep and added an #include <AP_Param.h> below
  every #include <AP_Common.h>. Not all of these example sketches might
  strictly need AP_Param.
This commit is contained in:
Pat Hickey 2012-08-20 16:22:44 -07:00 committed by Andrew Tridgell
parent c4dbe8c627
commit 3f1d9d7f69
44 changed files with 156 additions and 52 deletions

View File

@ -79,6 +79,7 @@ version 2.1 of the License, or (at your option) any later version.
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Menu.h>
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <AP_GPS.h> // ArduPilot GPS library

View File

@ -65,6 +65,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Menu.h>
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <AP_GPS.h> // ArduPilot GPS library

View File

@ -28,6 +28,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Menu.h>
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <AP_GPS.h> // ArduPilot GPS library

View File

@ -7,6 +7,7 @@
#define AC_PID_h
#include <AP_Common.h>
#include <AP_Param.h>
#include <math.h> // for fabs()
/// @class AC_PID

View File

@ -8,6 +8,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <APM_RC.h> // ArduPilot RC Library
#include <AC_PID.h> // ArduPilot Mega RC Library

View File

@ -12,6 +12,7 @@
*/
#include <AP_Common.h>
#include <AP_Param.h>
#include <inttypes.h>

View File

@ -7,6 +7,7 @@
#define APM_PI_h
#include <AP_Common.h>
#include <AP_Param.h>
//#include <math.h> // for fabs()
/// @class APM_PI

View File

@ -8,7 +8,7 @@
#ifndef AP_AUTOPILOT_H_
#define AP_AUTOPILOT_H_
#include "../AP_Common/AP_Loop.h"
#include "AP_Loop.h"
/**
* ArduPilotOne namespace to protect variables

View File

@ -16,6 +16,7 @@
#include <AP_GPS.h>
#include <AP_InertialSensor.h>
#include <AP_Baro.h>
#include <AP_Param.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"

View File

@ -17,6 +17,7 @@
#include <AP_AnalogSource.h>
#include <AP_AnalogSource_Arduino.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Compass.h>
#include <AP_Airspeed.h>
#include <AP_Baro.h>

View File

@ -10,6 +10,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_AnalogSource.h>
#include <AP_AnalogSource_Arduino.h>

View File

@ -6,6 +6,7 @@
#include <FastSerial.h>
#include <AP_Math.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <AP_PeriodicProcess.h>
#include <AP_AnalogSource.h>

View File

@ -13,6 +13,7 @@
#include <AP_InertialSensor.h>
#include <AP_Math.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AverageFilter.h>
#include <AP_Buffer.h>

View File

@ -2,6 +2,7 @@
#include <stdint.h>
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <I2C.h>
#include <SPI.h>

View File

@ -38,13 +38,6 @@ typedef struct {
//#include "AP_Vector.h"
//#include "AP_Loop.h"
// default to AP_Param system, unless USE_AP_VAR is defined
#ifdef USE_AP_VAR
#include "AP_Var.h"
#else
#include "AP_Param.h"
#endif
////////////////////////////////////////////////////////////////////////////////
/// @name Warning control
//@{

View File

@ -3,9 +3,10 @@
#define Compass_h
#include <inttypes.h>
#include "../AP_Common/AP_Common.h"
#include "../AP_Math/AP_Math.h"
#include "../AP_Declination/AP_Declination.h" // ArduPilot Mega Declination Helper Library
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
// compass product id
#define AP_COMPASS_TYPE_UNKNOWN 0x00

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Compass.h> // Compass Library
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <I2C.h>

View File

@ -3,6 +3,7 @@
// AVR runtime
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_Declination.h>
#include <Filter.h>

View File

@ -9,6 +9,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_GPS.h>
FastSerialPort0(Serial);

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_GPS.h>
#include <AP_Math.h>

View File

@ -8,6 +8,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_GPS.h>
#include <AP_Math.h>

View File

@ -6,6 +6,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_GPS.h>
FastSerialPort0(Serial);

View File

@ -8,6 +8,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_GPS.h>
#include <AP_Math.h>

View File

@ -12,6 +12,7 @@
#include <AP_InertialSensor.h>
#include <AP_Math.h>
#include <AP_Common.h>
#include <AP_Param.h>
#define APM_HARDWARE_APM1 1
#define APM_HARDWARE_APM2 2

View File

@ -7,6 +7,7 @@
#include <FastSerial.h>
#include <AP_Common.h> // ArduPilot Mega Common Library
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_LeadFilter.h> // GPS Lead filter

View File

@ -10,6 +10,7 @@
#define AP_LIMIT_MODULE_H_
#include <AP_Common.h>
#include <AP_Param.h>
// The module IDs are defined as powers of 2, to make a bit-field
enum moduleid {

View File

@ -13,8 +13,8 @@
#endif
#include <stdint.h>
#include <AP_Param.h>
#include <AP_Limit_Module.h>
#include <AP_Common.h>
// MAVLink messages, trying to pull into library
//#include "../GCS_MAVLink/include/mavlink/v1.0/protocol.h"

View File

@ -6,6 +6,7 @@
// Assorted useful math operations for ArduPilot(Mega)
#include <AP_Common.h>
#include <AP_Param.h>
#include <math.h>
#include <stdint.h>
#include "rotations.h"

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
FastSerialPort(Serial, 0);

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#ifdef DESKTOP_BUILD

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
FastSerialPort(Serial, 0);

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
FastSerialPort(Serial, 0);

View File

@ -12,6 +12,7 @@
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <RC_Channel.h> // RC Channel Library
@ -111,4 +112,4 @@ void print_motor_output()
Serial.printf("\t%d %d",i,motors.motor_out[i]);
}
}
}
}

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <SPI.h> // Arduino SPI library
#include <SPI3.h> // SPI3 library

View File

@ -0,0 +1,52 @@
/*
* Example of PID library.
* 2010 Code by Jason Short. DIYDrones.com
*/
#include <Arduino_Mega_ISR_Registry.h>
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <APM_RC.h> // ArduPilot RC Library
#include <AP_PID.h> // ArduPilot Mega RC Library
long radio_in;
long radio_trim;
Arduino_Mega_ISR_Registry isr_registry;
AP_PID pid;
APM_RC_APM1 APM_RC;
void setup()
{
Serial.begin(115200);
Serial.println("ArduPilot Mega AP_PID library test");
isr_registry.init();
APM_RC.Init(&isr_registry); // APM Radio initialization
delay(1000);
//rc.trim();
radio_trim = APM_RC.InputCh(0);
pid.kP(1);
pid.kI(0);
pid.kD(0.5);
pid.imax(50);
pid.kP(0);
pid.kI(0);
pid.kD(0);
pid.imax(0);
Serial.printf("P %f I %f D %f imax %f\n", pid.kP(), pid.kI(), pid.kD(), pid.imax());
}
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);
}

View File

@ -6,6 +6,7 @@
// includes
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <Filter.h>
#include <I2C.h> // Arduino I2C lib

View File

@ -4,6 +4,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <Filter.h>
#include <DerivativeFilter.h>

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <Filter.h> // Filter library
#include <ModeFilter.h> // ModeFilter class (inherits from Filter class)

View File

@ -5,6 +5,7 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <Filter.h> // Filter library
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)

View File

@ -6,6 +6,7 @@
#ifndef GCS_MAVLink_h
#define GCS_MAVLink_h
#include <AP_Param.h>
#include <BetterStream.h>
// we have separate helpers disabled to make it possible

View File

@ -7,6 +7,7 @@
#define PID_h
#include <AP_Common.h>
#include <AP_Param.h>
#include <math.h> // for fabs()
/// @class PID

View File

@ -6,6 +6,7 @@
#include <FastSerial.h>
#include <avr/pgmspace.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <APM_RC.h> // ArduPilot RC Library
#include <PID.h> // ArduPilot Mega RC Library

View File

@ -7,6 +7,7 @@
#define RC_Channel_h
#include <AP_Common.h>
#include <AP_Param.h>
#include <APM_RC.h>
#define RC_CHANNEL_TYPE_ANGLE 0

View File

@ -7,6 +7,7 @@
#include <FastSerial.h>
#include <AP_Common.h> // ArduPilot Mega Common Library
#include <AP_Param.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <APM_RC.h> // ArduPilot Mega RC Library
@ -145,46 +146,65 @@ print_radio_values()
void
setup_radio()
{
Serial.println("\n\nRadio Setup:");
for (byte i = 0; i < 100; i++) {
delay(20);
read_radio();
}
for (byte i=0; i<8; i++) {
rc[i].radio_min = rc[i].radio_in;
rc[i].radio_max = rc[i].radio_in;
}
rc_1.radio_trim = rc_1.radio_in;
rc_2.radio_trim = rc_2.radio_in;
rc_4.radio_trim = rc_4.radio_in;
// 3 is not trimed
rc_5.radio_trim = 1500;
rc_6.radio_trim = 1500;
rc_7.radio_trim = 1500;
rc_8.radio_trim = 1500;
Serial.println("\nMove all controls to each extreme. Hit Enter to save:");
while(1) {
delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
read_radio();
for (byte i=0; i<8; i++) {
rc[i].update_min_max();
Serial.println("\n\nRadio Setup:");
uint8_t i;
for(i = 0; i < 100;i++){
delay(20);
read_radio();
}
rc_1.radio_min = rc_1.radio_in;
rc_2.radio_min = rc_2.radio_in;
rc_3.radio_min = rc_3.radio_in;
rc_4.radio_min = rc_4.radio_in;
rc_5.radio_min = rc_5.radio_in;
rc_6.radio_min = rc_6.radio_in;
rc_7.radio_min = rc_7.radio_in;
rc_8.radio_min = rc_8.radio_in;
if(Serial.available() > 0) {
//rc_3.radio_max += 250;
Serial.flush();
rc_1.radio_max = rc_1.radio_in;
rc_2.radio_max = rc_2.radio_in;
rc_3.radio_max = rc_3.radio_in;
rc_4.radio_max = rc_4.radio_in;
rc_5.radio_max = rc_5.radio_in;
rc_6.radio_max = rc_6.radio_in;
rc_7.radio_max = rc_7.radio_in;
rc_8.radio_max = rc_8.radio_in;
Serial.println("Radio calibrated, Showing control values:");
break;
}
}
return;
rc_1.radio_trim = rc_1.radio_in;
rc_2.radio_trim = rc_2.radio_in;
rc_4.radio_trim = rc_4.radio_in;
// 3 is not trimed
rc_5.radio_trim = 1500;
rc_6.radio_trim = 1500;
rc_7.radio_trim = 1500;
rc_8.radio_trim = 1500;
Serial.println("\nMove all controls to each extreme. Hit Enter to save:");
while(1){
delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
read_radio();
rc_1.update_min_max();
rc_2.update_min_max();
rc_3.update_min_max();
rc_4.update_min_max();
rc_5.update_min_max();
rc_6.update_min_max();
rc_7.update_min_max();
rc_8.update_min_max();
if(Serial.available() > 0){
//rc_3.radio_max += 250;
Serial.flush();
Serial.println("Radio calibrated, Showing control values:");
break;
}
}
return;
}