mirror of https://github.com/ArduPilot/ardupilot
import Tools directory
This commit is contained in:
parent
e0dc1271d6
commit
0d5ea17f63
|
@ -0,0 +1,72 @@
|
|||
#include <avr/io.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
/*
|
||||
ArduPilotMega radio test tool
|
||||
Authors: Doug Weibel, Jose Julio
|
||||
|
||||
*/
|
||||
|
||||
|
||||
// GENERAL VARIABLE DECLARATIONS
|
||||
// --------------------------------------------
|
||||
|
||||
|
||||
/* Radio values
|
||||
Channel assignments
|
||||
1 Ailerons (rudder if no ailerons)
|
||||
2 Elevator
|
||||
3 Throttle
|
||||
4 Rudder (if we have ailerons)
|
||||
5 TBD
|
||||
6 TBD
|
||||
7 TBD
|
||||
8 Mode
|
||||
*/
|
||||
int radio_in[8]; // current values from the transmitter - microseconds
|
||||
float servo_out[] = {0,0,0,0,0,0,0};
|
||||
unsigned long fast_loopTimer = 0; // current values to the servos - -45 to 45 degrees, except [3] is 0 to 100
|
||||
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
// -----------------------------------------------------------------
|
||||
if (millis()-fast_loopTimer > 199) {
|
||||
fast_loopTimer = millis();
|
||||
|
||||
read_radio();
|
||||
|
||||
Serial.print("ch1: ");
|
||||
Serial.print(radio_in[0]);
|
||||
Serial.print(" ch2: ");
|
||||
Serial.print(radio_in[1]);
|
||||
Serial.print(" ch3: ");
|
||||
Serial.print(radio_in[2]);
|
||||
Serial.print(" ch4: ");
|
||||
Serial.print(radio_in[3]);
|
||||
Serial.print(" ch5: ");
|
||||
Serial.print(radio_in[4]);
|
||||
Serial.print(" ch6: ");
|
||||
Serial.print(radio_in[5]);
|
||||
Serial.print(" ch7: ");
|
||||
Serial.print(radio_in[6]);
|
||||
Serial.print(" ch8: ");
|
||||
Serial.println(radio_in[7]);
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void read_radio()
|
||||
{
|
||||
|
||||
for (int y=0;y<8;y++) radio_in[y] = APM_RC.InputCh(y);
|
||||
|
||||
}
|
|
@ -0,0 +1,100 @@
|
|||
//Realeased under really Creative Commons!
|
||||
//This just a basic demo code...
|
||||
//Reads and pulses the 8 channels...
|
||||
//By Jordi Munoz
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
volatile unsigned int Start_Pulse =0;
|
||||
volatile unsigned int Stop_Pulse =0;
|
||||
volatile unsigned int Pulse_Width =0;
|
||||
|
||||
volatile int Test=0;
|
||||
volatile int Test2=0;
|
||||
volatile int Temp=0;
|
||||
volatile int Counter=0;
|
||||
volatile byte PPM_Counter=0;
|
||||
volatile int PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400};
|
||||
int All_PWM=1500;
|
||||
|
||||
long timer=0;
|
||||
long timer2=0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Init_PWM1(); //OUT2&3
|
||||
Init_PWM3(); //OUT6&7
|
||||
Init_PWM5(); //OUT0&1
|
||||
Init_PPM_PWM4(); //OUT4&5
|
||||
Serial.begin(57600);
|
||||
|
||||
}
|
||||
void loop()
|
||||
{
|
||||
|
||||
//Switch low, forward the PPM
|
||||
if(InputCh(5) <= 1250) //Reading channel 5 to change mode
|
||||
{
|
||||
OutputCh(0, InputCh(0));
|
||||
OutputCh(1, InputCh(1));
|
||||
OutputCh(2, InputCh(2));
|
||||
OutputCh(3, InputCh(3));
|
||||
OutputCh(4, InputCh(4));
|
||||
OutputCh(5, InputCh(5));
|
||||
OutputCh(6, InputCh(6));
|
||||
OutputCh(7, InputCh(7));
|
||||
}
|
||||
else
|
||||
{
|
||||
//Switch High, Move servos
|
||||
if(InputCh(5) >= 1750)
|
||||
{
|
||||
if((millis()- timer2) >= 20)
|
||||
{
|
||||
timer2=millis();
|
||||
if(All_PWM >2100)
|
||||
All_PWM=900;
|
||||
else
|
||||
All_PWM+=20;
|
||||
}
|
||||
}
|
||||
//Switch in the midle, center all servos
|
||||
else
|
||||
{
|
||||
All_PWM=1500;
|
||||
}
|
||||
|
||||
OutputCh(0, All_PWM);
|
||||
OutputCh(1, All_PWM);
|
||||
OutputCh(2, All_PWM);
|
||||
OutputCh(3, All_PWM);
|
||||
OutputCh(4, All_PWM);
|
||||
OutputCh(5, All_PWM);
|
||||
OutputCh(6, All_PWM);
|
||||
OutputCh(7, All_PWM);
|
||||
}
|
||||
|
||||
//Printing all values.
|
||||
if((millis()- timer) >= 250)
|
||||
{
|
||||
timer=millis();
|
||||
Serial.print("Ch0:");
|
||||
Serial.print(InputCh(0));
|
||||
Serial.print(" Ch1:");
|
||||
Serial.print(InputCh(1));
|
||||
Serial.print(" Ch2:");
|
||||
Serial.print(InputCh(2));
|
||||
Serial.print(" Ch3:");
|
||||
Serial.print(InputCh(3));
|
||||
Serial.print(" Ch4:");
|
||||
Serial.print(InputCh(4));
|
||||
Serial.print(" Ch5:");
|
||||
Serial.print(InputCh(5));
|
||||
Serial.print(" Ch6:");
|
||||
Serial.print(InputCh(6));
|
||||
Serial.print(" Ch7:");
|
||||
Serial.println(InputCh(7));
|
||||
}
|
||||
delay(20);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,124 @@
|
|||
|
||||
void OutputCh(byte ch, int pwm)
|
||||
{
|
||||
pwm=constrain(pwm,900,2100);
|
||||
pwm*=2;
|
||||
|
||||
switch(ch)
|
||||
{
|
||||
case 0: OCR5B=pwm; break; //ch0
|
||||
case 1: OCR5C=pwm; break; //ch1
|
||||
case 2: OCR1B=pwm; break; //ch2
|
||||
case 3: OCR1C=pwm; break; //ch3
|
||||
case 4: OCR4C=pwm; break; //ch4
|
||||
case 5: OCR4B=pwm; break; //ch5
|
||||
case 6: OCR3C=pwm; break; //ch6
|
||||
case 7: OCR3B=pwm; break; //ch7
|
||||
case 8: OCR5A=pwm; break; //ch8, PL3
|
||||
case 9: OCR1A=pwm; break; //ch9, PB5
|
||||
case 10: OCR3A=pwm; break; //ch10, PE3
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int InputCh(byte ch)
|
||||
{
|
||||
return (PWM_RAW[ch]+600)/2;
|
||||
}
|
||||
|
||||
void Init_PWM1(void)
|
||||
{
|
||||
pinMode(11,OUTPUT);
|
||||
pinMode(12,OUTPUT);
|
||||
pinMode(13,OUTPUT);
|
||||
|
||||
//Remember the registers not declared here remains zero by default...
|
||||
TCCR1A =((1<<WGM11)|(1<<COM1A1)|(1<<COM1B1)|(1<<COM1C1)); //Please read page 131 of DataSheet, we are changing the registers settings of WGM11,COM1B1,COM1A1 to 1 thats all...
|
||||
TCCR1B = (1<<WGM13)|(1<<WGM12)|(1<<CS11); //Prescaler set to 8, that give us a resolution of 2us, read page 134 of data sheet
|
||||
OCR1A = 3000; //PB5, none
|
||||
OCR1B = 3000; //PB6, OUT2
|
||||
OCR1C = 3000; //PB7 OUT3
|
||||
ICR1 = 40000; //50hz freq...Datasheet says (system_freq/prescaler)/target frequency. So (16000000hz/8)/50hz=40000,
|
||||
}
|
||||
|
||||
void Init_PWM3(void)
|
||||
{
|
||||
pinMode(2,OUTPUT);
|
||||
pinMode(3,OUTPUT);
|
||||
pinMode(4,OUTPUT);
|
||||
|
||||
//Remember the registers not declared here remains zero by default...
|
||||
TCCR3A =((1<<WGM31)|(1<<COM3A1)|(1<<COM3B1)|(1<<COM3C1)); //Please read page 131 of DataSheet, we are changing the registers settings of WGM11,COM1B1,COM1A1 to 1 thats all...
|
||||
TCCR3B = (1<<WGM33)|(1<<WGM32)|(1<<CS31); //Prescaler set to 8, that give us a resolution of 2us, read page 134 of data sheet
|
||||
OCR3A = 3000; //PE3, NONE
|
||||
OCR3B = 3000; //PE4, OUT7
|
||||
OCR3C = 3000; //PE5, OUT6
|
||||
ICR3 = 40000; //50hz freq...Datasheet says (system_freq/prescaler)/target frequency. So (16000000hz/8)/50hz=40000,
|
||||
}
|
||||
|
||||
void Init_PWM5(void)
|
||||
{
|
||||
pinMode(44,OUTPUT);
|
||||
pinMode(45,OUTPUT);
|
||||
pinMode(46,OUTPUT);
|
||||
|
||||
TCCR5A =((1<<WGM51)|(1<<COM5A1)|(1<<COM5B1)|(1<<COM5C1));
|
||||
TCCR5B = (1<<WGM53)|(1<<WGM52)|(1<<CS51); //Prescaler set to 8
|
||||
OCR5A = 3000; //PL3,
|
||||
OCR5B = 3000; //PL4, OUT0
|
||||
OCR5C = 3000; //PL5 OUT1
|
||||
ICR5 = 40000;
|
||||
//ICR5 = 43910; //So (16000000hz/8)/50hz=40000,
|
||||
}
|
||||
|
||||
/*Note that timer4 is configured to used the Input capture for PPM decoding and to pulse two servos
|
||||
OCR4A is used as the top counter*/
|
||||
void Init_PPM_PWM4(void)
|
||||
{
|
||||
pinMode(49, INPUT);
|
||||
pinMode(7,OUTPUT);
|
||||
pinMode(8,OUTPUT);
|
||||
//Remember the registers not declared here remains zero by default...
|
||||
TCCR4A =((1<<WGM40)|(1<<WGM41)|(1<<COM4C1)|(1<<COM4B1)|(1<<COM4A1));
|
||||
TCCR4B = ((1<<WGM43)|(1<<WGM42)|(1<<CS41)|(1<<ICES4)); //Prescaler set to 8, that give us a resolution of 2us, read page 134 of data sheet
|
||||
OCR4A = 40000; ///50hz freq...Datasheet says (system_freq/prescaler)/target frequency. So (16000000hz/8)/50hz=40000,
|
||||
//must be 50hz because is the servo standard (every 20 ms, and 1hz = 1sec) 1000ms/20ms=50hz, elementary school stuff...
|
||||
OCR4B = 3000; //PH4, OUT5
|
||||
OCR4C = 3000; //PH5, OUT4
|
||||
|
||||
TIMSK4 |= (1<<ICIE4); //Timer interrupt mask
|
||||
sei();
|
||||
|
||||
}
|
||||
/****************************************************
|
||||
Interrupt Vector
|
||||
****************************************************/
|
||||
ISR(TIMER4_CAPT_vect)//interrupt.
|
||||
{
|
||||
if(((1<<ICES4)&TCCR4B) >= 0x01)
|
||||
{
|
||||
if(Start_Pulse>Stop_Pulse) //Checking if the Stop Pulse overflow the register, if yes i normalize it.
|
||||
{
|
||||
Stop_Pulse+=40000; //Nomarlizing the stop pulse.
|
||||
}
|
||||
Pulse_Width=Stop_Pulse-Start_Pulse; //Calculating pulse
|
||||
if(Pulse_Width>5000) //Verify if this is the sync pulse
|
||||
{
|
||||
PPM_Counter=0; //If yes restart the counter
|
||||
}
|
||||
else
|
||||
{
|
||||
PWM_RAW[PPM_Counter]=Pulse_Width; //Saving pulse.
|
||||
PPM_Counter++;
|
||||
}
|
||||
Start_Pulse=ICR4;
|
||||
TCCR4B &=(~(1<<ICES4)); //Changing edge detector.
|
||||
}
|
||||
else
|
||||
{
|
||||
Stop_Pulse=ICR4; //Capturing time stop of the drop edge
|
||||
TCCR4B |=(1<<ICES4); //Changing edge detector.
|
||||
//TCCR4B &=(~(1<<ICES4));
|
||||
}
|
||||
//Counter++;
|
||||
}
|
Binary file not shown.
|
@ -0,0 +1,925 @@
|
|||
//
|
||||
// Example and reference ArduPilot Mega configuration file
|
||||
// =======================================================
|
||||
//
|
||||
// This file contains documentation and examples for configuration options
|
||||
// supported by the ArduPilot Mega software.
|
||||
//
|
||||
// Most of these options are just that - optional. You should create
|
||||
// the APM_Config.h file and use this file as a reference for options
|
||||
// that you want to change. Don't copy this file directly; the options
|
||||
// described here and their default values may change over time.
|
||||
//
|
||||
// Each item is marked with a keyword describing when you should set it:
|
||||
//
|
||||
// REQUIRED
|
||||
// You must configure this in your APM_Config.h file. The
|
||||
// software will not compile if the option is not set.
|
||||
//
|
||||
// OPTIONAL
|
||||
// The option has a sensible default (which will be described
|
||||
// here), but you may wish to override it.
|
||||
//
|
||||
// EXPERIMENTAL
|
||||
// You should configure this option unless you are prepared
|
||||
// to deal with potential problems. It may relate to a feature
|
||||
// still in development, or which is not yet adequately tested.
|
||||
//
|
||||
// DEBUG
|
||||
// The option should only be set if you are debugging the
|
||||
// software, or if you are gathering information for a bug
|
||||
// report.
|
||||
//
|
||||
// NOTE:
|
||||
// Many of these settings are considered 'factory defaults', and the
|
||||
// live value is stored and managed in the ArduPilot Mega EEPROM.
|
||||
// Use the setup 'factoryreset' command after changing options in
|
||||
// your APM_Config.h file.
|
||||
//
|
||||
// Units
|
||||
// -----
|
||||
//
|
||||
// Unless indicated otherwise, numeric quantities use the following units:
|
||||
//
|
||||
// Measurement | Unit
|
||||
// ------------+-------------------------------------
|
||||
// angle | degrees
|
||||
// distance | metres
|
||||
// speed | metres per second
|
||||
// servo angle | microseconds
|
||||
// voltage | volts
|
||||
// times | seconds
|
||||
// throttle | percent
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HARDWARE CONFIGURATION AND CONNECTIONS
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GPS_PROTOCOL REQUIRED
|
||||
//
|
||||
// GPS configuration, must be one of:
|
||||
//
|
||||
// GPS_PROTOCOL_NONE No GPS attached
|
||||
// GPS_PROTOCOL_IMU X-Plane interface or ArduPilot IMU.
|
||||
// GPS_PROTOCOL_MTK MediaTek-based GPS.
|
||||
// GPS_PROTOCOL_UBLOX UBLOX GPS
|
||||
// GPS_PROTOCOL_SIRF SiRF-based GPS in Binary mode. NOT TESTED
|
||||
// GPS_PROTOCOL_NMEA Standard NMEA GPS. NOT SUPPORTED (yet?)
|
||||
//
|
||||
//#define GPS_PROTOCOL GPS_PROTOCOL_UBLOX
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AIRSPEED_SENSOR OPTIONAL
|
||||
// AIRSPEED_RATIO OPTIONAL
|
||||
//
|
||||
// Set AIRSPEED_SENSOR to ENABLED if you have an airspeed sensor attached.
|
||||
// Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed
|
||||
// sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s
|
||||
//
|
||||
// The default assumes that an airspeed sensor is connected.
|
||||
//
|
||||
//#define AIRSPEED_SENSOR ENABLED
|
||||
//#define AIRSPEED_RATIO 1.9936
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HIL_PROTOCOL OPTIONAL
|
||||
// HIL_MODE OPTIONAL
|
||||
// HIL_PORT OPTIONAL
|
||||
//
|
||||
// Configuration for Hardware-in-the-loop simulation. In these modes,
|
||||
// APM is connected via one or more interfaces to simulation software
|
||||
// running on another system.
|
||||
//
|
||||
// HIL_PROTOCOL_XPLANE Configure for the X-plane HIL interface.
|
||||
// HIL_PROTOCOL_MAVLINK Configure for HIL over MAVLink.
|
||||
//
|
||||
// HIL_MODE_DISABLED Configure for standard flight.
|
||||
// HIL_MODE_ATTITUDE Simulator provides attitude and position information.
|
||||
// HIL_MODE_SENSORS Simulator provides raw sensor values.
|
||||
//
|
||||
// Note that currently HIL_PROTOCOL_XPLANE requires HIL_MODE_ATTITUDE.
|
||||
// Note that currently HIL_PROTOCOL_MAVLINK requires HIL_MODE_SENSORS.
|
||||
//
|
||||
//#define HIL_MODE HIL_MODE_DISABLED
|
||||
//#define HIL_PORT 0
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GCS_PROTOCOL OPTIONAL
|
||||
// GCS_PORT OPTIONAL
|
||||
//
|
||||
// The GCS_PROTOCOL option determines which (if any) ground control station
|
||||
// protocol will be used. Must be one of:
|
||||
//
|
||||
// GCS_PROTOCOL_NONE No GCS output
|
||||
// GCS_PROTOCOL_STANDARD standard APM protocol
|
||||
// GCS_PROTOCOL_LEGACY legacy ArduPilot protocol
|
||||
// GCS_PROTOCOL_DEBUGTERMINAL In-flight debug console (experimental)
|
||||
// GCS_PROTOCOL_MAVLINK QGroundControl protocol
|
||||
//
|
||||
// The GCS_PORT option determines which serial port will be used by the
|
||||
// GCS protocol. The usual values are 0 for the console/USB port,
|
||||
// or 3 for the telemetry port on the oilpan. Note that some protocols
|
||||
// will ignore this value and always use the console port.
|
||||
//
|
||||
// The default serial port is the telemetry port for GCS_PROTOCOL_STANDARD
|
||||
// and GCS_PROTOCOL_LEGACY. For all other protocols, the default serial
|
||||
// port is the FTDI/console port. GCS_PORT normally should not be set
|
||||
// in your configuration.
|
||||
//
|
||||
//#define GCS_PROTOCOL GCS_PROTOCOL_NONE
|
||||
//#define GCS_PORT 3
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Serial port speeds.
|
||||
//
|
||||
// SERIAL0_BAUD OPTIONAL
|
||||
//
|
||||
// Baudrate for the console port. Default is 38400bps.
|
||||
//
|
||||
// SERIAL3_BAUD OPTIONAL
|
||||
//
|
||||
// Baudrate for the telemetry port. Default is 115200bps.
|
||||
//
|
||||
//#define SERIAL0_BAUD 115200
|
||||
//#define SERIAL3_BAUD 57600
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Battery monitoring OPTIONAL
|
||||
//
|
||||
// See the manual for details on selecting divider resistors for battery
|
||||
// monitoring via the oilpan.
|
||||
//
|
||||
// BATTERY_EVENT OPTIONAL
|
||||
//
|
||||
// Set BATTERY_EVENT to ENABLED to enable battery monitoring. The default is
|
||||
// DISABLED.
|
||||
//
|
||||
// BATTERY_TYPE OPTIONAL if BATTERY_EVENT is set
|
||||
//
|
||||
// Set to 0 for 3s LiPo, 1 for 4s LiPo. The default is 0, selecting a 3s
|
||||
// battery.
|
||||
//
|
||||
// LOW_VOLTAGE OPTIONAL if BATTERY_EVENT is set.
|
||||
//
|
||||
// Normally derived from BATTERY_TYPE, the automatic value can be overridden
|
||||
// here. Value in volts at which ArduPilot Mega should consider the
|
||||
// battery to be "low".
|
||||
//
|
||||
// VOLT_DIV_RATIO OPTIONAL
|
||||
//
|
||||
// See the manual for details. The default value corresponds to the resistors
|
||||
// recommended by the manual.
|
||||
//
|
||||
//#define BATTERY_EVENT DISABLED
|
||||
//#define BATTERY_TYPE 0
|
||||
//#define LOW_VOLTAGE 11.4
|
||||
//#define VOLT_DIV_RATIO 3.0
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// INPUT_VOLTAGE OPTIONAL
|
||||
//
|
||||
// In order to have accurate pressure and battery voltage readings, this
|
||||
// value should be set to the voltage measured on the 5V rail on the oilpan.
|
||||
//
|
||||
// See the manual for more details. The default value should be close.
|
||||
//
|
||||
//#define INPUT_VOLTAGE 5.0
|
||||
//
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RADIO CONFIGURATION
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT_MODE OPTIONAL
|
||||
// FLIGHT_MODE_CHANNEL OPTIONAL
|
||||
//
|
||||
// Flight modes assigned to the control channel, and the input channel that
|
||||
// is read for the control mode.
|
||||
//
|
||||
// Use a servo tester, or the ArduPilotMega_demo test program to check your
|
||||
// switch settings.
|
||||
//
|
||||
// ATTENTION: Some ArduPilot Mega boards have radio channels marked 0-7, and
|
||||
// others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option
|
||||
// uses channel numbers 1-8 (and defaults to 8).
|
||||
//
|
||||
// If you only have a three-position switch or just want three modes, set your
|
||||
// switch to produce 1165, 1425, and 1815 microseconds and configure
|
||||
// FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default.
|
||||
//
|
||||
// If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control
|
||||
// channel connected to input channel 8, the hardware failsafe mode will
|
||||
// activate for any control input over 1750ms.
|
||||
//
|
||||
// For more modes (up to six), set your switch(es) to produce any of 1165,
|
||||
// 1295, 1425, 1555, 1685, and 1815 microseconds.
|
||||
//
|
||||
// Flight mode | Switch Setting (ms)
|
||||
// ------------+---------------------
|
||||
// 1 | 1165
|
||||
// 2 | 1295
|
||||
// 3 | 1425
|
||||
// 4 | 1555
|
||||
// 5 | 1685
|
||||
// 6 | 1815 (FAILSAFE if using channel 8)
|
||||
//
|
||||
// The following standard flight modes are available:
|
||||
//
|
||||
// Name | Description
|
||||
// -----------------+--------------------------------------------
|
||||
// |
|
||||
// MANUAL | Full manual control via the hardware multiplexer.
|
||||
// |
|
||||
// STABILIZE | Tries to maintain level flight, but can be overridden with radio control inputs.
|
||||
// |
|
||||
// FLY_BY_WIRE_A | Autopilot style control via user input, with manual throttle.
|
||||
// |
|
||||
// FLY_BY_WIRE_B | Autopilot style control via user input, aispeed controlled with throttle.
|
||||
// |
|
||||
// RTL | Returns to the Home location and then LOITERs at a safe altitude.
|
||||
// |
|
||||
// AUTO | Autonomous flight based on programmed waypoints. Use the WaypointWriter
|
||||
// | application or your Ground Control System to edit and upload
|
||||
// | waypoints and other commands.
|
||||
// |
|
||||
//
|
||||
//
|
||||
// The following non-standard modes are EXPERIMENTAL:
|
||||
//
|
||||
// Name | Description
|
||||
// -----------------+--------------------------------------------
|
||||
// |
|
||||
// LOITER | Flies in a circle around the current location.
|
||||
// |
|
||||
// CIRCLE | Flies in a stabilized 'dumb' circle.
|
||||
// |
|
||||
//
|
||||
//
|
||||
// If you are using channel 8 for mode switching then FLIGHT_MODE_5 and
|
||||
// FLIGHT_MODE_6 should be MANUAL.
|
||||
//
|
||||
//
|
||||
//#define FLIGHT_MODE_CHANNEL 8
|
||||
//
|
||||
//#define FLIGHT_MODE_1 RTL
|
||||
//#define FLIGHT_MODE_2 RTL
|
||||
//#define FLIGHT_MODE_3 FLY_BY_WIRE_A
|
||||
//#define FLIGHT_MODE_4 FLY_BY_WIRE_A
|
||||
//#define FLIGHT_MODE_5 MANUAL
|
||||
//#define FLIGHT_MODE_6 MANUAL
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_FAILSAFE OPTIONAL
|
||||
// THROTTLE_FS_VALUE OPTIONAL
|
||||
// THROTTLE_FAILSAFE_ACTION OPTIONAL
|
||||
//
|
||||
// The throttle failsafe allows you to configure a software failsafe activated
|
||||
// by a setting on the throttle input channel (channel 3).
|
||||
//
|
||||
// This can be used to achieve a failsafe override on loss of radio control
|
||||
// without having to sacrifice one of your FLIGHT_MODE settings, as the
|
||||
// throttle failsafe overrides the switch-selected mode.
|
||||
//
|
||||
// Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1. The default
|
||||
// is for it to be disabled.
|
||||
//
|
||||
// If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value
|
||||
// below which the failsafe engages. The default is 975ms, which is a very low
|
||||
// throttle setting. Most transmitters will let you trim the manual throttle
|
||||
// position up so that you cannot engage the failsafe with a regular stick movement.
|
||||
//
|
||||
// Configure your receiver's failsafe setting for the throttle channel to the
|
||||
// absolute minimum, and use the ArduPilotMega_demo program to check that
|
||||
// you cannot reach that value with the throttle control. Leave a margin of
|
||||
// at least 50 microseconds between the lowest throttle setting and
|
||||
// THROTTLE_FS_VALUE.
|
||||
//
|
||||
// The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe
|
||||
// mode is entered while flying in AUTO mode. This is important in order to avoid
|
||||
// accidental failsafe behaviour when flying waypoints that take the aircraft
|
||||
// temporarily out of radio range.
|
||||
//
|
||||
// If FAILSAFE_ACTION is 1, when failsafe is entered in AUTO or LOITER modes,
|
||||
// the aircraft will head for home in RTL mode. If the throttle channel moves
|
||||
// back up, it will return to AUTO or LOITER mode.
|
||||
//
|
||||
// The default behaviour is to ignore throttle failsafe in AUTO and LOITER modes.
|
||||
//
|
||||
//#define THROTTLE_FAILSAFE DISABLED
|
||||
//#define THROTTLE_FS_VALUE 975
|
||||
//#define THROTTLE_FAILSAFE_ACTION 2
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AUTO_TRIM OPTIONAL
|
||||
//
|
||||
// ArduPilot Mega can update its trim settings by looking at the
|
||||
// radio inputs when switching out of MANUAL mode. This allows you to
|
||||
// manually trim your aircraft before switching to an assisted mode, but it
|
||||
// also means that you should avoid switching out of MANUAL while you have
|
||||
// any control stick deflection.
|
||||
//
|
||||
// The default is to enable AUTO_TRIM.
|
||||
//
|
||||
//#define AUTO_TRIM ENABLED
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_REVERSE OPTIONAL
|
||||
//
|
||||
// A few speed controls require the throttle servo signal be reversed. Setting
|
||||
// this to ENABLED will reverse the throttle output signal. Ensure that your
|
||||
// throttle needs to be reversed by using the hardware failsafe and the
|
||||
// ArduPilotMega_demo program before setting this option.
|
||||
//
|
||||
// The default is to not reverse the signal.
|
||||
//
|
||||
//#define THROTTLE_REVERSE DISABLED
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_STICK_MIXING OPTIONAL
|
||||
//
|
||||
// If this option is set to ENABLED, manual control inputs are are respected
|
||||
// while in the autopilot modes (AUTO, RTL, LOITER, CIRCLE etc.)
|
||||
//
|
||||
// The default is to enable stick mixing, allowing the pilot to take
|
||||
// emergency action without switching modes.
|
||||
//
|
||||
//#define ENABLE_STICK_MIXING ENABLED
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_OUT DEBUG
|
||||
//
|
||||
// When debugging, it can be useful to disable the throttle output. Set
|
||||
// this option to DISABLED to disable throttle output signals.
|
||||
//
|
||||
// The default is to not disable throttle output.
|
||||
//
|
||||
//#define THROTTLE_OUT ENABLED
|
||||
//
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// STARTUP BEHAVIOUR
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GROUND_START_DELAY OPTIONAL
|
||||
//
|
||||
// If configured, inserts a delay between power-up and the beginning of IMU
|
||||
// calibration during a ground start.
|
||||
//
|
||||
// Use this setting to give you time to position the aircraft horizontally
|
||||
// for the IMU calibration.
|
||||
//
|
||||
// The default is to begin IMU calibration immediately at startup.
|
||||
//
|
||||
//#define GROUND_START_DELAY 0
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_AIR_START OPTIONAL
|
||||
//
|
||||
// If air start is disabled then you will get a ground start (including IMU
|
||||
// calibration) every time the AP is powered up. This means that if you get
|
||||
// a power glitch or reboot for some reason in the air, you will probably
|
||||
// crash, but it prevents a lot of problems on the ground like unintentional
|
||||
// motor start-ups, etc.
|
||||
//
|
||||
// If air start is enabled then you will get an air start at power up and a
|
||||
// ground start will be performed if the speed is near zero when we get gps
|
||||
// lock.
|
||||
//
|
||||
// The default is to disable air start.
|
||||
//
|
||||
//#define ENABLE_AIR_START 0
|
||||
//
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT AND NAVIGATION CONTROL
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Altitude measurement and control.
|
||||
//
|
||||
// AOA OPTIONAL
|
||||
//
|
||||
// The angle in 100ths of a degree that the nose of the aircraft should be
|
||||
// raised from horizontal in level flight. The default is 1 degree.
|
||||
//
|
||||
//#define AOA 100 // note, 100ths of a degree
|
||||
//
|
||||
// ALT_EST_GAIN OPTIONAL
|
||||
//
|
||||
// The gain of the altitude estimation function; a lower number results
|
||||
// in slower error correction and smoother output. The default is a
|
||||
// reasonable starting point.
|
||||
//
|
||||
//#define ALT_EST_GAIN 0.01
|
||||
//
|
||||
// ALTITUDE_MIX OPTIONAL
|
||||
//
|
||||
// Configures the blend between GPS and pressure altitude.
|
||||
// 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc.
|
||||
//
|
||||
// The default is to use only GPS altitude.
|
||||
//
|
||||
//#define ALTITUDE_MIX 0
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AIRSPEED_CRUISE OPTIONAL
|
||||
//
|
||||
// The speed in metres per second to maintain during cruise. The default
|
||||
// is 10m/s, which is a conservative value suitable for relatively small,
|
||||
// light aircraft.
|
||||
//
|
||||
//#define AIRSPEED_CRUISE 10
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLY_BY_WIRE_B airspeed control (also used for throttle "nudging" in AUTO)
|
||||
//
|
||||
// AIRSPEED_FBW_MIN OPTIONAL
|
||||
// AIRSPEED_FBW_MAX OPTIONAL
|
||||
//
|
||||
// Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode.
|
||||
// The defaults are 6 and 30 metres per second.
|
||||
//
|
||||
// AIRSPEED_FBW_MAX also sets the maximum airspeed that the cruise airspeed can be "nudged" to in AUTO mode when ENABLE_STICK_MIXING is set.
|
||||
// In AUTO the cruise airspeed can be increased between AIRSPEED_CRUISE and AIRSPEED_FBW_MAX by positioning the throttle
|
||||
// stick in the top 1/2 of its range. Throttle stick in the bottom 1/2 provide regular AUTO control.
|
||||
//
|
||||
// THROTTLE_ALT_P OPTIONAL
|
||||
// THROTTLE_ALT_I OPTIONAL
|
||||
// THROTTLE_ALT_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for the throttle control loop. Defaults are 0.32, 0, 0.
|
||||
//
|
||||
// THROTTLE_ALT_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum throttle input due to the integral. Limits the throttle input
|
||||
// due to persistent inability to maintain the commanded speed. Helps
|
||||
// prevent the throttle from staying wide open when the control is reduced
|
||||
// after a period at maxium speed.
|
||||
// Default is 20 (20%).
|
||||
//
|
||||
//#define AIRSPEED_FBW_MIN 6
|
||||
//#define AIRSPEED_FBW_MAX 30
|
||||
//#define THROTTLE_ALT_P 0.32
|
||||
//#define THROTTLE_ALT_I 0.0
|
||||
//#define THROTTLE_ALT_D 0.0
|
||||
//#define THROTTLE_ALT_INT_MAX 20
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Throttle control
|
||||
//
|
||||
// THROTTLE_MIN OPTIONAL
|
||||
//
|
||||
// The minimum throttle setting to which the autopilot will reduce the
|
||||
// throttle while descending. The default is zero, which is
|
||||
// suitable for aircraft with a steady power-off glide. Increase this
|
||||
// value if your aircraft needs throttle to maintain a stable descent in
|
||||
// level flight.
|
||||
//
|
||||
// THROTTLE_CRUISE OPTIONAL
|
||||
//
|
||||
// The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight.
|
||||
// The default is 45%, which is reasonable for a modestly powered aircraft.
|
||||
//
|
||||
// THROTTLE_MAX OPTIONAL
|
||||
//
|
||||
// The maximum throttle setting the autopilot will apply. The default is 75%.
|
||||
// Reduce this value if your aicraft is overpowered, or has complex flight
|
||||
// characteristics at high throttle settings.
|
||||
//
|
||||
//#define THROTTLE_MIN 0
|
||||
//#define THROTTLE_CRUISE 45
|
||||
//#define THROTTLE_MAX 75
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Autopilot control limits
|
||||
//
|
||||
// HEAD_MAX OPTIONAL
|
||||
//
|
||||
// The maximum commanded bank angle in either direction.
|
||||
// The default is 45 degrees. Decrease this value if your aircraft is not
|
||||
// stable or has difficulty maintaining altitude in a steep bank.
|
||||
//
|
||||
// PITCH_MAX OPTIONAL
|
||||
//
|
||||
// The maximum commanded pitch up angle.
|
||||
// The default is 15 degrees. Care should be taken not to set this value too
|
||||
// large, as the aircraft may stall.
|
||||
//
|
||||
// PITCH_MIN
|
||||
//
|
||||
// The maximum commanded pitch down angle. Note that this value must be
|
||||
// negative. The default is -25 degrees. Care should be taken not to set
|
||||
// this value too large as it may result in overspeeding the aircraft.
|
||||
//
|
||||
//#define HEAD_MAX 45
|
||||
//#define PITCH_MAX 15
|
||||
//#define PITCH_MIN -25
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Attitude control gains
|
||||
//
|
||||
// Tuning values for the attitude control PID loops.
|
||||
//
|
||||
// The P term is the primary tuning value. This determines how the control
|
||||
// deflection varies in proportion to the required correction.
|
||||
//
|
||||
// The I term is used to help control surfaces settle. This value should
|
||||
// normally be kept low.
|
||||
//
|
||||
// The D term is used to control overshoot. Avoid using or adjusting this
|
||||
// term if you are not familiar with tuning PID loops. It should normally
|
||||
// be zero for most aircraft.
|
||||
//
|
||||
// Note: When tuning these values, start with changes of no more than 25% at
|
||||
// a time.
|
||||
//
|
||||
// SERVO_ROLL_P OPTIONAL
|
||||
// SERVO_ROLL_I OPTIONAL
|
||||
// SERVO_ROLL_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for roll control. Defaults are 0.4, 0, 0.
|
||||
//
|
||||
// SERVO_ROLL_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum control offset due to the integral. This prevents the control
|
||||
// output from being overdriven due to a persistent offset (e.g. crosstracking).
|
||||
// Default is 5 degrees.
|
||||
//
|
||||
// ROLL_SLEW_LIMIT EXPERIMENTAL
|
||||
//
|
||||
// Limits the slew rate of the roll control in degrees per second. If zero,
|
||||
// slew rate is not limited. Default is to not limit the roll control slew rate.
|
||||
// (This feature is currently not implemented.)
|
||||
//
|
||||
// SERVO_PITCH_P OPTIONAL
|
||||
// SERVO_PITCH_I OPTIONAL
|
||||
// SERVO_PITCH_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for the pitch control. Defaults are 0.6, 0, 0.
|
||||
//
|
||||
// SERVO_PITCH_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum control offset due to the integral. This prevents the control
|
||||
// output from being overdriven due to a persistent offset (e.g. native flight
|
||||
// AoA). If you find this value is insufficient, consider adjusting the AOA
|
||||
// parameter.
|
||||
// Default is 5 degrees.
|
||||
//
|
||||
// PITCH_COMP OPTIONAL
|
||||
//
|
||||
// Adds pitch input to compensate for the loss of lift due to roll control.
|
||||
// Default is 0.20 (20% of roll control also applied to pitch control).
|
||||
//
|
||||
// SERVO_YAW_P OPTIONAL
|
||||
// SERVO_YAW_I OPTIONAL
|
||||
// SERVO_YAW_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for the YAW control. Defaults are 0., 0., 0.
|
||||
//
|
||||
// SERVO_YAW_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum control offset due to the integral. This prevents the control
|
||||
// output from being overdriven due to a persistent offset (e.g. crosstracking).
|
||||
// Default is 5 degrees.
|
||||
//
|
||||
// RUDDER_MIX OPTIONAL
|
||||
//
|
||||
// Roll to yaw mixing. This allows for co-ordinated turns.
|
||||
// Default is 0.50 (50% of roll control also applied to yaw control.)
|
||||
//
|
||||
//#define SERVO_ROLL_P 0.4
|
||||
//#define SERVO_ROLL_I 0.0
|
||||
//#define SERVO_ROLL_D 0.0
|
||||
//#define SERVO_ROLL_INT_MAX 5
|
||||
//#define ROLL_SLEW_LIMIT 0
|
||||
//#define SERVO_PITCH_P 0.6
|
||||
//#define SERVO_PITCH_I 0.0
|
||||
//#define SERVO_PITCH_D 0.0
|
||||
//#define SERVO_PITCH_INT_MAX 5
|
||||
//#define PITCH_COMP 0.2
|
||||
//#define SERVO_YAW_P 0.0 // Default is zero. A suggested value if you want to use this parameter is 0.5
|
||||
//#define SERVO_YAW_I 0.0
|
||||
//#define SERVO_YAW_D 0.0
|
||||
//#define SERVO_YAW_INT_MAX 5
|
||||
//#define RUDDER_MIX 0.5
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation control gains
|
||||
//
|
||||
// Tuning values for the navigation control PID loops.
|
||||
//
|
||||
// The P term is the primary tuning value. This determines how the control
|
||||
// deflection varies in proportion to the required correction.
|
||||
//
|
||||
// The I term is used to control drift.
|
||||
//
|
||||
// The D term is used to control overshoot. Avoid adjusting this term if
|
||||
// you are not familiar with tuning PID loops.
|
||||
//
|
||||
// Note: When tuning these values, start with changes of no more than 25% at
|
||||
// a time.
|
||||
//
|
||||
// NAV_ROLL_P OPTIONAL
|
||||
// NAV_ROLL_I OPTIONAL
|
||||
// NAV_ROLL_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for navigation control over roll, normally used for
|
||||
// controlling the aircraft's course. The P term controls how aggressively
|
||||
// the aircraft will bank to change or hold course.
|
||||
// Defaults are 0.7, 0.0, 0.02.
|
||||
//
|
||||
// NAV_ROLL_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum control offset due to the integral. This prevents the control
|
||||
// output from being overdriven due to a persistent offset (e.g. crosstracking).
|
||||
// Default is 5 degrees.
|
||||
//
|
||||
// NAV_PITCH_ASP_P OPTIONAL
|
||||
// NAV_PITCH_ASP_I OPTIONAL
|
||||
// NAV_PITCH_ASP_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for pitch adjustments made to maintain airspeed.
|
||||
// Defaults are 0.65, 0, 0.
|
||||
//
|
||||
// NAV_PITCH_ASP_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum pitch offset due to the integral. This limits the control
|
||||
// output from being overdriven due to a persistent offset (eg. inability
|
||||
// to maintain the programmed airspeed).
|
||||
// Default is 5 degrees.
|
||||
//
|
||||
// NAV_PITCH_ALT_P OPTIONAL
|
||||
// NAV_PITCH_ALT_I OPTIONAL
|
||||
// NAV_PITCH_ALT_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for pitch adjustments made to maintain altitude.
|
||||
// Defaults are 0.65, 0, 0.
|
||||
//
|
||||
// NAV_PITCH_ALT_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum pitch offset due to the integral. This limits the control
|
||||
// output from being overdriven due to a persistent offset (eg. inability
|
||||
// to maintain the programmed altitude).
|
||||
// Default is 5 degrees.
|
||||
//
|
||||
//#define NAV_ROLL_P 0.7
|
||||
//#define NAV_ROLL_I 0.01
|
||||
//#define NAV_ROLL_D 0.02
|
||||
//#define NAV_ROLL_INT_MAX 5
|
||||
//#define NAV_PITCH_ASP_P 0.65
|
||||
//#define NAV_PITCH_ASP_I 0.0
|
||||
//#define NAV_PITCH_ASP_D 0.0
|
||||
//#define NAV_PITCH_ASP_INT_MAX 5
|
||||
//#define NAV_PITCH_ALT_P 0.65
|
||||
//#define NAV_PITCH_ALT_I 0.0
|
||||
//#define NAV_PITCH_ALT_D 0.0
|
||||
//#define NAV_PITCH_ALT_INT_MAX 5
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Energy/Altitude control gains
|
||||
//
|
||||
// The Energy/altitude control system uses throttle input to control aircraft
|
||||
// altitude.
|
||||
//
|
||||
// The P term is the primary tuning value. This determines how the throttle
|
||||
// setting varies in proportion to the required correction.
|
||||
//
|
||||
// The I term is used to compensate for small offsets.
|
||||
//
|
||||
// The D term is used to control overshoot. Avoid adjusting this term if
|
||||
// you are not familiar with tuning PID loops.
|
||||
//
|
||||
// THROTTLE_TE_P OPTIONAL
|
||||
// THROTTLE_TE_I OPTIONAL
|
||||
// THROTTLE_TE_D OPTIONAL
|
||||
//
|
||||
// P, I and D terms for throttle adjustments made to control altitude.
|
||||
// Defaults are 0.5, 0, 0.
|
||||
//
|
||||
// THROTTLE_TE_INT_MAX OPTIONAL
|
||||
//
|
||||
// Maximum throttle input due to the integral term. This limits the
|
||||
// throttle from being overdriven due to a persistent offset (e.g.
|
||||
// inability to maintain the programmed altitude).
|
||||
// Default is 20%.
|
||||
//
|
||||
// THROTTLE_SLEW_LIMIT OPTIONAL
|
||||
//
|
||||
// Limits the slew rate of the throttle, in percent per second. Helps
|
||||
// avoid sudden throttle changes, which can destabilise the aircraft.
|
||||
// A setting of zero disables the feature.
|
||||
// Default is zero (disabled).
|
||||
//
|
||||
// P_TO_T OPTIONAL
|
||||
//
|
||||
// Pitch to throttle feed-forward gain. Used when AIRSPEED_SENSOR
|
||||
// is DISABLED. Default is 2.5.
|
||||
//
|
||||
//#define THROTTLE_TE_P 0.50
|
||||
//#define THROTTLE_TE_I 0.0
|
||||
//#define THROTTLE_TE_D 0.0
|
||||
//#define THROTTLE_TE_INT_MAX 20
|
||||
//#define THROTTLE_SLEW_LIMIT 0
|
||||
//#define P_TO_T 2.5
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Crosstrack compensation
|
||||
//
|
||||
// XTRACK_GAIN OPTIONAL
|
||||
//
|
||||
// Crosstrack compensation in degrees per metre off track.
|
||||
// Default value is 0.01 degrees per metre. Values lower than 0.001 will
|
||||
// disable crosstrack compensation.
|
||||
//
|
||||
// XTRACK_ENTRY_ANGLE OPTIONAL
|
||||
//
|
||||
// Maximum angle used to correct for track following.
|
||||
// Default value is 30 degrees.
|
||||
//
|
||||
//#define XTRACK_GAIN 10 // deg/m * 100
|
||||
//#define XTRACK_ENTRY_ANGLE 3000 // deg * 100
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// DEBUGGING
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Subsystem test and debug.
|
||||
//
|
||||
// DEBUG_SUBSYSTEM DEBUG
|
||||
//
|
||||
// Selects a subsystem debug mode. Default is 0.
|
||||
//
|
||||
// 0 = no debug
|
||||
// 1 = Debug the Radio input
|
||||
// 2 = Radio Setup / Servo output
|
||||
// 4 = Debug the GPS input
|
||||
// 5 = Debug the GPS input - RAW OUTPUT
|
||||
// 6 = Debug the IMU
|
||||
// 7 = Debug the Control Switch
|
||||
// 8 = Debug the Servo DIP switches
|
||||
// 9 = Debug the Relay out
|
||||
// 10 = Debug the Magnetometer Note - The magnetometer is not supported in V1.0
|
||||
// 11 = Debug the ABS pressure sensor
|
||||
// 12 = Debug the stored waypoints
|
||||
// 13 = Debug the Throttle
|
||||
// 14 = Debug the Radio Min Max
|
||||
// 15 = Debug the EEPROM - Hex Dump
|
||||
// 16 = XBee X-CTU Range and RSSI Test
|
||||
// 17 = Debug IMU - raw gyro and accel outputs
|
||||
// 20 = Debug Analog Sensors
|
||||
//
|
||||
//
|
||||
//#define DEBUG_SUBSYSTEM 0
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// DEBUG_LEVEL DEBUG
|
||||
//
|
||||
// Selects the lowest level of debug messages passed to the telemetry system.
|
||||
// Default is SEVERITY_LOW. May be one of:
|
||||
//
|
||||
// SEVERITY_LOW
|
||||
// SEVERITY_MEDIUM
|
||||
// SEVERITY_HIGH
|
||||
// SEVERITY_CRITICAL
|
||||
//
|
||||
//#define DEBUG_LEVEL SEVERITY_LOW
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Dataflash logging control
|
||||
//
|
||||
// Each of these logging options may be set to ENABLED to enable, or DISABLED
|
||||
// to disable the logging of the respective data.
|
||||
//
|
||||
// LOG_ATTITUDE_FAST DEBUG
|
||||
//
|
||||
// Logs basic attitude info to the dataflash at 50Hz (uses more space).
|
||||
// Defaults to DISABLED.
|
||||
//
|
||||
// LOG_ATTITUDE_MED OPTIONAL
|
||||
//
|
||||
// Logs basic attitude info to the dataflash at 10Hz (uses less space than
|
||||
// LOG_ATTITUDE_FAST). Defaults to ENABLED.
|
||||
//
|
||||
// LOG_GPS OPTIONAL
|
||||
//
|
||||
// Logs GPS info to the dataflash at 10Hz. Defaults to ENABLED.
|
||||
//
|
||||
// LOG_PM OPTIONAL
|
||||
//
|
||||
// Logs IMU performance monitoring info every 20 seconds.
|
||||
// Defaults to DISABLED.
|
||||
//
|
||||
// LOG_CTUN OPTIONAL
|
||||
//
|
||||
// Logs control loop tuning info at 10 Hz. This information is useful for tuning
|
||||
// servo control loop gain values. Defaults to DISABLED.
|
||||
//
|
||||
// LOG_NTUN OPTIONAL
|
||||
//
|
||||
// Logs navigation tuning info at 10 Hz. This information is useful for tuning
|
||||
// navigation control loop gain values. Defaults to DISABLED.
|
||||
//
|
||||
// LOG_ MODE OPTIONAL
|
||||
//
|
||||
// Logs changes to the flight mode upon occurrence. Defaults to ENABLED.
|
||||
//
|
||||
// LOG_RAW DEBUG
|
||||
//
|
||||
// Logs raw accelerometer and gyro data at 50 Hz (uses more space).
|
||||
// Defaults to DISABLED.
|
||||
//
|
||||
// LOG_CMD OPTIONAL
|
||||
//
|
||||
// Logs new commands when they process.
|
||||
// Defaults to ENABLED.
|
||||
//
|
||||
//#define LOG_ATTITUDE_FAST DISABLED
|
||||
//#define LOG_ATTITUDE_MED ENABLED
|
||||
//#define LOG_GPS ENABLED
|
||||
//#define LOG_PM ENABLED
|
||||
//#define LOG_CTUN DISABLED
|
||||
//#define LOG_NTUN DISABLED
|
||||
//#define LOG_MODE ENABLED
|
||||
//#define LOG_RAW DISABLED
|
||||
//#define LOG_CMD ENABLED
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation defaults
|
||||
//
|
||||
// WP_RADIUS_DEFAULT OPTIONAL
|
||||
//
|
||||
// When the user performs a factory reset on the APM, set the waypoint radius
|
||||
// (the radius from a target waypoint within which the APM will consider
|
||||
// itself to have arrived at the waypoint) to this value in meters. This is
|
||||
// mainly intended to allow users to start using the APM without running the
|
||||
// WaypointWriter first.
|
||||
//
|
||||
// LOITER_RADIUS_DEFAULT OPTIONAL
|
||||
//
|
||||
// When the user performs a factory reset on the APM, set the loiter radius
|
||||
// (the distance the APM will attempt to maintain from a waypoint while
|
||||
// loitering) to this value in meters. This is mainly intended to allow
|
||||
// users to start using the APM without running the WaypointWriter first.
|
||||
//
|
||||
//#define WP_RADIUS_DEFAULT 20
|
||||
//#define LOITER_RADIUS_DEFAULT 60
|
||||
//
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Debugging interface
|
||||
//
|
||||
// DEBUG_PORT OPTIONAL
|
||||
//
|
||||
// The APM will periodically send messages reporting what it is doing; this
|
||||
// variable determines to which serial port they will be sent. Port 0 is the
|
||||
// USB serial port on the shield, port 3 is the telemetry port.
|
||||
//
|
||||
//#define DEBUG_PORT 0
|
||||
//
|
||||
|
||||
//
|
||||
// Do not remove - this is to discourage users from copying this file
|
||||
// and using it as-is rather than editing their own.
|
||||
//
|
||||
#error You should not copy APM_Config.h.reference - make your own APM_Config.h file with just the options you need.
|
|
@ -0,0 +1,55 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
// Enable Autopilot Flight Mode
|
||||
#define FLIGHT_MODE_CHANNEL 8
|
||||
#define FLIGHT_MODE_1 AUTO
|
||||
#define FLIGHT_MODE_2 RTL
|
||||
#define FLIGHT_MODE_3 FLY_BY_WIRE_A
|
||||
#define FLIGHT_MODE_4 FLY_BY_WIRE_B
|
||||
#define FLIGHT_MODE_5 STABILIZE
|
||||
#define FLIGHT_MODE_6 MANUAL
|
||||
|
||||
// Hardware in the loop protocol
|
||||
#define HIL_PROTOCOL HIL_PROTOCOL_MAVLINK
|
||||
|
||||
// HIL_MODE SELECTION
|
||||
//
|
||||
// Mavlink supports
|
||||
// 1. HIL_MODE_ATTITUDE : simulated position, airspeed, and attitude
|
||||
// 2. HIL_MODE_SENSORS: full sensor simulation
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
|
||||
// HIL_PORT SELCTION
|
||||
//
|
||||
// PORT 1
|
||||
// If you would like to run telemetry communications for a groundstation
|
||||
// while you are running hardware in the loop it is necessary to set
|
||||
// HIL_PORT to 1. This uses the port that would have been used for the gps
|
||||
// as the hardware in the loop port. You will have to solder
|
||||
// headers onto the gps port connection on the apm
|
||||
// and connect via an ftdi cable.
|
||||
// The baud rate is set to 115200 in this mode.
|
||||
//
|
||||
// PORT 3
|
||||
// If you don't require telemetry communication with a gcs while running
|
||||
// hardware in the loop you may use the telemetry port as the hardware in
|
||||
// the loop port.
|
||||
// The buad rate is controlled by SERIAL3_BAUD in this mode.
|
||||
#define HIL_PORT 1
|
||||
|
||||
// You can set your gps protocol here for your actual
|
||||
// hardware and leave it without affecting the hardware
|
||||
// in the loop simulation
|
||||
#define GPS_PROTOCOL GPS_PROTOCOL_MTK
|
||||
|
||||
// Ground control station comms
|
||||
#define GCS_PROTOCOL GCS_PROTOCOL_MAVLINK
|
||||
#define GCS_PORT 3
|
||||
|
||||
// Sensors
|
||||
// All sensors are supported in all modes.
|
||||
// The magnetometer is not used in
|
||||
// HIL_MODE_ATTITUDE but you may leave it
|
||||
// enabled if you wish.
|
||||
#define AIRSPEED_SENSOR ENABLED
|
||||
#define MAGNETOMETER ENABLED
|
|
@ -0,0 +1,23 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#define DEBUG_SUBSYSTEM 0
|
||||
|
||||
#define FLIGHT_MODE_CHANNEL 8
|
||||
#define FLIGHT_MODE_1 AUTO
|
||||
#define FLIGHT_MODE_2 RTL
|
||||
#define FLIGHT_MODE_3 FLY_BY_WIRE_A
|
||||
#define FLIGHT_MODE_4 FLY_BY_WIRE_B
|
||||
#define FLIGHT_MODE_5 STABILIZE
|
||||
#define FLIGHT_MODE_6 MANUAL
|
||||
|
||||
#define HIL_PROTOCOL HIL_PROTOCOL_XPLANE
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
#define HIL_PORT 0
|
||||
|
||||
#define GCS_PROTOCOL GCS_PROTOCOL_DEBUGTERMINAL
|
||||
#define GCS_PORT 3
|
||||
|
||||
#define AIRSPEED_CRUISE 25
|
||||
|
||||
#define THROTTLE_FAILSAFE ENABLED
|
||||
#define AIRSPEED_SENSOR ENABLED
|
|
@ -0,0 +1,877 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/*
|
||||
ArduPilotMega (unstable development version)
|
||||
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short
|
||||
Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi
|
||||
Please contribute your ideas!
|
||||
|
||||
|
||||
This firmware is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
*/
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Header includes
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
// AVR runtime
|
||||
#include <avr/io.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <math.h>
|
||||
|
||||
// Libraries
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <APM_BinComm.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <AP_GPS.h> // ArduPilot GPS library
|
||||
#include <Wire.h>
|
||||
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_IMU.h> // ArduPilot Mega IMU Library
|
||||
#include <AP_DCM.h> // ArduPilot Mega DCM Library
|
||||
#include <PID.h> // PID library
|
||||
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
|
||||
// Configuration
|
||||
#include "config.h"
|
||||
|
||||
// Local modules
|
||||
#include "defines.h"
|
||||
#include "global_data.h"
|
||||
#include "GCS.h"
|
||||
#include "HIL.h"
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Serial ports
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// Note that FastSerial port buffers are allocated at ::begin time,
|
||||
// so there is not much of a penalty to defining ports that we don't
|
||||
// use.
|
||||
//
|
||||
FastSerialPort0(Serial); // FTDI/console
|
||||
FastSerialPort1(Serial1); // GPS port
|
||||
FastSerialPort3(Serial3); // Telemetry port
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Sensors
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// There are three basic options related to flight sensor selection.
|
||||
//
|
||||
// - Normal flight mode. Real sensors are used.
|
||||
// - HIL Attitude mode. Most sensors are disabled, as the HIL
|
||||
// protocol supplies attitude information directly.
|
||||
// - HIL Sensors mode. Synthetic sensors are configured that
|
||||
// supply data from the simulation.
|
||||
//
|
||||
|
||||
#if HIL_MODE == HIL_MODE_NONE
|
||||
|
||||
// real sensors
|
||||
AP_ADC_ADS7844 adc;
|
||||
APM_BMP085_Class pitot; //TODO: 'pitot' is not an appropriate name for a static pressure sensor
|
||||
AP_Compass_HMC5843 compass;
|
||||
|
||||
// real GPS selection
|
||||
#if GPS_PROTOCOL == GPS_PROTOCOL_NMEA
|
||||
AP_GPS_NMEA gps(&Serial1);
|
||||
#elif GPS_PROTOCOL == GPS_PROTOCOL_SIRF
|
||||
AP_GPS_SIRF gps(&Serial1);
|
||||
#elif GPS_PROTOCOL == GPS_PROTOCOL_UBLOX
|
||||
AP_GPS_UBLOX gps(&Serial1);
|
||||
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK
|
||||
AP_GPS_MTK gps(&Serial1);
|
||||
#elif GPS_PROTOCOL == GPS_PROTOCOL_NONE
|
||||
AP_GPS_NONE gps(NULL);
|
||||
#else
|
||||
#error Unrecognised GPS_PROTOCOL setting.
|
||||
#endif // GPS PROTOCOL
|
||||
|
||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||
// sensor emulators
|
||||
AP_ADC_HIL adc;
|
||||
APM_BMP085_HIL_Class pitot;
|
||||
AP_Compass_HIL compass;
|
||||
AP_GPS_HIL gps(NULL);
|
||||
|
||||
#elif HIL_MODE == HIL_MODE_ATTITUDE
|
||||
AP_DCM_HIL dcm;
|
||||
AP_GPS_HIL gps(NULL);
|
||||
|
||||
#else
|
||||
#error Unrecognised HIL_MODE setting.
|
||||
#endif // HIL MODE
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK
|
||||
HIL_MAVLINK hil;
|
||||
#elif HIL_PROTOCOL == HIL_PROTOCOL_XPLANE
|
||||
HIL_XPLANE hil;
|
||||
#endif // HIL PROTOCOL
|
||||
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
AP_IMU imu(&adc,getAddress(PARAM_IMU_OFFSET_0));
|
||||
AP_DCM dcm(&imu, &gps, &compass);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// GCS selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_STANDARD
|
||||
// create an instance of the standard GCS.
|
||||
BinComm::MessageHandler GCS_MessageHandlers[] = {
|
||||
{BinComm::MSG_ANY, receive_message, NULL},
|
||||
{BinComm::MSG_NULL, NULL, NULL}
|
||||
};
|
||||
GCS_STANDARD gcs(GCS_MessageHandlers);
|
||||
|
||||
#elif GCS_PROTOCOL == GCS_PROTOCOL_LEGACY
|
||||
GCS_LEGACY gcs;
|
||||
#elif GCS_PROTOCOL == GCS_PROTOCOL_DEBUGTERMINAL
|
||||
GCS_DEBUGTERMINAL gcs;
|
||||
#elif GCS_PROTOCOL == GCS_PROTOCOL_XPLANE
|
||||
GCS_XPLANE gcs; // Should become a HIL
|
||||
#elif GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
GCS_MAVLINK gcs;
|
||||
#else
|
||||
// If we are not using a GCS, we need a stub that does nothing.
|
||||
GCS_Class gcs;
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Global variables
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
byte control_mode = MANUAL;
|
||||
boolean failsafe = false; // did our throttle dip below the failsafe value?
|
||||
boolean ch3_failsafe = false;
|
||||
byte crash_timer;
|
||||
byte oldSwitchPosition; // for remembering the control mode switch
|
||||
boolean reverse_switch = 1; // do we read the reversing switches after startup?
|
||||
|
||||
byte ground_start_count = 6; // have we achieved first lock and set Home?
|
||||
int ground_start_avg; // 5 samples to avg speed for ground start
|
||||
boolean ground_start = false; // have we started on the ground?
|
||||
const char *comma = ",";
|
||||
|
||||
const char* flight_mode_strings[] = {
|
||||
"Manual",
|
||||
"Circle",
|
||||
"Stabilize",
|
||||
"",
|
||||
"",
|
||||
"FBW_A",
|
||||
"FBW_B",
|
||||
"",
|
||||
"",
|
||||
"",
|
||||
"Auto",
|
||||
"RTL",
|
||||
"Loiter",
|
||||
"Takeoff",
|
||||
"Land"};
|
||||
|
||||
|
||||
/* Radio values
|
||||
Channel assignments
|
||||
1 Ailerons (rudder if no ailerons)
|
||||
2 Elevator
|
||||
3 Throttle
|
||||
4 Rudder (if we have ailerons)
|
||||
5 Mode
|
||||
6 TBD
|
||||
7 TBD
|
||||
8 TBD
|
||||
*/
|
||||
|
||||
uint16_t radio_in[8]; // current values from the transmitter - microseconds
|
||||
uint16_t radio_out[8]; // Send to the PWM library
|
||||
int16_t servo_out[8]; // current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100
|
||||
|
||||
uint16_t elevon1_trim = 1500; // TODO: handle in EEProm
|
||||
uint16_t elevon2_trim = 1500;
|
||||
uint16_t ch1_temp = 1500; // Used for elevon mixing
|
||||
uint16_t ch2_temp = 1500;
|
||||
|
||||
int reverse_roll = 1;
|
||||
int reverse_pitch = 1;
|
||||
int reverse_rudder = 1;
|
||||
byte mix_mode = 0; // 0 = normal , 1 = elevons
|
||||
int reverse_elevons = 1;
|
||||
int reverse_ch1_elevon = 1;
|
||||
int reverse_ch2_elevon = 1;
|
||||
|
||||
// for elevons radio_in[CH_ROLL] and radio_in[CH_PITCH] are equivalent aileron and elevator, not left and right elevon
|
||||
|
||||
|
||||
float nav_gain_scaler = 1; // Gain scaling for headwind/tailwind TODO: why does this variable need to be initialized to 1?
|
||||
|
||||
// PID controllers
|
||||
PID pidServoRoll(getAddress(PARAM_RLL2SRV_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidServoPitch(getAddress(PARAM_PTCH2SRV_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidServoRudder(getAddress(PARAM_YW2SRV_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidNavRoll(getAddress(PARAM_HDNG2RLL_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidNavPitchAirspeed(getAddress(PARAM_ARSPD2PTCH_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidNavPitchAltitude(getAddress(PARAM_ALT2PTCH_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidTeThrottle(getAddress(PARAM_ENRGY2THR_P),PID::STORE_EEPROM_FLOAT);
|
||||
PID pidAltitudeThrottle(getAddress(PARAM_ALT2THR_P),PID::STORE_EEPROM_FLOAT);
|
||||
|
||||
PID *pid_index[] = {
|
||||
&pidServoRoll,
|
||||
&pidServoPitch,
|
||||
&pidServoRudder,
|
||||
&pidNavRoll,
|
||||
&pidNavPitchAirspeed,
|
||||
&pidNavPitchAltitude,
|
||||
&pidTeThrottle,
|
||||
&pidAltitudeThrottle
|
||||
};
|
||||
|
||||
// GPS variables
|
||||
// -------------
|
||||
const float t7 = 10000000.0; // used to scale values for EEPROM and flash memory storage
|
||||
float scaleLongUp; // used to reverse longtitude scaling
|
||||
float scaleLongDown; // used to reverse longtitude scaling
|
||||
boolean GPS_light = false; // status of the GPS light
|
||||
|
||||
// Location & Navigation
|
||||
// ---------------------
|
||||
const float radius_of_earth = 6378100; // meters
|
||||
const float gravity = 9.81; // meters/ sec^2
|
||||
long hold_course = -1; // deg * 100 dir of plane
|
||||
long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate
|
||||
long target_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
||||
long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target
|
||||
int climb_rate; // m/s * 100 - For future implementation of controlled ascent/descent by rate
|
||||
|
||||
|
||||
byte command_must_index; // current command memory location
|
||||
byte command_may_index; // current command memory location
|
||||
byte command_must_ID; // current command ID
|
||||
byte command_may_ID; // current command ID
|
||||
//byte EEPROM_command // 1 = from the list, 0 = generated
|
||||
|
||||
|
||||
// Airspeed
|
||||
// --------
|
||||
int airspeed; // m/s * 100
|
||||
int airspeed_nudge = 0; // m/s * 100 : additional airspeed based on throttle stick position in top 1/2 of range
|
||||
float airspeed_error; // m/s * 100
|
||||
long energy_error; // energy state error (kinetic + potential) for altitude hold
|
||||
long airspeed_energy_error; // kinetic portion of energy error
|
||||
|
||||
// Location Errors
|
||||
// ---------------
|
||||
long bearing_error; // deg * 100 : 0 to 36000
|
||||
long altitude_error; // meters * 100 we are off in altitude
|
||||
float crosstrack_error; // meters we are off trackline
|
||||
|
||||
// Sensors
|
||||
// --------
|
||||
float airpressure_raw; // Airspeed Sensor - is a float to better handle filtering
|
||||
int airpressure_offset; // analog air pressure sensor while still
|
||||
int airpressure; // airspeed as a pressure value
|
||||
float battery_voltage = LOW_VOLTAGE * 1.05; // Battery Voltage of total battery, initialized above threshold for filter
|
||||
float battery_voltage1 = LOW_VOLTAGE * 1.05; // Battery Voltage of cell 1, initialized above threshold for filter
|
||||
float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2, initialized above threshold for filter
|
||||
float battery_voltage3 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2+3, initialized above threshold for filter
|
||||
float battery_voltage4 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2+3+4, initialized above threshold for filter
|
||||
|
||||
// Pressure Sensor variables
|
||||
unsigned long abs_press;
|
||||
unsigned long abs_press_filt;
|
||||
unsigned long abs_press_gnd;
|
||||
int ground_temperature;
|
||||
int temp_unfilt;
|
||||
long ground_alt; // Ground altitude from gps at startup in centimeters
|
||||
long press_alt; // Pressure altitude
|
||||
|
||||
// flight mode specific
|
||||
// --------------------
|
||||
boolean takeoff_complete = true; // Flag for using gps ground course instead of IMU yaw. Set false when takeoff command processes.
|
||||
boolean land_complete = false;
|
||||
int landing_pitch; // pitch for landing set by commands
|
||||
int takeoff_pitch;
|
||||
int takeoff_altitude;
|
||||
int landing_distance; // meters;
|
||||
|
||||
// Loiter management
|
||||
// -----------------
|
||||
long old_target_bearing; // deg * 100
|
||||
int loiter_total; // deg : how many times to loiter * 360
|
||||
int loiter_delta; // deg : how far we just turned
|
||||
int loiter_sum; // deg : how far we have turned around a waypoint
|
||||
long loiter_time; // millis : when we started LOITER mode
|
||||
int loiter_time_max; // millis : how long to stay in LOITER mode
|
||||
|
||||
// these are the values for navigation control functions
|
||||
// ----------------------------------------------------
|
||||
long nav_roll; // deg * 100 : target roll angle
|
||||
long nav_pitch; // deg * 100 : target pitch angle
|
||||
long altitude_estimate; // for smoothing GPS output
|
||||
|
||||
int throttle_nudge = 0; // 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel
|
||||
|
||||
// Waypoints
|
||||
// ---------
|
||||
long wp_distance; // meters - distance between plane and next waypoint
|
||||
long wp_totalDistance; // meters - distance between old and next waypoint
|
||||
byte next_wp_index; // Current active command index
|
||||
|
||||
// repeating event control
|
||||
// -----------------------
|
||||
byte event_id; // what to do - see defines
|
||||
long event_timer; // when the event was asked for in ms
|
||||
int event_delay; // how long to delay the next firing of event in millis
|
||||
int event_repeat; // how many times to fire : 0 = forever, 1 = do once, 2 = do twice
|
||||
int event_value; // per command value, such as PWM for servos
|
||||
int event_undo_value; // the value used to undo commands
|
||||
byte repeat_forever;
|
||||
byte undo_event; // counter for timing the undo
|
||||
|
||||
// delay command
|
||||
// --------------
|
||||
int delay_timeout = 0; // used to delay commands
|
||||
long delay_start = 0; // used to delay commands
|
||||
|
||||
// 3D Location vectors
|
||||
// -------------------
|
||||
struct Location home; // home location
|
||||
struct Location prev_WP; // last waypoint
|
||||
struct Location current_loc; // current location
|
||||
struct Location next_WP; // next waypoint
|
||||
struct Location tell_command; // command for telemetry
|
||||
struct Location next_command; // command preloaded
|
||||
long target_altitude; // used for
|
||||
long offset_altitude; // used for
|
||||
boolean home_is_set = false; // Flag for if we have gps lock and have set the home location
|
||||
|
||||
// patch antenna variables
|
||||
struct Location trackVehicle_loc; // vehicle location to track with antenna
|
||||
|
||||
// IMU variables
|
||||
// -------------
|
||||
float G_Dt = 0.02; // Integration time for the gyros (DCM algorithm)
|
||||
|
||||
float COGX; // Course overground X axis
|
||||
float COGY = 1; // Course overground Y axis
|
||||
|
||||
// Performance monitoring
|
||||
// ----------------------
|
||||
long perf_mon_timer;
|
||||
float imu_health; // Metric based on accel gain deweighting
|
||||
int G_Dt_max; // Max main loop cycle time in milliseconds
|
||||
byte gyro_sat_count;
|
||||
byte adc_constraints;
|
||||
byte renorm_sqrt_count;
|
||||
byte renorm_blowup_count;
|
||||
int gps_fix_count;
|
||||
byte gcs_messages_sent;
|
||||
|
||||
|
||||
// GCS
|
||||
// ---
|
||||
char GCS_buffer[53];
|
||||
char display_PID = -1; // Flag used by DebugTerminal to indicate that the next PID calculation with this index should be displayed
|
||||
|
||||
// System Timers
|
||||
// --------------
|
||||
unsigned long fast_loopTimer; // Time in miliseconds of main control loop
|
||||
unsigned long fast_loopTimeStamp = 0; // Time Stamp when fast loop was complete
|
||||
unsigned long medium_loopTimer; // Time in miliseconds of navigation control loop
|
||||
byte medium_loopCounter = 0; // Counters for branching from main control loop to slower loops
|
||||
byte slow_loopCounter = 0;
|
||||
byte superslow_loopCounter = 0;
|
||||
unsigned long deltaMiliSeconds; // Delta Time in miliseconds
|
||||
unsigned long dTnav; // Delta Time in milliseconds for navigation computations
|
||||
int mainLoop_count;
|
||||
unsigned long elapsedTime; // for doing custom events
|
||||
unsigned long GPS_timer;
|
||||
float load; // % MCU cycles used
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Top-level logic
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
void setup() {
|
||||
|
||||
init_ardupilot();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// We want this to execute at 50Hz if possible
|
||||
// -------------------------------------------
|
||||
if (millis()-fast_loopTimer > 19) {
|
||||
deltaMiliSeconds = millis() - fast_loopTimer;
|
||||
load = float(fast_loopTimeStamp - fast_loopTimer)/deltaMiliSeconds;
|
||||
G_Dt = (float)deltaMiliSeconds / 1000.f;
|
||||
fast_loopTimer = millis();
|
||||
|
||||
mainLoop_count++;
|
||||
|
||||
// Execute the fast loop
|
||||
// ---------------------
|
||||
fast_loop();
|
||||
|
||||
// Execute the medium loop
|
||||
// -----------------------
|
||||
medium_loop();
|
||||
|
||||
if (millis()- perf_mon_timer > 20000) {
|
||||
if (mainLoop_count != 0) {
|
||||
gcs.send_message(MSG_PERF_REPORT);
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_PM)
|
||||
Log_Write_Performance();
|
||||
|
||||
resetPerfData();
|
||||
}
|
||||
}
|
||||
fast_loopTimeStamp = millis();
|
||||
}
|
||||
}
|
||||
|
||||
void fast_loop()
|
||||
{
|
||||
// This is the fast loop - we want it to execute at 50Hz if possible
|
||||
// -----------------------------------------------------------------
|
||||
if (deltaMiliSeconds > G_Dt_max)
|
||||
G_Dt_max = deltaMiliSeconds;
|
||||
|
||||
// Read radio
|
||||
// ----------
|
||||
read_radio();
|
||||
|
||||
// check for throtle failsafe condition
|
||||
// ------------------------------------
|
||||
//if (get(PARAM_THR_FAILSAFE))
|
||||
//set_failsafe(ch3_failsafe);
|
||||
|
||||
// Read Airspeed
|
||||
// -------------
|
||||
# if AIRSPEED_SENSOR == 1 && HIL_MODE != HIL_MODE_ATTITUDE
|
||||
//read_airspeed();
|
||||
# endif
|
||||
|
||||
//dcm.update_DCM(G_Dt);
|
||||
|
||||
# if HIL_MODE == HIL_MODE_DISABLED
|
||||
//if (get(PARAM_LOG_BITMASK) & MASK_LOG_ATTITUDE_FAST)
|
||||
//Log_Write_Attitude((int)dcm.roll_sensor, (int)dcm.pitch_sensor, (uint16_t)dcm.yaw_sensor);
|
||||
|
||||
//if (get(PARAM_LOG_BITMASK) & MASK_LOG_RAW)
|
||||
//Log_Write_Raw();
|
||||
#endif // HIL_MODE
|
||||
|
||||
// altitude smoothing
|
||||
// ------------------
|
||||
//if (control_mode != FLY_BY_WIRE_B)
|
||||
//calc_altitude_error();
|
||||
|
||||
// inertial navigation
|
||||
// ------------------
|
||||
#if INERTIAL_NAVIGATION == ENABLED
|
||||
// TODO: implement inertial nav function
|
||||
//inertialNavigation();
|
||||
#endif
|
||||
|
||||
// custom code/exceptions for flight modes
|
||||
// ---------------------------------------
|
||||
//update_current_flight_mode();
|
||||
|
||||
// apply desired roll, pitch and yaw to the plane
|
||||
// ----------------------------------------------
|
||||
//if (control_mode > MANUAL)
|
||||
//stabilize();
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
|
||||
|
||||
// XXX is it appropriate to be doing the comms below on the fast loop?
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
// kick the HIL to process incoming sensor packets
|
||||
hil.update();
|
||||
// send out hil data
|
||||
hil.send_message(MSG_SERVO_OUT);
|
||||
//hil.send_message(MSG_ATTITUDE);
|
||||
//hil.send_message(MSG_LOCATION);
|
||||
//hil.send_message(MSG_AIRSPEED);
|
||||
#endif
|
||||
|
||||
// kick the GCS to process uplink data
|
||||
gcs.update();
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
gcs.data_stream_send(45,1000);
|
||||
#endif
|
||||
// XXX this should be absorbed into the above,
|
||||
// or be a "GCS fast loop" interface
|
||||
}
|
||||
|
||||
void medium_loop()
|
||||
{
|
||||
// This is the start of the medium (10 Hz) loop pieces
|
||||
// -----------------------------------------
|
||||
switch(medium_loopCounter) {
|
||||
|
||||
// This case deals with the GPS
|
||||
//-------------------------------
|
||||
case 0:
|
||||
medium_loopCounter++;
|
||||
update_GPS();
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE && MAGNETOMETER == 1
|
||||
//compass.read(); // Read magnetometer
|
||||
//compass.calculate(dcm.roll,dcm.pitch); // Calculate heading
|
||||
#endif
|
||||
|
||||
break;
|
||||
|
||||
// This case performs some navigation computations
|
||||
//------------------------------------------------
|
||||
case 1:
|
||||
medium_loopCounter++;
|
||||
|
||||
|
||||
if(gps.new_data){
|
||||
dTnav = millis() - medium_loopTimer;
|
||||
medium_loopTimer = millis();
|
||||
}
|
||||
|
||||
// calculate the plane's desired bearing
|
||||
// -------------------------------------
|
||||
//navigate();
|
||||
break;
|
||||
|
||||
// command processing
|
||||
//------------------------------
|
||||
case 2:
|
||||
medium_loopCounter++;
|
||||
|
||||
// perform next command
|
||||
// --------------------
|
||||
//update_commands();
|
||||
break;
|
||||
|
||||
// This case deals with sending high rate telemetry
|
||||
//-------------------------------------------------
|
||||
case 3:
|
||||
medium_loopCounter++;
|
||||
|
||||
//if ((get(PARAM_LOG_BITMASK) & MASK_LOG_ATTITUDE_MED) && !(get(PARAM_LOG_BITMASK) & MASK_LOG_ATTITUDE_FAST))
|
||||
//Log_Write_Attitude((int)dcm.roll_sensor, (int)dcm.pitch_sensor, (uint16_t)dcm.yaw_sensor);
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
//if (get(PARAM_LOG_BITMASK) & MASK_LOG_CTUN)
|
||||
//Log_Write_Control_Tuning();
|
||||
#endif
|
||||
|
||||
//if (get(PARAM_LOG_BITMASK) & MASK_LOG_NTUN)
|
||||
//Log_Write_Nav_Tuning();
|
||||
|
||||
//if (get(PARAM_LOG_BITMASK) & MASK_LOG_GPS)
|
||||
//Log_Write_GPS(gps.time, current_loc.lat, current_loc.lng, gps.altitude, current_loc.alt, (long) gps.ground_speed, gps.ground_course, gps.fix, gps.num_sats);
|
||||
|
||||
// XXX this should be a "GCS medium loop" interface
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
gcs.data_stream_send(5,45);
|
||||
// send all requested output streams with rates requested
|
||||
// between 5 and 45 Hz
|
||||
#else
|
||||
//gcs.send_message(MSG_ATTITUDE); // Sends attitude data
|
||||
#endif
|
||||
break;
|
||||
|
||||
// This case controls the slow loop
|
||||
//---------------------------------
|
||||
case 4:
|
||||
medium_loopCounter=0;
|
||||
slow_loop();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void slow_loop()
|
||||
{
|
||||
// This is the slow (3 1/3 Hz) loop pieces
|
||||
//----------------------------------------
|
||||
switch (slow_loopCounter){
|
||||
case 0:
|
||||
slow_loopCounter++;
|
||||
|
||||
|
||||
|
||||
|
||||
superslow_loopCounter++;
|
||||
//if(superslow_loopCounter >=15) {
|
||||
// keep track of what page is in use in the log
|
||||
// *** We need to come up with a better scheme to handle this...
|
||||
//eeprom_write_word((uint16_t *) EE_LAST_LOG_PAGE, DataFlash.GetWritePage());
|
||||
//superslow_loopCounter = 0;
|
||||
//}
|
||||
break;
|
||||
|
||||
case 1:
|
||||
slow_loopCounter++;
|
||||
|
||||
// Read 3-position switch on radio
|
||||
// -------------------------------
|
||||
read_control_switch();
|
||||
|
||||
// Read Control Surfaces/Mix switches
|
||||
// ----------------------------------
|
||||
if(reverse_switch){
|
||||
update_servo_switches();
|
||||
}
|
||||
|
||||
// Read main battery voltage if hooked up - does not read the 5v from radio
|
||||
// ------------------------------------------------------------------------
|
||||
#if BATTERY_EVENT == 1
|
||||
read_battery();
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
// Read Baro pressure
|
||||
// ------------------
|
||||
//read_airpressure();
|
||||
#endif
|
||||
|
||||
break;
|
||||
|
||||
case 2:
|
||||
slow_loopCounter = 0;
|
||||
//update_events();
|
||||
|
||||
// XXX this should be a "GCS slow loop" interface
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
gcs.data_stream_send(1,5);
|
||||
// send all requested output streams with rates requested
|
||||
// between 1 and 5 Hz
|
||||
#else
|
||||
//gcs.send_message(MSG_LOCATION);
|
||||
#endif
|
||||
// send a heartbeat
|
||||
gcs.send_message(MSG_HEARTBEAT); // XXX This is running at 3 1/3 Hz
|
||||
//but should be at 1 Hz, new loop timer?
|
||||
// display load
|
||||
gcs.send_message(MSG_CPU_LOAD, load*100);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void update_GPS(void)
|
||||
{
|
||||
if(gps.status() == 0)
|
||||
{
|
||||
gps.init(); // reinitialize dead connections
|
||||
return; // let it warm up while other stuff is running
|
||||
}
|
||||
gps.update();
|
||||
update_GPS_light();
|
||||
|
||||
if (gps.new_data && gps.fix) {
|
||||
GPS_timer = millis();
|
||||
// XXX We should be sending GPS data off one of the regular loops so that we send
|
||||
// no-GPS-fix data too
|
||||
#if GCS_PROTOCOL != GCS_PROTOCOL_MAVLINK
|
||||
gcs.send_message(MSG_LOCATION);
|
||||
#endif
|
||||
|
||||
// for performance
|
||||
// ---------------
|
||||
gps_fix_count++;
|
||||
|
||||
if(ground_start_count > 1){
|
||||
ground_start_count--;
|
||||
ground_start_avg += gps.ground_speed;
|
||||
|
||||
} else if (ground_start_count == 1) {
|
||||
// We countdown N number of good GPS fixes
|
||||
// so that the altitude is more accurate
|
||||
// -------------------------------------
|
||||
if (current_loc.lat == 0) {
|
||||
SendDebugln("!! bad loc");
|
||||
ground_start_count = 5;
|
||||
|
||||
} else {
|
||||
if(ENABLE_AIR_START == 1 && (ground_start_avg / 5) < SPEEDFILT){
|
||||
startup_ground();
|
||||
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_CMD)
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
|
||||
init_home();
|
||||
} else if (ENABLE_AIR_START == 0) {
|
||||
init_home();
|
||||
}
|
||||
|
||||
ground_start_count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
current_loc.lng = gps.longitude; // Lon * 10**7
|
||||
current_loc.lat = gps.latitude; // Lat * 10**7
|
||||
|
||||
// XXX this is bogus; should just force get(PARAM_ALT_MIX) to zero for GPS_PROTOCOL_IMU
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
current_loc.alt = gps.altitude;
|
||||
#else
|
||||
current_loc.alt = ((1 - get(PARAM_ALT_MIX)) * gps.altitude) + (get(PARAM_ALT_MIX) * press_alt); // alt_MSL centimeters (meters * 100)
|
||||
#endif
|
||||
|
||||
// Calculate new climb rate
|
||||
add_altitude_data(millis()/100, gps.altitude/10);
|
||||
|
||||
COGX = cos(ToRad(gps.ground_course/100.0));
|
||||
COGY = sin(ToRad(gps.ground_course/100.0));
|
||||
}
|
||||
}
|
||||
|
||||
void update_current_flight_mode(void)
|
||||
{
|
||||
if(control_mode == AUTO){
|
||||
crash_checker();
|
||||
|
||||
switch(command_must_ID){
|
||||
case CMD_TAKEOFF:
|
||||
if (hold_course > -1) {
|
||||
calc_nav_roll();
|
||||
} else {
|
||||
nav_roll = 0;
|
||||
}
|
||||
|
||||
#if AIRSPEED_SENSOR == ENABLED
|
||||
calc_nav_pitch();
|
||||
if (nav_pitch < (long)takeoff_pitch) nav_pitch = (long)takeoff_pitch;
|
||||
#else
|
||||
nav_pitch = (long)((float)gps.ground_speed / (float)get(PARAM_TRIM_AIRSPEED) * (float)takeoff_pitch * 0.5);
|
||||
nav_pitch = constrain(nav_pitch, 500l, (long)takeoff_pitch);
|
||||
#endif
|
||||
|
||||
|
||||
servo_out[CH_THROTTLE] = get(PARAM_THR_MAX); //TODO: Replace with THROTTLE_TAKEOFF or other method of controlling throttle
|
||||
// What is the case for doing something else? Why wouldn't you want max throttle for TO?
|
||||
// ******************************
|
||||
|
||||
break;
|
||||
|
||||
case CMD_LAND:
|
||||
calc_nav_roll();
|
||||
|
||||
#if AIRSPEED_SENSOR == ENABLED
|
||||
calc_nav_pitch();
|
||||
calc_throttle();
|
||||
#else
|
||||
calc_nav_pitch(); // calculate nav_pitch just to use for calc_throttle
|
||||
calc_throttle(); // throttle based on altitude error
|
||||
nav_pitch = landing_pitch; // pitch held constant
|
||||
#endif
|
||||
|
||||
if (land_complete) {
|
||||
servo_out[CH_THROTTLE] = 0;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
hold_course = -1;
|
||||
calc_nav_roll();
|
||||
calc_nav_pitch();
|
||||
calc_throttle();
|
||||
break;
|
||||
}
|
||||
}else{
|
||||
switch(control_mode){
|
||||
case RTL:
|
||||
case LOITER:
|
||||
hold_course = -1;
|
||||
crash_checker();
|
||||
calc_nav_roll();
|
||||
calc_nav_pitch();
|
||||
calc_throttle();
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_A:
|
||||
// fake Navigation output using sticks
|
||||
nav_roll = ((radio_in[CH_ROLL] - radio_trim(CH_ROLL)) *
|
||||
get(PARAM_LIM_ROLL) * reverse_roll) / 350;
|
||||
nav_pitch = ((radio_in[CH_PITCH] - radio_trim(CH_PITCH)) *
|
||||
3500l * reverse_pitch) / 350;
|
||||
nav_roll = constrain(nav_roll, -get(PARAM_LIM_ROLL), get(PARAM_LIM_ROLL));
|
||||
nav_pitch = constrain(nav_pitch, -3000, 3000); // trying to give more pitch authority
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_B:
|
||||
// fake Navigation output using sticks
|
||||
// We use get(PARAM_PITCH_MIN) because its magnitude is
|
||||
// normally greater than get(PARAM_get(PARAM_PITCH_MAX))
|
||||
nav_roll = ((radio_in[CH_ROLL] - radio_trim(CH_ROLL))
|
||||
* get(PARAM_LIM_ROLL) * reverse_roll) / 350;
|
||||
altitude_error = ((radio_in[CH_PITCH] - radio_trim(CH_PITCH))
|
||||
* get(PARAM_LIM_PITCH_MIN) * -reverse_pitch) / 350;
|
||||
nav_roll = constrain(nav_roll, -get(PARAM_LIM_ROLL), get(PARAM_LIM_ROLL));
|
||||
|
||||
#if AIRSPEED_SENSOR == ENABLED
|
||||
airspeed_error = ((int)(get(PARAM_ARSPD_FBW_MAX) -
|
||||
get(PARAM_ARSPD_FBW_MIN)) *
|
||||
servo_out[CH_THROTTLE]) +
|
||||
((int)get(PARAM_ARSPD_FBW_MIN) * 100);
|
||||
// Intermediate calculation - airspeed_error is just desired airspeed at this point
|
||||
airspeed_energy_error = (long)(((long)airspeed_error *
|
||||
(long)airspeed_error) -
|
||||
((long)airspeed * (long)airspeed))/20000;
|
||||
//Changed 0.00005f * to / 20000 to avoid floating point calculation
|
||||
airspeed_error = (airspeed_error - airspeed);
|
||||
#endif
|
||||
|
||||
calc_throttle();
|
||||
calc_nav_pitch();
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
nav_roll = 0;
|
||||
nav_pitch = 0;
|
||||
// throttle is passthrough
|
||||
break;
|
||||
|
||||
case CIRCLE:
|
||||
// we have no GPS installed and have lost radio contact
|
||||
// or we just want to fly around in a gentle circle w/o GPS
|
||||
// ----------------------------------------------------
|
||||
nav_roll = get(PARAM_LIM_ROLL) / 3;
|
||||
nav_pitch = 0;
|
||||
|
||||
if (failsafe == true){
|
||||
servo_out[CH_THROTTLE] = get(PARAM_TRIM_THROTTLE);
|
||||
}
|
||||
break;
|
||||
|
||||
case MANUAL:
|
||||
// servo_out is for Sim control only
|
||||
// ---------------------------------
|
||||
servo_out[CH_ROLL] = reverse_roll * (radio_in[CH_ROLL] - radio_trim(CH_ROLL)) * 9;
|
||||
servo_out[CH_PITCH] = reverse_pitch * (radio_in[CH_PITCH] - radio_trim(CH_PITCH)) * 9;
|
||||
servo_out[CH_RUDDER] = reverse_rudder * (radio_in[CH_RUDDER] - radio_trim(CH_RUDDER)) * 9;
|
||||
break;
|
||||
//roll: -13788.000, pitch: -13698.000, thr: 0.000, rud: -13742.000
|
||||
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,380 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
//****************************************************************
|
||||
// Function that controls aileron/rudder, elevator, rudder (if 4 channel control) and throttle to produce desired attitude and airspeed.
|
||||
//****************************************************************
|
||||
|
||||
void stabilize()
|
||||
{
|
||||
float ch1_inf = 1.0;
|
||||
float ch2_inf = 1.0;
|
||||
float ch4_inf = 1.0;
|
||||
#if AIRSPEED_SENSOR == ENABLED
|
||||
float speed_scaler = STANDARD_SPEED_SQUARED / (airspeed * airspeed);
|
||||
speed_scaler = constrain(speed_scaler, 0.11, 9.0);
|
||||
#endif
|
||||
#if AIRSPEED_SENSOR == DISABLED
|
||||
float speed_scaler;
|
||||
if (servo_out[CH_THROTTLE] > 0)
|
||||
speed_scaler = 0.5 + (THROTTLE_CRUISE / servo_out[CH_THROTTLE] / 2.0); // First order taylor expansion of square root
|
||||
// Should maybe be to the 2/7 power, but we aren't goint to implement that...
|
||||
else
|
||||
speed_scaler = 1.67;
|
||||
speed_scaler = constrain(speed_scaler, 0.6, 1.67); // This case is constrained tighter as we don't have real speed info
|
||||
#endif
|
||||
|
||||
|
||||
if(crash_timer > 0){
|
||||
nav_roll = 0;
|
||||
}
|
||||
|
||||
// For Testing Only
|
||||
// roll_sensor = (radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 10;
|
||||
// Serial.print(" roll_sensor ");
|
||||
// Serial.print(roll_sensor,DEC);
|
||||
|
||||
// Calculate dersired servo output for the roll
|
||||
// ---------------------------------------------
|
||||
servo_out[CH_ROLL] = pidServoRoll.get_pid((nav_roll - dcm.roll_sensor), deltaMiliSeconds, speed_scaler);
|
||||
servo_out[CH_PITCH] = pidServoPitch.get_pid((nav_pitch + fabs(dcm.roll_sensor * get(PARAM_KFF_PTCHCOMP)) - (dcm.pitch_sensor - get(PARAM_TRIM_PITCH))), deltaMiliSeconds, speed_scaler);
|
||||
//Serial.print(" servo_out[CH_ROLL] ");
|
||||
//Serial.print(servo_out[CH_ROLL],DEC);
|
||||
|
||||
// Mix Stick input to allow users to override control surfaces
|
||||
// -----------------------------------------------------------
|
||||
if ((control_mode < FLY_BY_WIRE_A) || (ENABLE_STICK_MIXING == 1 && control_mode > FLY_BY_WIRE_B)) {
|
||||
|
||||
ch1_inf = (float)radio_in[CH_ROLL] - (float)radio_trim(CH_ROLL);
|
||||
ch1_inf = fabs(ch1_inf);
|
||||
ch1_inf = min(ch1_inf, 400.0);
|
||||
ch1_inf = ((400.0 - ch1_inf) /400.0);
|
||||
|
||||
ch2_inf = (float)radio_in[CH_PITCH] - radio_trim(CH_PITCH);
|
||||
ch2_inf = fabs(ch2_inf);
|
||||
ch2_inf = min(ch2_inf, 400.0);
|
||||
ch2_inf = ((400.0 - ch2_inf) /400.0);
|
||||
|
||||
// scale the sensor input based on the stick input
|
||||
// -----------------------------------------------
|
||||
servo_out[CH_ROLL] *= ch1_inf;
|
||||
servo_out[CH_PITCH] *= ch2_inf;
|
||||
|
||||
// Mix in stick inputs
|
||||
// -------------------
|
||||
servo_out[CH_ROLL] += reverse_roll * (radio_in[CH_ROLL] - radio_trim(CH_ROLL)) * 9;
|
||||
servo_out[CH_PITCH] += reverse_pitch * (radio_in[CH_PITCH] - radio_trim(CH_PITCH)) * 9;
|
||||
|
||||
//Serial.print(" servo_out[CH_ROLL] ");
|
||||
//Serial.println(servo_out[CH_ROLL],DEC);
|
||||
}
|
||||
|
||||
// stick mixing performed for rudder for all cases including FBW unless disabled for higher modes
|
||||
// important for steering on the ground during landing
|
||||
// -----------------------------------------------
|
||||
if (control_mode <= FLY_BY_WIRE_B || ENABLE_STICK_MIXING == 1) {
|
||||
ch4_inf = (float)radio_in[CH_RUDDER] - (float)radio_trim(CH_RUDDER);
|
||||
ch4_inf = fabs(ch4_inf);
|
||||
ch4_inf = min(ch4_inf, 400.0);
|
||||
ch4_inf = ((400.0 - ch4_inf) /400.0);
|
||||
}
|
||||
|
||||
// Apply output to Rudder
|
||||
// ----------------------
|
||||
calc_nav_yaw(speed_scaler);
|
||||
servo_out[CH_RUDDER] *= ch4_inf;
|
||||
servo_out[CH_RUDDER] += reverse_rudder * (radio_in[CH_RUDDER] - radio_trim(CH_RUDDER)) * 9;
|
||||
|
||||
// Call slew rate limiter if used
|
||||
// ------------------------------
|
||||
//#if(ROLL_SLEW_LIMIT != 0)
|
||||
// servo_out[CH_ROLL] = roll_slew_limit(servo_out[CH_ROLL]);
|
||||
//#endif
|
||||
}
|
||||
|
||||
void crash_checker()
|
||||
{
|
||||
if(dcm.pitch_sensor < -4500){
|
||||
crash_timer = 255;
|
||||
}
|
||||
if(crash_timer > 0)
|
||||
crash_timer--;
|
||||
}
|
||||
|
||||
|
||||
#if AIRSPEED_SENSOR == DISABLED
|
||||
void calc_throttle()
|
||||
{
|
||||
int throttle_target = get(PARAM_TRIM_THROTTLE) + throttle_nudge;
|
||||
|
||||
// no airspeed sensor, we use nav pitch to determine the proper throttle output
|
||||
// AUTO, RTL, etc
|
||||
// ---------------------------------------------------------------------------
|
||||
if (nav_pitch >= 0) {
|
||||
servo_out[CH_THROTTLE] = throttle_target + (get(PARAM_THR_MAX) - throttle_target) * nav_pitch / get(PARAM_LIM_PITCH_MAX);
|
||||
} else {
|
||||
servo_out[CH_THROTTLE] = throttle_target - (throttle_target - get(PARAM_THR_MIN)) * nav_pitch / get(PARAM_LIM_PITCH_MIN);
|
||||
}
|
||||
|
||||
servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], get(PARAM_THR_MIN), get(PARAM_THR_MAX));
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AIRSPEED_SENSOR == ENABLED
|
||||
void calc_throttle()
|
||||
{
|
||||
// throttle control with airspeed compensation
|
||||
// -------------------------------------------
|
||||
energy_error = airspeed_energy_error + (float)altitude_error * 0.098f;
|
||||
|
||||
// positive energy errors make the throttle go higher
|
||||
servo_out[CH_THROTTLE] = get(PARAM_TRIM_THROTTLE) + pidTeThrottle.get_pid(energy_error, dTnav);
|
||||
servo_out[CH_THROTTLE] = max(servo_out[CH_THROTTLE], 0);
|
||||
|
||||
// are we going too slow? up the throttle to get some more groundspeed
|
||||
// move into PID loop in the future
|
||||
// lower the contstant value to limit the effect : 50 = default
|
||||
|
||||
//JASON - We really should change this to act on airspeed in this case. Let's visit about it....
|
||||
/*int gs_boost = 30 * (1.0 - ((float)gps.ground_speed / (float)airspeed_cruise));
|
||||
gs_boost = max(0,gs_boost);
|
||||
servo_out[CH_THROTTLE] += gs_boost;*/
|
||||
servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE],
|
||||
get(PARAM_THR_MIN), get(PARAM_THR_MAX));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
/*****************************************
|
||||
* Calculate desired roll/pitch/yaw angles (in medium freq loop)
|
||||
*****************************************/
|
||||
|
||||
// Yaw is separated into a function for future implementation of heading hold on rolling take-off
|
||||
// ----------------------------------------------------------------------------------------
|
||||
void calc_nav_yaw(float speed_scaler)
|
||||
{
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
Vector3f temp = imu.get_accel();
|
||||
long error = -temp.y;
|
||||
|
||||
// Control is a feedforward from the aileron control + a PID to coordinate the turn (drive y axis accel to zero)
|
||||
servo_out[CH_RUDDER] = get(PARAM_KFF_RDDRMIX) * servo_out[CH_ROLL] + pidServoRudder.get_pid(error, deltaMiliSeconds, speed_scaler);
|
||||
#else
|
||||
servo_out[CH_RUDDER] = get(PARAM_KFF_RDDRMIX) * servo_out[CH_ROLL];
|
||||
// XXX probably need something here based on heading
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void calc_nav_pitch()
|
||||
{
|
||||
// Calculate the Pitch of the plane
|
||||
// --------------------------------
|
||||
#if AIRSPEED_SENSOR == ENABLED
|
||||
nav_pitch = -pidNavPitchAirspeed.get_pid(airspeed_error, dTnav);
|
||||
#else
|
||||
nav_pitch = pidNavPitchAltitude.get_pid(altitude_error, dTnav);
|
||||
#endif
|
||||
nav_pitch = constrain(nav_pitch, get(PARAM_LIM_PITCH_MIN), get(PARAM_LIM_PITCH_MAX));
|
||||
}
|
||||
|
||||
|
||||
void calc_nav_roll()
|
||||
{
|
||||
|
||||
// Adjust gain based on ground speed - We need lower nav gain going in to a headwind, etc.
|
||||
// This does not make provisions for wind speed in excess of airframe speed
|
||||
nav_gain_scaler = (float)gps.ground_speed / (STANDARD_SPEED * 100.0);
|
||||
nav_gain_scaler = constrain(nav_gain_scaler, 0.2, 1.4);
|
||||
|
||||
// negative error = left turn
|
||||
// positive error = right turn
|
||||
// Calculate the required roll of the plane
|
||||
// ----------------------------------------
|
||||
nav_roll = pidNavRoll.get_pid(bearing_error, dTnav, nav_gain_scaler); //returns desired bank angle in degrees*100
|
||||
nav_roll = constrain(nav_roll,-get(PARAM_LIM_ROLL), get(PARAM_LIM_ROLL));
|
||||
|
||||
}
|
||||
|
||||
|
||||
/*****************************************
|
||||
* Roll servo slew limit
|
||||
*****************************************/
|
||||
/*
|
||||
float roll_slew_limit(float servo)
|
||||
{
|
||||
static float last;
|
||||
float temp = constrain(servo, last-ROLL_SLEW_LIMIT * deltaMiliSeconds/1000.f, last + ROLL_SLEW_LIMIT * deltaMiliSeconds/1000.f);
|
||||
last = servo;
|
||||
return temp;
|
||||
}*/
|
||||
|
||||
/*****************************************
|
||||
* Throttle slew limit
|
||||
*****************************************/
|
||||
/*float throttle_slew_limit(float throttle)
|
||||
{
|
||||
static float last;
|
||||
float temp = constrain(throttle, last-THROTTLE_SLEW_LIMIT * deltaMiliSeconds/1000.f, last + THROTTLE_SLEW_LIMIT * deltaMiliSeconds/1000.f);
|
||||
last = throttle;
|
||||
return temp;
|
||||
}
|
||||
*/
|
||||
|
||||
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.
|
||||
// Keeps outdated data out of our calculations
|
||||
void reset_I(void)
|
||||
{
|
||||
pidNavRoll.reset_I();
|
||||
pidNavPitchAirspeed.reset_I();
|
||||
pidNavPitchAltitude.reset_I();
|
||||
pidTeThrottle.reset_I();
|
||||
pidAltitudeThrottle.reset_I();
|
||||
}
|
||||
|
||||
/*****************************************
|
||||
* Set the flight control servos based on the current calculated values
|
||||
*****************************************/
|
||||
void set_servos_4(void)
|
||||
{
|
||||
if(control_mode == MANUAL){
|
||||
// do a direct pass through of radio values
|
||||
for(int y=0; y<4; y++) {
|
||||
radio_out[y] = radio_in[y];
|
||||
}
|
||||
|
||||
} else {
|
||||
// Patch Antenna Control Code
|
||||
float phi, theta; //,servo_phi, servo_theta;
|
||||
float x1,x2,y1,y2,x,y,r,z;
|
||||
|
||||
y1 = 110600*current_loc.lat/t7;
|
||||
x1 = (PI/180)*6378137*(cos(atan(0.99664719*tan(current_loc.lat/t7*PI/180))))*(current_loc.lng/t7);
|
||||
|
||||
y2 = 110600*trackVehicle_loc.lat/t7;
|
||||
x2 = (PI/180)*6378137*(cos(atan(0.99664719*tan(current_loc.lat/t7*PI/180))))*(trackVehicle_loc.lng/t7);
|
||||
|
||||
x = abs(x2 - x1);
|
||||
y = abs(y2 - y1);
|
||||
|
||||
r = sqrt(x*x+y*y);
|
||||
z = trackVehicle_loc.alt/100.0 - current_loc.alt;
|
||||
|
||||
phi = (atan(z/r)*180/PI);
|
||||
theta = (atan(x/y)*180/PI);
|
||||
// Check to see which quadrant of the angle
|
||||
|
||||
if (trackVehicle_loc.lat >= current_loc.lat && trackVehicle_loc.lng >= current_loc.lng)
|
||||
{
|
||||
theta = abs(theta);
|
||||
}
|
||||
else if (trackVehicle_loc.lat >= current_loc.lat && trackVehicle_loc.lng <= current_loc.lng)
|
||||
{
|
||||
theta = 360 - abs(theta);
|
||||
}
|
||||
else if (trackVehicle_loc.lat <= current_loc.lat && trackVehicle_loc.lng >= current_loc.lng)
|
||||
{
|
||||
theta = 180 - abs(theta);
|
||||
}
|
||||
else if (trackVehicle_loc.lat <= current_loc.lat && trackVehicle_loc.lng <= current_loc.lng)
|
||||
{
|
||||
theta = 180 + abs(theta);
|
||||
}
|
||||
|
||||
// Calibration of the top servo
|
||||
//servo_phi = (91*phi + 7650)/9;
|
||||
|
||||
// Calibration of the bottom servo
|
||||
//servo_theta = (2*theta + 5940)/3;
|
||||
|
||||
|
||||
Serial.print("target lat: "); Serial.println(current_loc.lat);
|
||||
Serial.print("tracker lat: "); Serial.println(trackVehicle_loc.lat);
|
||||
Serial.print("phi: "); Serial.println(phi);
|
||||
Serial.print("theta: "); Serial.println(theta);
|
||||
|
||||
// Outputing to the servos
|
||||
servo_out[CH_ROLL] = 10000*phi/90.0;
|
||||
servo_out[CH_PITCH] = 10000*theta/360.0;
|
||||
servo_out[CH_RUDDER] = 0;
|
||||
servo_out[CH_THROTTLE] = 0;
|
||||
|
||||
radio_out[CH_ROLL] = radio_trim(CH_ROLL) + (reverse_roll * ((float)servo_out[CH_ROLL] * 0.11111));
|
||||
radio_out[CH_PITCH] = radio_trim(CH_PITCH) + (reverse_pitch * ((float)servo_out[CH_PITCH] * 0.11111));
|
||||
radio_out[CH_RUDDER] = 0;
|
||||
radio_out[CH_THROTTLE] = 0;
|
||||
|
||||
/*
|
||||
if (mix_mode == 0){
|
||||
radio_out[CH_ROLL] = radio_trim(CH_ROLL) + (reverse_roll * ((float)servo_out[CH_ROLL] * 0.11111));
|
||||
radio_out[CH_PITCH] = radio_trim(CH_PITCH) + (reverse_pitch * ((float)servo_out[CH_PITCH] * 0.11111));
|
||||
radio_out[CH_RUDDER] = radio_trim(CH_RUDDER) + (reverse_rudder * ((float)servo_out[CH_RUDDER] * 0.11111));
|
||||
}else{
|
||||
//Elevon mode
|
||||
float ch1;
|
||||
float ch2;
|
||||
ch1 = reverse_elevons * (servo_out[CH_PITCH] - servo_out[CH_ROLL]);
|
||||
ch2 = servo_out[CH_PITCH] + servo_out[CH_ROLL];
|
||||
radio_out[CH_ROLL] = elevon1_trim + (reverse_ch1_elevon * (ch1 * 0.11111));
|
||||
radio_out[CH_PITCH] = elevon2_trim + (reverse_ch2_elevon * (ch2 * 0.11111));
|
||||
}
|
||||
|
||||
#if THROTTLE_OUT == 0
|
||||
radio_out[CH_THROTTLE] = 0;
|
||||
#endif
|
||||
|
||||
|
||||
// convert 0 to 100% into PWM
|
||||
servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100);
|
||||
radio_out[CH_THROTTLE] = servo_out[CH_THROTTLE] * ((radio_max(CH_THROTTLE) - radio_min(CH_THROTTLE)) / 100);
|
||||
radio_out[CH_THROTTLE] += radio_min(CH_THROTTLE);
|
||||
|
||||
//Radio_in: 1763 PWM output: 2000 Throttle: 78.7695999145 PWM Min: 1110 PWM Max: 1938
|
||||
|
||||
#if THROTTLE_REVERSE == 1
|
||||
radio_out[CH_THROTTLE] = radio_max(CH_THROTTLE) + radio_min(CH_THROTTLE) - radio_out[CH_THROTTLE];
|
||||
#endif
|
||||
*/
|
||||
}
|
||||
|
||||
// send values to the PWM timers for output
|
||||
// ----------------------------------------
|
||||
for(int y=0; y<4; y++) {
|
||||
APM_RC.OutputCh(y, radio_out[y]); // send to Servos
|
||||
}
|
||||
}
|
||||
|
||||
void demo_servos(byte i) {
|
||||
|
||||
while(i > 0){
|
||||
gcs.send_text(SEVERITY_LOW,"Demo Servos!");
|
||||
APM_RC.OutputCh(1, 1400);
|
||||
delay(400);
|
||||
APM_RC.OutputCh(1, 1600);
|
||||
delay(200);
|
||||
APM_RC.OutputCh(1, 1500);
|
||||
delay(400);
|
||||
i--;
|
||||
}
|
||||
}
|
||||
|
||||
int readOutputCh(unsigned char ch)
|
||||
{
|
||||
int pwm;
|
||||
switch(ch)
|
||||
{
|
||||
case 0: pwm = OCR5B; break; // ch0
|
||||
case 1: pwm = OCR5C; break; // ch1
|
||||
case 2: pwm = OCR1B; break; // ch2
|
||||
case 3: pwm = OCR1C; break; // ch3
|
||||
case 4: pwm = OCR4C; break; // ch4
|
||||
case 5: pwm = OCR4B; break; // ch5
|
||||
case 6: pwm = OCR3C; break; // ch6
|
||||
case 7: pwm = OCR3B; break; // ch7
|
||||
case 8: pwm = OCR5A; break; // ch8, PL3
|
||||
case 9: pwm = OCR1A; break; // ch9, PB5
|
||||
case 10: pwm = OCR3A; break; // ch10, PE3
|
||||
}
|
||||
pwm >>= 1; // pwm / 2;
|
||||
return pwm;
|
||||
}
|
|
@ -0,0 +1,266 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file GCS.h
|
||||
/// @brief Interface definition for the various Ground Control System protocols.
|
||||
|
||||
#ifndef __GCS_H
|
||||
#define __GCS_H
|
||||
|
||||
#include <BetterStream.h>
|
||||
#include <AP_Common.h>
|
||||
#include <APM_BinComm.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <GPS.h>
|
||||
#include <Stream.h>
|
||||
#include <stdint.h>
|
||||
|
||||
///
|
||||
/// @class GCS
|
||||
/// @brief Class describing the interface between the APM code
|
||||
/// proper and the GCS implementation.
|
||||
///
|
||||
/// GCS' are currently implemented inside the sketch and as such have
|
||||
/// access to all global state. The sketch should not, however, call GCS
|
||||
/// internal functions - all calls to the GCS should be routed through
|
||||
/// this interface (or functions explicitly exposed by a subclass).
|
||||
///
|
||||
class GCS_Class
|
||||
{
|
||||
public:
|
||||
|
||||
/// Startup initialisation.
|
||||
///
|
||||
/// This routine performs any one-off initialisation required before
|
||||
/// GCS messages are exchanged.
|
||||
///
|
||||
/// @note The stream is expected to be set up and configured for the
|
||||
/// correct bitrate before ::init is called.
|
||||
///
|
||||
/// @note The stream is currently BetterStream so that we can use the _P
|
||||
/// methods; this may change if Arduino adds them to Print.
|
||||
///
|
||||
/// @param port The stream over which messages are exchanged.
|
||||
///
|
||||
void init(BetterStream *port) { _port = port; }
|
||||
|
||||
/// Update GCS state.
|
||||
///
|
||||
/// This may involve checking for received bytes on the stream,
|
||||
/// or sending additional periodic messages.
|
||||
void update(void) {}
|
||||
|
||||
/// Send a message with a single numeric parameter.
|
||||
///
|
||||
/// This may be a standalone message, or the GCS driver may
|
||||
/// have its own way of locating additional parameters to send.
|
||||
///
|
||||
/// @param id ID of the message to send.
|
||||
/// @param param Explicit message parameter.
|
||||
///
|
||||
void send_message(uint8_t id, int32_t param = 0) {}
|
||||
|
||||
/// Send a text message.
|
||||
///
|
||||
/// @param severity A value describing the importance of the message.
|
||||
/// @param str The text to be sent.
|
||||
///
|
||||
void send_text(uint8_t severity, const char *str) {}
|
||||
|
||||
/// Send acknowledgement for a message.
|
||||
///
|
||||
/// @param id The message ID being acknowledged.
|
||||
/// @param sum1 Checksum byte 1 from the message being acked.
|
||||
/// @param sum2 Checksum byte 2 from the message being acked.
|
||||
///
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) {}
|
||||
|
||||
/// Emit an update of the "current" waypoints, often previous, current and
|
||||
/// next.
|
||||
///
|
||||
void print_current_waypoints() {}
|
||||
|
||||
//
|
||||
// The following interfaces are not currently implemented as their counterparts
|
||||
// are not called in the mainline code. XXX ripe for re-specification.
|
||||
//
|
||||
|
||||
/// Send a text message with printf-style formatting.
|
||||
///
|
||||
/// @param severity A value describing the importance of the message.
|
||||
/// @param fmt The format string to send.
|
||||
/// @param ... Additional arguments to the format string.
|
||||
///
|
||||
// void send_message(uint8_t severity, const char *fmt, ...) {}
|
||||
|
||||
/// Log a waypoint
|
||||
///
|
||||
/// @param wp The waypoint to log.
|
||||
/// @param index The index of the waypoint.
|
||||
// void print_waypoint(struct Location *wp, uint8_t index) {}
|
||||
|
||||
// test if frequency within range requested for loop
|
||||
// used by data_stream_send
|
||||
static bool freqLoopMatch(uint16_t freq, uint16_t freqMin, uint16_t freqMax)
|
||||
{
|
||||
if (freq != 0 && freq >= freqMin && freq < freqMax) return true;
|
||||
else return false;
|
||||
}
|
||||
|
||||
// send streams which match frequency range
|
||||
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
|
||||
|
||||
protected:
|
||||
/// The stream we are communicating over
|
||||
BetterStream *_port;
|
||||
};
|
||||
|
||||
//
|
||||
// GCS class definitions.
|
||||
//
|
||||
// These are here so that we can declare the GCS object early in the sketch
|
||||
// and then reference it statically rather than via a pointer.
|
||||
//
|
||||
|
||||
///
|
||||
/// @class GCS_STANDARD
|
||||
/// @brief The default APM GCS protocol
|
||||
///
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_STANDARD
|
||||
class GCS_STANDARD : public GCS_Class
|
||||
{
|
||||
public:
|
||||
GCS_STANDARD(BinComm::MessageHandler GCS_MessageHandlers[]);
|
||||
|
||||
void update(void);
|
||||
void init(BetterStream *port);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
||||
BinComm & getBinComm(void) { return _binComm; }
|
||||
private:
|
||||
BinComm _binComm;
|
||||
};
|
||||
#endif // GCS_PROTOCOL_STANDARD
|
||||
|
||||
///
|
||||
/// @class GCS_MAVLINK
|
||||
/// @brief The mavlink protocol for qgroundcontrol
|
||||
///
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
class GCS_MAVLINK : public GCS_Class
|
||||
{
|
||||
public:
|
||||
GCS_MAVLINK();
|
||||
void update(void);
|
||||
void init(BetterStream *port);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
||||
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
|
||||
private:
|
||||
void handleMessage(mavlink_message_t * msg);
|
||||
mavlink_channel_t chan;
|
||||
uint16_t packet_drops;
|
||||
uint16_t rawSensorStreamRate;
|
||||
uint16_t attitudeStreamRate;
|
||||
uint16_t positionStreamRate;
|
||||
uint16_t rawControllerStreamRate;
|
||||
uint16_t rcStreamRate;
|
||||
uint16_t extraStreamRate[3];
|
||||
};
|
||||
#endif // GCS_PROTOCOL_MAVLINK
|
||||
|
||||
///
|
||||
/// @class GCS_LEGACY
|
||||
/// @brief Support for the legacy Ardupilot GCS
|
||||
///
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_LEGACY
|
||||
class GCS_LEGACY : public GCS_Class
|
||||
{
|
||||
public:
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
|
||||
private:
|
||||
void print_attitude(void);
|
||||
void print_control_mode(void);
|
||||
void print_position(void);
|
||||
void print_waypoint(struct Location *cmd,byte index);
|
||||
};
|
||||
#endif // GCS_PROTOTOL_LEGACY
|
||||
|
||||
///
|
||||
/// @class GCS_DEBUGTERMINAL
|
||||
/// @brief A GCS driver with an interactive management interface
|
||||
///
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_DEBUGTERMINAL
|
||||
class GCS_DEBUGTERMINAL : public GCS_Class
|
||||
{
|
||||
public:
|
||||
GCS_DEBUGTERMINAL() :
|
||||
report_command(1)
|
||||
{}
|
||||
|
||||
void update(void);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void print_current_waypoints(void);
|
||||
void print_commands();
|
||||
void print_PID(long PID_error, long dt, float scaler, float derivative, float integrator, float last_error);
|
||||
|
||||
private:
|
||||
char gcsinputbuffer[120]; // read buffer
|
||||
byte bufferidx;
|
||||
|
||||
// Reporting flags
|
||||
byte report_heartbeat;
|
||||
byte report_attitude;
|
||||
byte report_location;
|
||||
byte report_command;
|
||||
byte report_severity;
|
||||
byte first_location;
|
||||
byte report_cpu_load;
|
||||
|
||||
void processgcsinput(char c);
|
||||
void run_debugt_command(char *buf);
|
||||
static int strmatch(char* s1, const char* s2);
|
||||
static long readfloat(char* s, unsigned char* i);
|
||||
void process_set_cmd(char *buffer, int bufferlen);
|
||||
static int get_pid_offset_name(char *buffer, int *offset, unsigned char *length);
|
||||
void print_rlocation(Location *wp);
|
||||
void print_error(const char *msg);
|
||||
void print_position(void);
|
||||
void print_attitude(void);
|
||||
void print_new_wp_info();
|
||||
void print_control_mode(void);
|
||||
void print_tuning(void);
|
||||
void print_command(struct Location *cmd, byte index);
|
||||
void print_command_id(byte id);
|
||||
void print_gain(unsigned char g);
|
||||
void print_gains();
|
||||
void print_gain_keyword_error();
|
||||
void print_commands(unsigned char i1, unsigned char i2);
|
||||
};
|
||||
#endif // GCS_PROTOCOL_DEBUGTERMINAL
|
||||
|
||||
///
|
||||
/// @class GCS_XPLANE
|
||||
/// @brief GCS driver for HIL operation with the X-plane simulator
|
||||
///
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_XPLANE
|
||||
class GCS_XPLANE : public GCS_Class
|
||||
{
|
||||
public:
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void print_current_waypoints(void);
|
||||
|
||||
private:
|
||||
void print_control_mode(void);
|
||||
void print_waypoint(struct Location *wp, uint8_t index);
|
||||
void print_waypoints(void);
|
||||
};
|
||||
#endif // GCS_PROTOCOL_XPLANE
|
||||
|
||||
|
||||
#endif // __GCS_H
|
|
@ -0,0 +1,157 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
///
|
||||
/// @file GCS_Ardupilot.pde
|
||||
/// @brief GCS driver for the legacy Ardupilot GCS protocol.
|
||||
///
|
||||
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_LEGACY
|
||||
|
||||
/*
|
||||
Message Prefixes
|
||||
!!! Position Low rate telemetry
|
||||
+++ Attitude High rate telemetry
|
||||
### Mode Change in control mode
|
||||
%%% Waypoint Current and previous waypoints
|
||||
XXX Alert Text alert - NOTE: Alert message generation is not localized to a function
|
||||
PPP IMU Performance Sent every 20 seconds for performance monitoring
|
||||
|
||||
Message Suffix
|
||||
*** All messages use this suffix
|
||||
*/
|
||||
|
||||
void
|
||||
GCS_LEGACY::send_text(uint8_t severity, const char *str)
|
||||
{
|
||||
if(severity >= DEBUG_LEVEL){
|
||||
_port->print("MSG: ");
|
||||
_port->println(str);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_LEGACY::send_message(uint8_t id, uint32_t param)
|
||||
{
|
||||
switch(id) {
|
||||
case MSG_ATTITUDE: // ** Attitude message
|
||||
print_attitude();
|
||||
break;
|
||||
case MSG_LOCATION: // ** Location/GPS message
|
||||
print_position();
|
||||
break;
|
||||
case MSG_MODE_CHANGE:
|
||||
case MSG_HEARTBEAT: // ** Location/GPS message
|
||||
print_control_mode();
|
||||
break;
|
||||
case MSG_CPU_LOAD:
|
||||
//TODO: replace with appropriate message
|
||||
_port->printf_P(PSTR("MSG: load %ld%%\n"), param);
|
||||
break;
|
||||
//case MSG_PERF_REPORT:
|
||||
// printPerfData();
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_LEGACY::print_attitude(void)
|
||||
{
|
||||
_port->print("+++");
|
||||
_port->print("ASP:");
|
||||
_port->print((int)airspeed / 100, DEC);
|
||||
_port->print(",THH:");
|
||||
_port->print(servo_out[CH_THROTTLE], DEC);
|
||||
_port->print (",RLL:");
|
||||
_port->print(roll_sensor / 100, DEC);
|
||||
_port->print (",PCH:");
|
||||
_port->print(pitch_sensor / 100, DEC);
|
||||
_port->println(",***");
|
||||
}
|
||||
|
||||
void
|
||||
GCS_LEGACY::print_control_mode(void)
|
||||
{
|
||||
switch (control_mode){
|
||||
case MANUAL:
|
||||
_port->println("###MANUAL***");
|
||||
break;
|
||||
case STABILIZE:
|
||||
_port->println("###STABILIZE***");
|
||||
break;
|
||||
case CIRCLE:
|
||||
_port->println("###CIRCLE***");
|
||||
break;
|
||||
case FLY_BY_WIRE_A:
|
||||
_port->println("###FBW A***");
|
||||
break;
|
||||
case FLY_BY_WIRE_B:
|
||||
_port->println("###FBW B***");
|
||||
break;
|
||||
case AUTO:
|
||||
_port->println("###AUTO***");
|
||||
break;
|
||||
case RTL:
|
||||
_port->println("###RTL***");
|
||||
break;
|
||||
case LOITER:
|
||||
_port->println("###LOITER***");
|
||||
break;
|
||||
case TAKEOFF:
|
||||
_port->println("##TAKEOFF***");
|
||||
break;
|
||||
case LAND:
|
||||
_port->println("##LAND***");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_LEGACY::print_position(void)
|
||||
{
|
||||
_port->print("!!!");
|
||||
_port->print("LAT:");
|
||||
_port->print(current_loc.lat/10,DEC);
|
||||
_port->print(",LON:");
|
||||
_port->print(current_loc.lng/10,DEC); //wp_current_lat
|
||||
_port->print(",SPD:");
|
||||
_port->print(gps.ground_speed/100,DEC);
|
||||
_port->print(",CRT:");
|
||||
_port->print(climb_rate,DEC);
|
||||
_port->print(",ALT:");
|
||||
_port->print(current_loc.alt/100,DEC);
|
||||
_port->print(",ALH:");
|
||||
_port->print(next_WP.alt/100,DEC);
|
||||
_port->print(",CRS:");
|
||||
_port->print(yaw_sensor/100,DEC);
|
||||
_port->print(",BER:");
|
||||
_port->print(target_bearing/100,DEC);
|
||||
_port->print(",WPN:");
|
||||
_port->print(get(PARAM_WP_INDEX),DEC);//Actually is the waypoint.
|
||||
_port->print(",DST:");
|
||||
_port->print(wp_distance,DEC);
|
||||
_port->print(",BTV:");
|
||||
_port->print(battery_voltage,DEC);
|
||||
_port->print(",RSP:");
|
||||
_port->print(servo_out[CH_ROLL]/100,DEC);
|
||||
_port->print(",TOW:");
|
||||
_port->print(gps.time);
|
||||
_port->println(",***");
|
||||
}
|
||||
|
||||
void
|
||||
GCS_LEGACY::print_waypoint(struct Location *cmd,byte index)
|
||||
{
|
||||
_port->print("command #: ");
|
||||
_port->print(index, DEC);
|
||||
_port->print(" id: ");
|
||||
_port->print(cmd->id,DEC);
|
||||
_port->print(" p1: ");
|
||||
_port->print(cmd->p1,DEC);
|
||||
_port->print(" p2: ");
|
||||
_port->print(cmd->alt,DEC);
|
||||
_port->print(" p3: ");
|
||||
_port->print(cmd->lat,DEC);
|
||||
_port->print(" p4: ");
|
||||
_port->println(cmd->lng,DEC);
|
||||
}
|
||||
|
||||
#endif // GCS_PROTOCOL_LEGACY
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,610 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
|
||||
#include "Mavlink_Common.h"
|
||||
|
||||
GCS_MAVLINK::GCS_MAVLINK() :
|
||||
packet_drops(0)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::init(BetterStream * port)
|
||||
{
|
||||
GCS_Class::init(port);
|
||||
mavlink_comm_1_port = port;
|
||||
chan = MAVLINK_COMM_1;
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::update(void)
|
||||
{
|
||||
// recieve new packets
|
||||
mavlink_message_t msg;
|
||||
mavlink_status_t status;
|
||||
|
||||
// process received bytes
|
||||
while(comm_get_available(chan))
|
||||
{
|
||||
uint8_t c = comm_receive_ch(chan);
|
||||
|
||||
// Try to get a new message
|
||||
if(mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg);
|
||||
}
|
||||
|
||||
// Update packet drops counter
|
||||
packet_drops += status.packet_rx_drop_count;
|
||||
|
||||
// send out queued params/ waypoints
|
||||
mavlink_queued_send(chan);
|
||||
|
||||
// send parameters communication_queued_send(chan);
|
||||
// stop waypoint sending if timeout
|
||||
if (global_data.waypoint_sending &&
|
||||
millis() - global_data.waypoint_timelast_send >
|
||||
global_data.waypoint_send_timeout)
|
||||
{
|
||||
send_text(SEVERITY_LOW,"waypoint send timeout");
|
||||
global_data.waypoint_sending = false;
|
||||
}
|
||||
|
||||
// stop waypoint receiving if timeout
|
||||
if (global_data.waypoint_receiving &&
|
||||
millis() - global_data.waypoint_timelast_receive >
|
||||
global_data.waypoint_receive_timeout)
|
||||
{
|
||||
send_text(SEVERITY_LOW,"waypoint receive timeout");
|
||||
global_data.waypoint_receiving = false;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
|
||||
{
|
||||
if (freqLoopMatch(global_data.streamRateRawSensors,freqMin,freqMax))
|
||||
send_message(MSG_RAW_IMU);
|
||||
|
||||
if (freqLoopMatch(global_data.streamRateExtendedStatus,freqMin,freqMax))
|
||||
send_message(MSG_EXTENDED_STATUS);
|
||||
|
||||
if (freqLoopMatch(global_data.streamRateRCChannels,freqMin,freqMax))
|
||||
send_message(MSG_RADIO_OUT);
|
||||
|
||||
if (freqLoopMatch(global_data.streamRateRawController,freqMin,freqMax))
|
||||
send_message(MSG_SERVO_OUT);
|
||||
|
||||
//if (freqLoopMatch(global_data.streamRateRawSensorFusion,freqMin,freqMax))
|
||||
|
||||
if (freqLoopMatch(global_data.streamRatePosition,freqMin,freqMax))
|
||||
send_message(MSG_LOCATION);
|
||||
|
||||
if (freqLoopMatch(global_data.streamRateExtra1,freqMin,freqMax))
|
||||
send_message(MSG_GPS_STATUS);
|
||||
|
||||
if (freqLoopMatch(global_data.streamRateExtra2,freqMin,freqMax))
|
||||
send_message(MSG_CURRENT_WAYPOINT);
|
||||
|
||||
if (freqLoopMatch(global_data.streamRateExtra3,freqMin,freqMax))
|
||||
{
|
||||
send_message(MSG_LOCAL_LOCATION);
|
||||
send_message(MSG_ATTITUDE);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_message(uint8_t id, uint32_t param)
|
||||
{
|
||||
mavlink_send_message(chan,id,param,packet_drops);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_text(uint8_t severity, const char *str)
|
||||
{
|
||||
mavlink_send_text(chan,severity,str);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
mavlink_acknowledge(chan,id,sum1,sum2);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
|
||||
case MAVLINK_MSG_ID_GLOBAL_POSITION:
|
||||
{
|
||||
// decode
|
||||
mavlink_global_position_t packet;
|
||||
mavlink_msg_global_position_decode(msg, &packet);
|
||||
//if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
trackVehicle_loc.id = 0;
|
||||
trackVehicle_loc.p1 = 0;
|
||||
trackVehicle_loc.alt = packet.alt;
|
||||
trackVehicle_loc.lat = packet.lat;
|
||||
trackVehicle_loc.lng = packet.lon;
|
||||
Serial.println("received global position packet");
|
||||
}
|
||||
|
||||
|
||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
||||
{
|
||||
// decode
|
||||
mavlink_request_data_stream_t packet;
|
||||
mavlink_msg_request_data_stream_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
int freq = 0; // packet frequency
|
||||
|
||||
if (packet.start_stop == 0) freq = 0; // stop sending
|
||||
else if (packet.start_stop == 1) freq = packet.req_message_rate; // start sending
|
||||
else break;
|
||||
|
||||
switch(packet.req_stream_id)
|
||||
{
|
||||
case MAV_DATA_STREAM_ALL:
|
||||
global_data.streamRateRawSensors = freq;
|
||||
global_data.streamRateExtendedStatus = freq;
|
||||
global_data.streamRateRCChannels = freq;
|
||||
global_data.streamRateRawController = freq;
|
||||
global_data.streamRateRawSensorFusion = freq;
|
||||
global_data.streamRatePosition = freq;
|
||||
global_data.streamRateExtra1 = freq;
|
||||
global_data.streamRateExtra2 = freq;
|
||||
global_data.streamRateExtra3 = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_RAW_SENSORS:
|
||||
global_data.streamRateRawSensors = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_EXTENDED_STATUS:
|
||||
global_data.streamRateExtendedStatus = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_RC_CHANNELS:
|
||||
global_data.streamRateRCChannels = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_RAW_CONTROLLER:
|
||||
global_data.streamRateRawController = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_RAW_SENSOR_FUSION:
|
||||
global_data.streamRateRawSensorFusion = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_POSITION:
|
||||
global_data.streamRatePosition = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_EXTRA1:
|
||||
global_data.streamRateExtra1 = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_EXTRA2:
|
||||
global_data.streamRateExtra2 = freq;
|
||||
break;
|
||||
case MAV_DATA_STREAM_EXTRA3:
|
||||
global_data.streamRateExtra3 = freq;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_ACTION:
|
||||
{
|
||||
// decode
|
||||
mavlink_action_t packet;
|
||||
mavlink_msg_action_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target,packet.target_component)) break;
|
||||
|
||||
// do action
|
||||
gcs.send_text(SEVERITY_LOW,"action received");
|
||||
switch(packet.action)
|
||||
{
|
||||
|
||||
case MAV_ACTION_LAUNCH:
|
||||
set_mode(TAKEOFF);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_RETURN:
|
||||
set_mode(RTL);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_EMCY_LAND:
|
||||
set_mode(LAND);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_HALT:
|
||||
loiter_at_location();
|
||||
break;
|
||||
|
||||
// can't implement due to APM configuration
|
||||
// just setting to manual to be safe
|
||||
case MAV_ACTION_MOTORS_START:
|
||||
case MAV_ACTION_CONFIRM_KILL:
|
||||
case MAV_ACTION_EMCY_KILL:
|
||||
case MAV_ACTION_MOTORS_STOP:
|
||||
case MAV_ACTION_SHUTDOWN:
|
||||
set_mode(MANUAL);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_CONTINUE:
|
||||
process_next_command();
|
||||
break;
|
||||
|
||||
case MAV_ACTION_SET_MANUAL:
|
||||
set_mode(MANUAL);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_SET_AUTO:
|
||||
set_mode(AUTO);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_STORAGE_READ:
|
||||
//read_EEPROM_startup();
|
||||
//read_EEPROM_airstart_critical();
|
||||
//read_command_index();
|
||||
//read_EEPROM_flight_modes();
|
||||
break;
|
||||
|
||||
case MAV_ACTION_STORAGE_WRITE:
|
||||
//save_EEPROM_trims();
|
||||
//save_EEPROM_waypoint_info();
|
||||
//save_EEPROM_gains();
|
||||
//save_command_index();
|
||||
//save_pressure_data();
|
||||
//save_EEPROM_radio_minmax();
|
||||
//save_user_configs();
|
||||
//save_EEPROM_flight_modes();
|
||||
break;
|
||||
|
||||
case MAV_ACTION_CALIBRATE_RC: break;
|
||||
trim_radio();
|
||||
break;
|
||||
|
||||
case MAV_ACTION_CALIBRATE_GYRO:
|
||||
case MAV_ACTION_CALIBRATE_MAG:
|
||||
case MAV_ACTION_CALIBRATE_ACC:
|
||||
case MAV_ACTION_CALIBRATE_PRESSURE:
|
||||
case MAV_ACTION_REBOOT: // this is a rough interpretation
|
||||
startup_IMU_ground();
|
||||
break;
|
||||
|
||||
case MAV_ACTION_REC_START: break;
|
||||
case MAV_ACTION_REC_PAUSE: break;
|
||||
case MAV_ACTION_REC_STOP: break;
|
||||
|
||||
case MAV_ACTION_TAKEOFF:
|
||||
set_mode(TAKEOFF);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_NAVIGATE:
|
||||
set_mode(AUTO);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_LAND:
|
||||
set_mode(LAND);
|
||||
break;
|
||||
|
||||
case MAV_ACTION_LOITER:
|
||||
set_mode(LOITER);
|
||||
break;
|
||||
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"waypoint request list");
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_request_list_t packet;
|
||||
mavlink_msg_waypoint_request_list_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// Start sending waypoints
|
||||
mavlink_msg_waypoint_count_send(chan,msg->sysid,
|
||||
msg->compid,get(PARAM_WP_TOTAL));
|
||||
global_data.waypoint_timelast_send = millis();
|
||||
global_data.waypoint_sending = true;
|
||||
global_data.waypoint_receiving = false;
|
||||
global_data.waypoint_dest_sysid = msg->sysid;
|
||||
global_data.waypoint_dest_compid = msg->compid;
|
||||
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"waypoint request");
|
||||
|
||||
// Check if sending waypiont
|
||||
if (!global_data.waypoint_sending) break;
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_request_t packet;
|
||||
mavlink_msg_waypoint_request_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// send waypoint
|
||||
tell_command = get_wp_with_index(packet.seq);
|
||||
|
||||
// set frame of waypoint
|
||||
uint8_t frame = MAV_FRAME_GLOBAL; // reference frame
|
||||
uint8_t action = MAV_ACTION_NAVIGATE; // action
|
||||
uint8_t orbit_direction = 0; // clockwise(0), counter-clockwise(1)
|
||||
float orbit = 0; // loiter radius
|
||||
float param1 = 0, param2 = 0;
|
||||
|
||||
switch(tell_command.id)
|
||||
{
|
||||
|
||||
case CMD_WAYPOINT: // navigate
|
||||
action = MAV_ACTION_NAVIGATE; // action
|
||||
break;
|
||||
|
||||
case CMD_LOITER_TIME: // loiter
|
||||
orbit = get(PARAM_WP_RADIUS); // XXX setting loiter radius as waypoint acceptance radius
|
||||
action = MAV_ACTION_LOITER; // action
|
||||
param1 = get(PARAM_WP_RADIUS);
|
||||
param2 = tell_command.p1*100; // loiter time
|
||||
break;
|
||||
|
||||
case CMD_TAKEOFF: // takeoff
|
||||
action = MAV_ACTION_TAKEOFF;
|
||||
break;
|
||||
|
||||
case CMD_LAND: // land
|
||||
action = MAV_ACTION_LAND;
|
||||
break;
|
||||
|
||||
defaut:
|
||||
gcs.send_text(SEVERITY_LOW,"command not handled");
|
||||
break;
|
||||
}
|
||||
|
||||
// time that the mav should loiter in milliseconds
|
||||
uint8_t current = 0; // 1 (true), 0 (false)
|
||||
if (packet.seq == get(PARAM_WP_INDEX)) current = 1;
|
||||
float yaw_dir = 0; // yaw orientation in radians, 0 = north XXX: what does this do?
|
||||
uint8_t autocontinue = 1; // 1 (true), 0 (false)
|
||||
float x = tell_command.lng/1.0e7; // local (x), global (longitude)
|
||||
float y = tell_command.lat/1.0e7; // local (y), global (latitude)
|
||||
float z = tell_command.alt/1.0e2; // local (z), global (altitude)
|
||||
// note XXX: documented x,y,z order does not match with gps raw
|
||||
mavlink_msg_waypoint_send(chan,msg->sysid,
|
||||
msg->compid,packet.seq,frame,action,
|
||||
orbit,orbit_direction,param1,param2,current,x,y,z,yaw_dir,autocontinue);
|
||||
|
||||
// update last waypoint comm stamp
|
||||
global_data.waypoint_timelast_send = millis();
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_ACK:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"waypoint ack");
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_ack_t packet;
|
||||
mavlink_msg_waypoint_ack_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// check for error
|
||||
uint8_t type = packet.type; // ok (0), error(1)
|
||||
|
||||
// turn off waypoint send
|
||||
global_data.waypoint_sending = false;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"param request list");
|
||||
|
||||
// decode
|
||||
mavlink_param_request_list_t packet;
|
||||
mavlink_msg_param_request_list_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// Start sending parameters
|
||||
global_data.parameter_i = 0;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"waypoint clear all");
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_clear_all_t packet;
|
||||
mavlink_msg_waypoint_clear_all_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// clear all waypoints
|
||||
uint8_t type = 0; // ok (0), error(1)
|
||||
set(PARAM_WP_TOTAL,0);
|
||||
|
||||
// send acknowledgement 3 times to makes sure it is received
|
||||
for (int i=0;i<3;i++) mavlink_msg_waypoint_ack_send(chan,msg->sysid,msg->compid,type);
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"waypoint set current");
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_set_current_t packet;
|
||||
mavlink_msg_waypoint_set_current_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// set current waypoint
|
||||
set(PARAM_WP_INDEX,packet.seq);
|
||||
{
|
||||
Location temp; // XXX this is gross
|
||||
temp = get_wp_with_index(packet.seq);
|
||||
set_next_WP(&temp);
|
||||
}
|
||||
mavlink_msg_waypoint_current_send(chan,get(PARAM_WP_INDEX));
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_COUNT:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,"waypoint count");
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_count_t packet;
|
||||
mavlink_msg_waypoint_count_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// start waypoint receiving
|
||||
set(PARAM_WP_TOTAL,packet.count);
|
||||
if (get(PARAM_WP_TOTAL) > MAX_WAYPOINTS)
|
||||
set(PARAM_WP_TOTAL,MAX_WAYPOINTS);
|
||||
global_data.waypoint_timelast_receive = millis();
|
||||
global_data.waypoint_receiving = true;
|
||||
global_data.waypoint_sending = false;
|
||||
global_data.waypoint_request_i = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT:
|
||||
{
|
||||
// Check if receiving waypiont
|
||||
if (!global_data.waypoint_receiving) break;
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_t packet;
|
||||
mavlink_msg_waypoint_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// check if this is the requested waypoint
|
||||
if (packet.seq != global_data.waypoint_request_i) break;
|
||||
|
||||
// store waypoint
|
||||
uint8_t loadAction = 0; // 0 insert in list, 1 exec now
|
||||
|
||||
switch (packet.frame)
|
||||
{
|
||||
case MAV_FRAME_GLOBAL:
|
||||
{
|
||||
tell_command.lng = 1.0e7*packet.x;
|
||||
tell_command.lat = 1.0e7*packet.y;
|
||||
tell_command.alt = packet.z*1.0e2;
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_FRAME_LOCAL: // local (relative to home position)
|
||||
{
|
||||
tell_command.lng = 1.0e7*ToDeg(packet.x/
|
||||
(radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lng;
|
||||
tell_command.lat = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lat;
|
||||
tell_command.alt = -packet.z*1.0e2 + home.alt;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// defaults
|
||||
tell_command.id = CMD_BLANK;
|
||||
|
||||
switch (packet.action)
|
||||
{
|
||||
|
||||
case MAV_ACTION_TAKEOFF:
|
||||
{
|
||||
tell_command.id = CMD_TAKEOFF;
|
||||
break;
|
||||
}
|
||||
case MAV_ACTION_LAND:
|
||||
{
|
||||
tell_command.id = CMD_LAND;
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_ACTION_NAVIGATE:
|
||||
{
|
||||
tell_command.id = CMD_WAYPOINT;
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_ACTION_LOITER:
|
||||
{
|
||||
tell_command.id = CMD_LOITER_TIME;
|
||||
tell_command.p1 = packet.param2/1.0e2;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// save waypoint
|
||||
set_wp_with_index(tell_command, packet.seq);
|
||||
|
||||
// update waypoint receiving state machine
|
||||
global_data.waypoint_timelast_receive = millis();
|
||||
global_data.waypoint_request_i++;
|
||||
|
||||
if (global_data.waypoint_request_i == get(PARAM_WP_TOTAL))
|
||||
{
|
||||
gcs.send_text(SEVERITY_LOW,"flight plane received");
|
||||
uint8_t type = 0; // ok (0), error(1)
|
||||
mavlink_msg_waypoint_ack_send(chan,msg->sysid,msg->compid,type);
|
||||
global_data.waypoint_receiving = false;
|
||||
set(PARAM_WP_RADIUS,packet.param1); // XXX takes last waypoint radius for all
|
||||
//save_EEPROM_waypoint_info();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_SET:
|
||||
{
|
||||
// decode
|
||||
mavlink_param_set_t packet;
|
||||
mavlink_msg_param_set_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component))
|
||||
break;
|
||||
|
||||
// set parameter
|
||||
const char * key = (const char*) packet.param_id;
|
||||
|
||||
// iterate known parameters
|
||||
// XXX linear search; would be better to sort params & use a binary search
|
||||
for (uint16_t i = 0; i < global_data.param_count; i++) {
|
||||
|
||||
// compare key with parameter name
|
||||
if (!strcmp_P(key, getParamName(i))) {
|
||||
|
||||
// sanity-check the new parameter
|
||||
if (!isnan(packet.param_value) && // not nan
|
||||
!isinf(packet.param_value)) { // not inf
|
||||
|
||||
setParamAsFloat(i,packet.param_value);
|
||||
|
||||
// Report back new value
|
||||
char param_name[ONBOARD_PARAM_NAME_LENGTH]; /// XXX HACK
|
||||
strcpy_P(param_name, getParamName(i)); /// XXX HACK
|
||||
mavlink_msg_param_value_send(chan,
|
||||
(int8_t*)param_name,
|
||||
getParamAsFloat(i),
|
||||
global_data.param_count,i);
|
||||
// call load if required
|
||||
if (i >= PARAM_RLL2SRV_P && i <= PARAM_RLL2SRV_IMAX) pidServoRoll.load_gains();
|
||||
if (i >= PARAM_PTCH2SRV_P && i <= PARAM_PTCH2SRV_IMAX) pidServoPitch.load_gains();
|
||||
if (i >= PARAM_YW2SRV_P && i <= PARAM_YW2SRV_IMAX) pidServoRudder.load_gains();
|
||||
if (i >= PARAM_HDNG2RLL_P && i <= PARAM_HDNG2RLL_IMAX) pidNavRoll.load_gains();
|
||||
if (i >= PARAM_ARSPD2PTCH_P && i <= PARAM_ARSPD2PTCH_IMAX) pidNavPitchAirspeed.load_gains();
|
||||
if (i >= PARAM_ALT2PTCH_P && i <= PARAM_ALT2PTCH_IMAX) pidNavPitchAltitude.load_gains();
|
||||
if (i >= PARAM_ENRGY2THR_P && i <= PARAM_ENRGY2THR_IMAX) pidTeThrottle.load_gains();
|
||||
if (i >= PARAM_ALT2THR_P && i <= PARAM_ALT2THR_IMAX) pidAltitudeThrottle.load_gains();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
} // end case
|
||||
} // end switch
|
||||
} // end handle mavlink
|
||||
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,276 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
///
|
||||
/// @file GCS_Standard.pde
|
||||
/// @brief GCS driver for the APM binary protocol
|
||||
///
|
||||
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_STANDARD
|
||||
|
||||
// constructor
|
||||
GCS_STANDARD::GCS_STANDARD(BinComm::MessageHandler GCS_MessageHandlers[]) :
|
||||
_binComm(GCS_MessageHandlers)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
GCS_STANDARD::init(BetterStream *port)
|
||||
{
|
||||
GCS_Class::init(port);
|
||||
_binComm.init(port);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_STANDARD::update()
|
||||
{
|
||||
_binComm.update();
|
||||
}
|
||||
|
||||
void
|
||||
GCS_STANDARD::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
_binComm.send_msg_acknowledge(id, sum1, sum2);
|
||||
gcs_messages_sent++;
|
||||
}
|
||||
|
||||
void
|
||||
GCS_STANDARD::send_message(uint8_t id, uint32_t param)
|
||||
{
|
||||
byte mess_buffer[54];
|
||||
byte mess_ck_a = 0;
|
||||
byte mess_ck_b = 0;
|
||||
int tempint;
|
||||
int ck;
|
||||
long templong;
|
||||
|
||||
switch(id) {
|
||||
case MSG_MODE_CHANGE:
|
||||
case MSG_HEARTBEAT:
|
||||
_binComm.send_msg_heartbeat(control_mode, // current control mode
|
||||
millis() / 1000, // seconds since power-up
|
||||
battery_voltage1 * 100, // battery voltage * 100
|
||||
command_must_index); // command index (waypoint #)
|
||||
break;
|
||||
|
||||
case MSG_ATTITUDE:
|
||||
_binComm.send_msg_attitude(roll_sensor,
|
||||
pitch_sensor,
|
||||
yaw_sensor);
|
||||
break;
|
||||
|
||||
case MSG_LOCATION:
|
||||
_binComm.send_msg_location(current_loc.lat,
|
||||
current_loc.lng,
|
||||
GPS.altitude / 100,
|
||||
GPS.ground_speed,
|
||||
yaw_sensor,
|
||||
GPS.time);
|
||||
break;
|
||||
|
||||
case MSG_PRESSURE:
|
||||
_binComm.send_msg_pressure(current_loc.alt / 10,
|
||||
airspeed / 100);
|
||||
break;
|
||||
|
||||
case MSG_PERF_REPORT:
|
||||
_binComm.send_msg_perf_report(millis() - perf_mon_timer,
|
||||
mainLoop_count,
|
||||
G_Dt_max & 0xff,
|
||||
gyro_sat_count,
|
||||
adc_constraints,
|
||||
renorm_sqrt_count,
|
||||
renorm_blowup_count,
|
||||
gps_fix_count,
|
||||
imu_health * 100,
|
||||
gcs_messages_sent);
|
||||
break;
|
||||
|
||||
case MSG_CPU_LOAD:
|
||||
//TODO: Implement appropriate BinComm routine here
|
||||
|
||||
case MSG_VALUE:
|
||||
switch(param) {
|
||||
//case 0x00: templong = roll_mode; break;
|
||||
//case 0x01: templong = pitch_mode; break;
|
||||
//case 0x02: templong = throttle_mode; break;
|
||||
case 0x03: templong = yaw_mode; break;
|
||||
case 0x04: templong = elevon1_trim; break;
|
||||
case 0x05: templong = elevon2_trim; break;
|
||||
/* TODO: implement for new PID lib
|
||||
case 0x10: templong = integrator[0] * 1000; break;
|
||||
case 0x11: templong = integrator[1] * 1000; break;
|
||||
case 0x12: templong = integrator[2] * 1000; break;
|
||||
case 0x13: templong = integrator[3] * 1000; break;
|
||||
case 0x14: templong = integrator[4] * 1000; break;
|
||||
case 0x15: templong = integrator[5] * 1000; break;
|
||||
case 0x16: templong = integrator[6] * 1000; break;
|
||||
case 0x17: templong = integrator[7] * 1000; break;
|
||||
*/
|
||||
case 0x1a: templong = kff[0]; break;
|
||||
case 0x1b: templong = kff[1]; break;
|
||||
case 0x1c: templong = kff[2]; break;
|
||||
case 0x20: templong = target_bearing; break;
|
||||
case 0x21: templong = nav_bearing; break;
|
||||
case 0x22: templong = bearing_error; break;
|
||||
case 0x23: templong = crosstrack_bearing; break;
|
||||
case 0x24: templong = crosstrack_error; break;
|
||||
case 0x25: templong = altitude_error; break;
|
||||
case 0x26: templong = wp_radius; break;
|
||||
case 0x27: templong = loiter_radius; break;
|
||||
// case 0x28: templong = wp_mode; break;
|
||||
// case 0x29: templong = loop_commands; break;
|
||||
case 0x2a: templong = nav_gain_scaler; break;
|
||||
}
|
||||
_binComm.send_msg_value(param,
|
||||
templong);
|
||||
break;
|
||||
|
||||
case MSG_COMMAND_LIST:
|
||||
tell_command = get_wp_with_index((int)param);
|
||||
_binComm.send_msg_command_list(param,
|
||||
wp_total,
|
||||
tell_command.id,
|
||||
tell_command.p1,
|
||||
tell_command.alt,
|
||||
tell_command.lat,
|
||||
tell_command.lng);
|
||||
break;
|
||||
|
||||
case MSG_TRIM_STARTUP:
|
||||
_binComm.send_msg_trim_startup(radio_trim);
|
||||
break;
|
||||
|
||||
case MSG_TRIM_MIN:
|
||||
_binComm.send_msg_trim_min(radio_min);
|
||||
break;
|
||||
|
||||
case MSG_TRIM_MAX:
|
||||
_binComm.send_msg_trim_max(radio_max);
|
||||
break;
|
||||
|
||||
/* TODO: implement for new PID lib
|
||||
case MSG_PID: // PID Gains message
|
||||
_binComm.send_msg_pid(param,
|
||||
kp[param] * 1000000,
|
||||
ki[param] * 1000000,
|
||||
kd[param] * 1000000,
|
||||
integrator_max[param]);
|
||||
break;
|
||||
*/
|
||||
|
||||
case MSG_SERVO_OUT:
|
||||
_binComm.send_msg_servo_out(servo_out);
|
||||
break;
|
||||
|
||||
case MSG_RADIO_OUT:
|
||||
_binComm.send_msg_radio_out(radio_out);
|
||||
break;
|
||||
|
||||
default:
|
||||
GCS.send_text(SEVERITY_LOW,"<send_message> unknown message ID");
|
||||
}
|
||||
gcs_messages_sent++;
|
||||
}
|
||||
|
||||
void
|
||||
GCS_STANDARD::send_text(byte severity, const char *str)
|
||||
{
|
||||
if (severity >= DEBUG_LEVEL) {
|
||||
char text[50]; // XXX magic numbers
|
||||
|
||||
strncpy(text, str, 50);
|
||||
_binComm.send_msg_status_text(severity, text);
|
||||
gcs_messages_sent++;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
receive_message(void * arg, uint8_t id, uint8_t messageVersion, void * messageData)
|
||||
{
|
||||
// process command
|
||||
switch(id) {
|
||||
|
||||
case MSG_STATUS_TEXT:
|
||||
{
|
||||
char str[50];
|
||||
uint8_t severity;
|
||||
GCS.getBinComm().unpack_msg_status_text(severity,str);
|
||||
SendDebug(str);
|
||||
SendDebug(" severity: "); SendDebugln(severity);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSG_VERSION_REQUEST:
|
||||
break;
|
||||
|
||||
case MSG_VALUE_REQUEST:
|
||||
break;
|
||||
|
||||
case MSG_VALUE_SET:
|
||||
break;
|
||||
|
||||
case MSG_PID_REQUEST:
|
||||
break;
|
||||
|
||||
case MSG_PID_SET:
|
||||
break;
|
||||
|
||||
case MSG_EEPROM_REQUEST:
|
||||
break;
|
||||
|
||||
case MSG_EEPROM_SET:
|
||||
break;
|
||||
|
||||
case MSG_PIN_REQUEST:
|
||||
break;
|
||||
|
||||
case MSG_PIN_SET:
|
||||
break;
|
||||
|
||||
case MSG_DATAFLASH_REQUEST:
|
||||
break;
|
||||
|
||||
case MSG_DATAFLASH_SET:
|
||||
break;
|
||||
|
||||
case MSG_COMMAND_REQUEST:
|
||||
uint16_t commandIndex;
|
||||
GCS.getBinComm().unpack_msg_command_request(commandIndex);
|
||||
tell_command = get_wp_with_index(commandIndex);
|
||||
GCS.getBinComm().send_msg_command_list(commandIndex,uint16_t(wp_total),tell_command.id,
|
||||
tell_command.p1,tell_command.alt,tell_command.lat,tell_command.lng);
|
||||
break;
|
||||
|
||||
case MSG_COMMAND_UPLOAD:
|
||||
uint8_t action; // 0 -insert in list, 1- execute immediately
|
||||
uint16_t itemNumber; // item number ( i.e. waypoint number)
|
||||
uint16_t listLength; // list length
|
||||
struct Location temp;
|
||||
GCS.getBinComm().unpack_msg_command_upload(action,itemNumber,listLength,temp.id,temp.p1,temp.alt,temp.lat,temp.lng);
|
||||
wp_total=listLength;
|
||||
if (action == 0) // insert in list
|
||||
{
|
||||
// save waypoint total to eeprom at start of the list
|
||||
if (itemNumber == 1) save_EEPROM_waypoint_info();
|
||||
set_wp_with_index(temp, itemNumber);
|
||||
}
|
||||
else if (action == 1)
|
||||
{
|
||||
next_command = temp;
|
||||
process_now();
|
||||
}
|
||||
break;
|
||||
|
||||
case MSG_ACKNOWLEDGE:
|
||||
break;
|
||||
|
||||
default:
|
||||
{
|
||||
char str[50];
|
||||
sprintf(str,"<receive_message> unknown messageID:%x",id);
|
||||
GCS.send_text(SEVERITY_LOW,str);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // GCS_PROTOCOL_STANDARD
|
|
@ -0,0 +1,113 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
///
|
||||
/// @file GCS_Xplane.pde
|
||||
/// @brief GCS driver for the X-plane HIL interface.
|
||||
///
|
||||
|
||||
#if GCS_PROTOCOL == GCS_PROTOCOL_XPLANE
|
||||
|
||||
void
|
||||
GCS_XPLANE::send_text(uint8_t severity, const char *str)
|
||||
{
|
||||
if(severity >= DEBUG_LEVEL){
|
||||
Serial.print("MSG: ");
|
||||
Serial.println(str);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_XPLANE::send_message(uint8_t id, uint32_t param)
|
||||
{
|
||||
switch(id) {
|
||||
case MSG_HEARTBEAT:
|
||||
print_control_mode();
|
||||
break;
|
||||
|
||||
case MSG_ATTITUDE:
|
||||
//print_attitude();
|
||||
break;
|
||||
|
||||
case MSG_LOCATION:
|
||||
//print_position();
|
||||
break;
|
||||
|
||||
case MSG_CPU_LOAD:
|
||||
//TODO: implement appropriate routine here if applicable
|
||||
break;
|
||||
|
||||
case MSG_COMMAND_LIST:
|
||||
struct Location cmd = get_wp_with_index(param);
|
||||
print_waypoint(&cmd, param);
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GCS_XPLANE::print_control_mode(void)
|
||||
{
|
||||
Serial.print("MSG: ");
|
||||
Serial.print(flight_mode_strings[control_mode]);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_XPLANE::print_current_waypoints()
|
||||
{
|
||||
Serial.print("MSG: ");
|
||||
Serial.print("CUR:");
|
||||
Serial.print("\t");
|
||||
Serial.print(current_loc.lat,DEC);
|
||||
Serial.print(",\t");
|
||||
Serial.print(current_loc.lng,DEC);
|
||||
Serial.print(",\t");
|
||||
Serial.println(current_loc.alt,DEC);
|
||||
|
||||
Serial.print("MSG: ");
|
||||
Serial.print("NWP:");
|
||||
Serial.print(wp_index,DEC);
|
||||
Serial.print(",\t");
|
||||
Serial.print(next_WP.lat,DEC);
|
||||
Serial.print(",\t");
|
||||
Serial.print(next_WP.lng,DEC);
|
||||
Serial.print(",\t");
|
||||
Serial.println(next_WP.alt,DEC);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_XPLANE::print_waypoint(struct Location *cmd,byte index)
|
||||
{
|
||||
Serial.print("MSG: command #: ");
|
||||
Serial.print(index, DEC);
|
||||
Serial.print(" id: ");
|
||||
Serial.print(cmd->id,DEC);
|
||||
Serial.print(" p1: ");
|
||||
Serial.print(cmd->p1,DEC);
|
||||
Serial.print(" p2: ");
|
||||
Serial.print(cmd->alt,DEC);
|
||||
Serial.print(" p3: ");
|
||||
Serial.print(cmd->lat,DEC);
|
||||
Serial.print(" p4: ");
|
||||
Serial.println(cmd->lng,DEC);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_XPLANE::print_waypoints()
|
||||
{
|
||||
Serial.println("Commands in memory");
|
||||
Serial.print("commands total: ");
|
||||
Serial.println(wp_total, DEC);
|
||||
// create a location struct to hold the temp Waypoints for printing
|
||||
//Location tmp;
|
||||
Serial.println("Home: ");
|
||||
struct Location cmd = get_wp_with_index(0);
|
||||
print_waypoint(&cmd, 0);
|
||||
Serial.println("Commands: ");
|
||||
|
||||
for (int i=1; i<wp_total; i++){
|
||||
cmd = get_wp_with_index(i);
|
||||
print_waypoint(&cmd, i);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // GCS_PROTOCOL_XPLANE
|
|
@ -0,0 +1,141 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/// @file HIL.h
|
||||
/// @brief Interface definition for the various Ground Control System protocols.
|
||||
|
||||
#ifndef __HIL_H
|
||||
#define __HIL_H
|
||||
|
||||
# if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
#include <BetterStream.h>
|
||||
#include <AP_Common.h>
|
||||
#include <APM_BinComm.h>
|
||||
#include <GPS.h>
|
||||
#include <Stream.h>
|
||||
#include <stdint.h>
|
||||
|
||||
///
|
||||
/// @class HIL
|
||||
/// @brief Class describing the interface between the APM code
|
||||
/// proper and the HIL implementation.
|
||||
///
|
||||
/// HIL' are currently implemented inside the sketch and as such have
|
||||
/// access to all global state. The sketch should not, however, call HIL
|
||||
/// internal functions - all calls to the HIL should be routed through
|
||||
/// this interface (or functions explicitly exposed by a subclass).
|
||||
///
|
||||
class HIL_Class
|
||||
{
|
||||
public:
|
||||
|
||||
/// Startup initialisation.
|
||||
///
|
||||
/// This routine performs any one-off initialisation required before
|
||||
/// HIL messages are exchanged.
|
||||
///
|
||||
/// @note The stream is expected to be set up and configured for the
|
||||
/// correct bitrate before ::init is called.
|
||||
///
|
||||
/// @note The stream is currently BetterStream so that we can use the _P
|
||||
/// methods; this may change if Arduino adds them to Print.
|
||||
///
|
||||
/// @param port The stream over which messages are exchanged.
|
||||
///
|
||||
void init(BetterStream *port) { _port = port; }
|
||||
|
||||
/// Update HIL state.
|
||||
///
|
||||
/// This may involve checking for received bytes on the stream,
|
||||
/// or sending additional periodic messages.
|
||||
void update(void) {}
|
||||
|
||||
/// Send a message with a single numeric parameter.
|
||||
///
|
||||
/// This may be a standalone message, or the HIL driver may
|
||||
/// have its own way of locating additional parameters to send.
|
||||
///
|
||||
/// @param id ID of the message to send.
|
||||
/// @param param Explicit message parameter.
|
||||
///
|
||||
void send_message(uint8_t id, int32_t param = 0) {}
|
||||
|
||||
/// Send a text message.
|
||||
///
|
||||
/// @param severity A value describing the importance of the message.
|
||||
/// @param str The text to be sent.
|
||||
///
|
||||
void send_text(uint8_t severity, const char *str) {}
|
||||
|
||||
/// Send acknowledgement for a message.
|
||||
///
|
||||
/// @param id The message ID being acknowledged.
|
||||
/// @param sum1 Checksum byte 1 from the message being acked.
|
||||
/// @param sum2 Checksum byte 2 from the message being acked.
|
||||
///
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) {}
|
||||
|
||||
protected:
|
||||
/// The stream we are communicating over
|
||||
BetterStream *_port;
|
||||
};
|
||||
|
||||
//
|
||||
// HIL class definitions.
|
||||
//
|
||||
// These are here so that we can declare the HIL object early in the sketch
|
||||
// and then reference it statically rather than via a pointer.
|
||||
//
|
||||
|
||||
///
|
||||
/// @class HIL_MAVLINK
|
||||
/// @brief The mavlink protocol for hil
|
||||
///
|
||||
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK
|
||||
class HIL_MAVLINK : public HIL_Class
|
||||
{
|
||||
public:
|
||||
HIL_MAVLINK();
|
||||
void update(void);
|
||||
void init(BetterStream *port);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
||||
private:
|
||||
void handleMessage(mavlink_message_t * msg);
|
||||
mavlink_channel_t chan;
|
||||
uint16_t packet_drops;
|
||||
};
|
||||
#endif // HIL_PROTOCOL_MAVLINK
|
||||
|
||||
///
|
||||
/// @class HIL_XPLANE
|
||||
/// @brief The xplane protocol for hil
|
||||
///
|
||||
#if HIL_PROTOCOL == HIL_PROTOCOL_XPLANE
|
||||
class HIL_XPLANE : public HIL_Class
|
||||
{
|
||||
public:
|
||||
HIL_XPLANE();
|
||||
void update(void);
|
||||
void init(BetterStream *port);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
||||
private:
|
||||
void output_HIL();
|
||||
void output_HIL_();
|
||||
void output_int(int value);
|
||||
void output_byte(byte value);
|
||||
void print_buffer();
|
||||
|
||||
AP_GPS_IMU * hilPacketDecoder;
|
||||
byte buf_len;
|
||||
byte out_buffer[32];
|
||||
};
|
||||
#endif // HIL_PROTOCOL_XPLANE
|
||||
|
||||
#endif // HIL not disabled
|
||||
|
||||
#endif // __HIL_H
|
||||
|
|
@ -0,0 +1,154 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED && HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK
|
||||
|
||||
#include "Mavlink_Common.h"
|
||||
|
||||
HIL_MAVLINK::HIL_MAVLINK() :
|
||||
packet_drops(0)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
HIL_MAVLINK::init(BetterStream * port)
|
||||
{
|
||||
HIL_Class::init(port);
|
||||
mavlink_comm_0_port = port;
|
||||
chan = MAVLINK_COMM_0;
|
||||
}
|
||||
|
||||
void
|
||||
HIL_MAVLINK::update(void)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_status_t status;
|
||||
|
||||
// process received bytes
|
||||
while(comm_get_available(chan))
|
||||
{
|
||||
uint8_t c = comm_receive_ch(chan);
|
||||
|
||||
// Try to get a new message
|
||||
if(mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg);
|
||||
}
|
||||
|
||||
// Update packet drops counter
|
||||
packet_drops += status.packet_rx_drop_count;
|
||||
}
|
||||
|
||||
void
|
||||
HIL_MAVLINK::send_message(uint8_t id, uint32_t param)
|
||||
{
|
||||
mavlink_send_message(chan,id,param,packet_drops);
|
||||
}
|
||||
|
||||
void
|
||||
HIL_MAVLINK::send_text(uint8_t severity, const char *str)
|
||||
{
|
||||
mavlink_send_text(chan,severity,str);
|
||||
}
|
||||
|
||||
void
|
||||
HIL_MAVLINK::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
mavlink_acknowledge(chan,id,sum1,sum2);
|
||||
}
|
||||
|
||||
void
|
||||
HIL_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
|
||||
// handle incoming vehicle position
|
||||
case MAVLINK_MSG_ID_GLOBAL_POSITION:
|
||||
{
|
||||
// decode
|
||||
mavlink_global_position_t packet;
|
||||
mavlink_msg_global_position_decode(msg, &packet);
|
||||
//if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
trackVehicle_loc.id = 0;
|
||||
trackVehicle_loc.p1 = 0;
|
||||
trackVehicle_loc.alt = packet.alt;
|
||||
trackVehicle_loc.lat = packet.lat;
|
||||
trackVehicle_loc.lng = packet.lon;
|
||||
Serial.println("received global position packet");
|
||||
}
|
||||
|
||||
// This is used both as a sensor and to pass the location
|
||||
// in HIL_ATTITUDE mode.
|
||||
case MAVLINK_MSG_ID_GPS_RAW:
|
||||
{
|
||||
// decode
|
||||
mavlink_gps_raw_t packet;
|
||||
mavlink_msg_gps_raw_decode(msg, &packet);
|
||||
|
||||
// set gps hil sensor
|
||||
gps.setHIL(packet.usec/1000.0,packet.lat,packet.lon,packet.alt,
|
||||
packet.v,packet.hdg,0,0);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_AIRSPEED:
|
||||
{
|
||||
// decode
|
||||
mavlink_airspeed_t packet;
|
||||
mavlink_msg_airspeed_decode(msg, &packet);
|
||||
|
||||
// set airspeed
|
||||
airspeed = 100*packet.airspeed;
|
||||
break;
|
||||
}
|
||||
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
|
||||
case MAVLINK_MSG_ID_ATTITUDE:
|
||||
{
|
||||
// decode
|
||||
mavlink_attitude_t packet;
|
||||
mavlink_msg_attitude_decode(msg, &packet);
|
||||
|
||||
// set gps hil sensor
|
||||
dcm.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
|
||||
packet.pitchspeed,packet.yawspeed);
|
||||
break;
|
||||
}
|
||||
|
||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||
|
||||
case MAVLINK_MSG_ID_RAW_IMU:
|
||||
{
|
||||
// decode
|
||||
mavlink_raw_imu_t packet;
|
||||
mavlink_msg_raw_imu_decode(msg, &packet);
|
||||
|
||||
// set imu hil sensors
|
||||
// TODO: check scaling for temp/absPress
|
||||
float temp = 70;
|
||||
float absPress = 1;
|
||||
//Serial.printf_P(PSTR("\nreceived accel:\t%d\t%d\t%d\n"), packet.xacc, packet.yacc, packet.zacc);
|
||||
//Serial.printf_P(PSTR("\nreceived gyro:\t%d\t%d\t%d\n"), packet.xgyro, packet.ygyro, packet.zgyro);
|
||||
|
||||
adc.setHIL(packet.xgyro,packet.ygyro,packet.zgyro,temp,
|
||||
packet.xacc,packet.yacc,packet.zacc,absPress);
|
||||
compass.setHIL(packet.xmag,packet.ymag,packet.zmag);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_RAW_PRESSURE:
|
||||
{
|
||||
// decode
|
||||
mavlink_raw_pressure_t packet;
|
||||
mavlink_msg_raw_pressure_decode(msg, &packet);
|
||||
|
||||
// set pressure hil sensor
|
||||
// TODO: check scaling
|
||||
float temp = 70;
|
||||
pitot.setHIL(temp,packet.press_diff1);
|
||||
break;
|
||||
}
|
||||
#endif // HIL_MODE
|
||||
|
||||
} // end switch
|
||||
}
|
||||
#endif
|
||||
|
|
@ -0,0 +1,151 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED && HIL_PROTOCOL == HIL_PROTOCOL_XPLANE
|
||||
|
||||
|
||||
void HIL_XPLANE::output_HIL(void)
|
||||
{
|
||||
// output real-time sensor data
|
||||
Serial.print("AAA"); // Message preamble
|
||||
output_int((int)(servo_out[CH_ROLL])); // 0 bytes 0, 1
|
||||
output_int((int)(servo_out[CH_PITCH])); // 1 bytes 2, 3
|
||||
output_int((int)(servo_out[CH_THROTTLE])); // 2 bytes 4, 5
|
||||
output_int((int)(servo_out[CH_RUDDER])); // 3 bytes 6, 7
|
||||
output_int((int)wp_distance); // 4 bytes 8,9
|
||||
output_int((int)bearing_error); // 5 bytes 10,11
|
||||
output_int((int)next_WP.alt / 100); // 6 bytes 12, 13
|
||||
output_int((int)energy_error); // 7 bytes 14,15
|
||||
output_byte(get(PARAM_WP_INDEX)); // 8 bytes 16
|
||||
output_byte(control_mode); // 9 bytes 17
|
||||
|
||||
// print out the buffer and checksum
|
||||
// ---------------------------------
|
||||
print_buffer();
|
||||
}
|
||||
|
||||
// This is for debugging only!,
|
||||
// I just move the underscore to keep the above version pristene.
|
||||
void HIL_XPLANE::output_HIL_(void)
|
||||
{
|
||||
// output real-time sensor data
|
||||
Serial.print("AAA"); // Message preamble
|
||||
output_int((int)(servo_out[CH_ROLL])); // 0 bytes 0, 1
|
||||
output_int((int)(servo_out[CH_PITCH])); // 1 bytes 2, 3
|
||||
output_int((int)(servo_out[CH_THROTTLE])); // 2 bytes 4, 5
|
||||
output_int((int)(servo_out[CH_RUDDER])); // 3 bytes 6, 7
|
||||
output_int((int)wp_distance); // 4 bytes 8, 9
|
||||
output_int((int)bearing_error); // 5 bytes 10,11
|
||||
output_int((int)dcm.roll_sensor); // 6 bytes 12,13
|
||||
output_int((int)loiter_total); // 7 bytes 14,15
|
||||
output_byte(get(PARAM_WP_INDEX)); // 8 bytes 16
|
||||
output_byte(control_mode); // 9 bytes 17
|
||||
|
||||
// print out the buffer and checksum
|
||||
// ---------------------------------
|
||||
print_buffer();
|
||||
}
|
||||
|
||||
void HIL_XPLANE::output_int(int value)
|
||||
{
|
||||
//buf_len += 2;
|
||||
out_buffer[buf_len++] = value & 0xff;
|
||||
out_buffer[buf_len++] = (value >> 8) & 0xff;
|
||||
}
|
||||
|
||||
void HIL_XPLANE::output_byte(byte value)
|
||||
{
|
||||
out_buffer[buf_len++] = value;
|
||||
}
|
||||
|
||||
void HIL_XPLANE::print_buffer()
|
||||
{
|
||||
byte ck_a = 0;
|
||||
byte ck_b = 0;
|
||||
for (byte i = 0;i < buf_len; i++){
|
||||
Serial.print (out_buffer[i]);
|
||||
}
|
||||
Serial.print('\r');
|
||||
Serial.print('\n');
|
||||
buf_len = 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
HIL_XPLANE::HIL_XPLANE() :
|
||||
buf_len(0)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::init(BetterStream * port)
|
||||
{
|
||||
HIL_Class::init(port);
|
||||
hilPacketDecoder = new AP_GPS_IMU(port);
|
||||
hilPacketDecoder->init();
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::update(void)
|
||||
{
|
||||
hilPacketDecoder->update();
|
||||
airspeed = (float)hilPacketDecoder->airspeed; //airspeed is * 100 coming in from Xplane for accuracy
|
||||
calc_airspeed_errors();
|
||||
dcm.setHil(hilPacketDecoder->roll_sensor*M_PI/18000,
|
||||
hilPacketDecoder->pitch_sensor*M_PI/18000,
|
||||
hilPacketDecoder->ground_course*M_PI/18000,
|
||||
0,0,0);
|
||||
|
||||
// set gps hil sensor
|
||||
gps.setHIL(hilPacketDecoder->time/1000.0,(float)hilPacketDecoder->latitude/1.0e7,(float)hilPacketDecoder->longitude/1.0e7,(float)hilPacketDecoder->altitude/1.0e2,
|
||||
(float)hilPacketDecoder->speed_3d/1.0e2,(float)hilPacketDecoder->ground_course/1.0e2,0,0);
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::send_message(uint8_t id, uint32_t param)
|
||||
{
|
||||
// TODO: split output by actual request
|
||||
uint64_t timeStamp = micros();
|
||||
switch(id) {
|
||||
|
||||
case MSG_HEARTBEAT:
|
||||
break;
|
||||
case MSG_EXTENDED_STATUS:
|
||||
break;
|
||||
case MSG_ATTITUDE:
|
||||
break;
|
||||
case MSG_LOCATION:
|
||||
break;
|
||||
case MSG_LOCAL_LOCATION:
|
||||
break;
|
||||
case MSG_GPS_RAW:
|
||||
break;
|
||||
case MSG_SERVO_OUT:
|
||||
output_HIL();
|
||||
break;
|
||||
case MSG_AIRSPEED:
|
||||
break;
|
||||
case MSG_RADIO_OUT:
|
||||
break;
|
||||
case MSG_RAW_IMU:
|
||||
break;
|
||||
case MSG_GPS_STATUS:
|
||||
break;
|
||||
case MSG_CURRENT_WAYPOINT:
|
||||
break;
|
||||
defualt:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::send_text(uint8_t severity, const char *str)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,611 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
// Code to Write and Read packets from DataFlash log memory
|
||||
// Code to interact with the user to dump or erase logs
|
||||
|
||||
#define HEAD_BYTE1 0xA3 // Decimal 163
|
||||
#define HEAD_BYTE2 0x95 // Decimal 149
|
||||
#define END_BYTE 0xBA // Decimal 186
|
||||
|
||||
|
||||
// These are function definitions so the Menu can be constructed before the functions
|
||||
// are defined below. Order matters to the compiler.
|
||||
static int8_t print_log_menu(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t dump_log(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t erase_logs(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
|
||||
|
||||
// This is the help function
|
||||
// PSTR is an AVR macro to read strings from flash memory
|
||||
// printf_P is a version of print_f that reads from flash memory
|
||||
static int8_t help_log(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
Serial.printf_P(PSTR("\n"
|
||||
"Commands:\n"
|
||||
" dump <n> dump log <n>\n"
|
||||
" erase erase all logs\n"
|
||||
" enable <name>|all enable logging <name> or everything\n"
|
||||
" disable <name>|all disable logging <name> or everything\n"
|
||||
"\n"));
|
||||
}
|
||||
|
||||
// Creates a constant array of structs representing menu options
|
||||
// and stores them in Flash memory, not RAM.
|
||||
// User enters the string in the console to call the functions on the right.
|
||||
// See class Menu in AP_Coommon for implementation details
|
||||
const struct Menu::command log_menu_commands[] PROGMEM = {
|
||||
{"dump", dump_log},
|
||||
{"erase", erase_logs},
|
||||
{"enable", select_logs},
|
||||
{"disable", select_logs},
|
||||
{"help", help_log}
|
||||
};
|
||||
|
||||
// A Macro to create the Menu
|
||||
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
||||
|
||||
static bool
|
||||
print_log_menu(void)
|
||||
{
|
||||
int log_start;
|
||||
int log_end;
|
||||
byte last_log_num = eeprom_read_byte((uint8_t *) EE_LAST_LOG_NUM);
|
||||
|
||||
Serial.printf_P(PSTR("logs enabled: "));
|
||||
if (0 == get(PARAM_LOG_BITMASK)) {
|
||||
Serial.printf_P(PSTR("none"));
|
||||
} else {
|
||||
// Macro to make the following code a bit easier on the eye.
|
||||
// Pass it the capitalised name of the log option, as defined
|
||||
// in defines.h but without the LOG_ prefix. It will check for
|
||||
// the bit being set and print the name of the log option to suit.
|
||||
#define PLOG(_s) if (get(PARAM_LOG_BITMASK) & LOGBIT_ ## _s) Serial.printf_P(PSTR(" %S"), PSTR(#_s))
|
||||
PLOG(ATTITUDE_FAST);
|
||||
PLOG(ATTITUDE_MED);
|
||||
PLOG(GPS);
|
||||
PLOG(PM);
|
||||
PLOG(CTUN);
|
||||
PLOG(NTUN);
|
||||
PLOG(MODE);
|
||||
PLOG(RAW);
|
||||
PLOG(CMD);
|
||||
#undef PLOG
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
if (last_log_num == 0) {
|
||||
Serial.printf_P(PSTR("\nNo logs available for download\n"));
|
||||
} else {
|
||||
|
||||
Serial.printf_P(PSTR("\n%d logs available for download\n"), last_log_num);
|
||||
for(int i=1;i<last_log_num+1;i++) {
|
||||
log_start = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(i-1)*0x02));
|
||||
log_end = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(i)*0x02))-1;
|
||||
if (i == last_log_num) {
|
||||
log_end = eeprom_read_word((uint16_t *) EE_LAST_LOG_PAGE);
|
||||
}
|
||||
Serial.printf_P(PSTR("Log number %d, start page %d, end page %d\n"),
|
||||
i, log_start, log_end);
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
return(true);
|
||||
}
|
||||
|
||||
static int8_t
|
||||
dump_log(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
byte dump_log;
|
||||
int dump_log_start;
|
||||
int dump_log_end;
|
||||
byte last_log_num;
|
||||
|
||||
// check that the requested log number can be read
|
||||
dump_log = argv[1].i;
|
||||
last_log_num = eeprom_read_byte((uint8_t *) EE_LAST_LOG_NUM);
|
||||
if ((argc != 2) || (dump_log < 1) || (dump_log > last_log_num)) {
|
||||
Serial.printf_P(PSTR("bad log number\n"));
|
||||
return(-1);
|
||||
}
|
||||
|
||||
dump_log_start = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(dump_log-1)*0x02));
|
||||
dump_log_end = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(dump_log)*0x02))-1;
|
||||
if (dump_log == last_log_num) {
|
||||
dump_log_end = eeprom_read_word((uint16_t *) EE_LAST_LOG_PAGE);
|
||||
}
|
||||
Serial.printf_P(PSTR("Dumping Log number %d, start page %d, end page %d\n"),
|
||||
dump_log, dump_log_start, dump_log_end);
|
||||
Log_Read(dump_log_start, dump_log_end);
|
||||
Serial.printf_P(PSTR("Log read complete\n"));
|
||||
}
|
||||
|
||||
static int8_t
|
||||
erase_logs(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
for(int i = 10 ; i > 0; i--) {
|
||||
Serial.printf_P(PSTR("ATTENTION - Erasing log in %d seconds. Power off now to save log! \n"), i);
|
||||
delay(1000);
|
||||
}
|
||||
Serial.printf_P(PSTR("\nErasing log...\n"));
|
||||
for(int j = 1; j < 4001; j++)
|
||||
DataFlash.PageErase(j);
|
||||
eeprom_write_byte((uint8_t *)EE_LAST_LOG_NUM, 0);
|
||||
eeprom_write_byte((uint8_t *)EE_LAST_LOG_PAGE, 1);
|
||||
Serial.printf_P(PSTR("\nLog erased.\n"));
|
||||
}
|
||||
|
||||
static int8_t
|
||||
select_logs(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
uint16_t bits;
|
||||
|
||||
if (argc != 2) {
|
||||
Serial.printf_P(PSTR("missing log type\n"));
|
||||
return(-1);
|
||||
}
|
||||
|
||||
bits = 0;
|
||||
|
||||
// Macro to make the following code a bit easier on the eye.
|
||||
// Pass it the capitalised name of the log option, as defined
|
||||
// in defines.h but without the LOG_ prefix. It will check for
|
||||
// that name as the argument to the command, and set the bit in
|
||||
// bits accordingly.
|
||||
//
|
||||
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
|
||||
bits = ~(bits = 0);
|
||||
} else {
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= LOGBIT_ ## _s
|
||||
TARG(ATTITUDE_FAST);
|
||||
TARG(ATTITUDE_MED);
|
||||
TARG(GPS);
|
||||
TARG(PM);
|
||||
TARG(CTUN);
|
||||
TARG(NTUN);
|
||||
TARG(MODE);
|
||||
TARG(RAW);
|
||||
TARG(CMD);
|
||||
#undef TARG
|
||||
}
|
||||
|
||||
if (!strcasecmp_P(argv[0].str, PSTR("enable"))) {
|
||||
set(PARAM_LOG_BITMASK, get(PARAM_LOG_BITMASK) | bits);
|
||||
} else {
|
||||
set(PARAM_LOG_BITMASK, get(PARAM_LOG_BITMASK) & ~bits);
|
||||
}
|
||||
return(0);
|
||||
}
|
||||
|
||||
int8_t
|
||||
process_logs(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
log_menu.run();
|
||||
}
|
||||
|
||||
// Write an attitude packet. Total length : 10 bytes
|
||||
void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_ATTITUDE_MSG);
|
||||
DataFlash.WriteInt(log_roll);
|
||||
DataFlash.WriteInt(log_pitch);
|
||||
DataFlash.WriteInt(log_yaw);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
// Write a performance monitoring packet. Total length : 19 bytes
|
||||
void Log_Write_Performance()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_PERFORMANCE_MSG);
|
||||
DataFlash.WriteLong(millis()- perf_mon_timer);
|
||||
DataFlash.WriteInt(mainLoop_count);
|
||||
DataFlash.WriteInt(G_Dt_max);
|
||||
DataFlash.WriteByte(gyro_sat_count);
|
||||
DataFlash.WriteByte(adc_constraints);
|
||||
DataFlash.WriteByte(renorm_sqrt_count);
|
||||
DataFlash.WriteByte(renorm_blowup_count);
|
||||
DataFlash.WriteByte(gps_fix_count);
|
||||
DataFlash.WriteInt((int)(imu_health*1000));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
// Write a command processing packet. Total length : 19 bytes
|
||||
//void Log_Write_Cmd(byte num, byte id, byte p1, long alt, long lat, long lng)
|
||||
void Log_Write_Cmd(byte num, struct Location *wp)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_CMD_MSG);
|
||||
DataFlash.WriteByte(num);
|
||||
DataFlash.WriteByte(wp->id);
|
||||
DataFlash.WriteByte(wp->p1);
|
||||
DataFlash.WriteLong(wp->alt);
|
||||
DataFlash.WriteLong(wp->lat);
|
||||
DataFlash.WriteLong(wp->lng);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
void Log_Write_Startup(byte type)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_STARTUP_MSG);
|
||||
DataFlash.WriteByte(type);
|
||||
DataFlash.WriteByte(get(PARAM_WP_TOTAL));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
|
||||
// create a location struct to hold the temp Waypoints for printing
|
||||
struct Location cmd = get_wp_with_index(0);
|
||||
Log_Write_Cmd(0, &cmd);
|
||||
|
||||
for (int i=1; i<get(PARAM_WP_TOTAL); i++){
|
||||
cmd = get_wp_with_index(i);
|
||||
Log_Write_Cmd(i, &cmd);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Write a control tuning packet. Total length : 22 bytes
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
void Log_Write_Control_Tuning()
|
||||
{
|
||||
Vector3f accel = imu.get_accel();
|
||||
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_CONTROL_TUNING_MSG);
|
||||
DataFlash.WriteInt((int)(servo_out[CH_ROLL]));
|
||||
DataFlash.WriteInt((int)nav_roll);
|
||||
DataFlash.WriteInt((int)dcm.roll_sensor);
|
||||
DataFlash.WriteInt((int)(servo_out[CH_PITCH]));
|
||||
DataFlash.WriteInt((int)nav_pitch);
|
||||
DataFlash.WriteInt((int)dcm.pitch_sensor);
|
||||
DataFlash.WriteInt((int)(servo_out[CH_THROTTLE]));
|
||||
DataFlash.WriteInt((int)(servo_out[CH_RUDDER]));
|
||||
DataFlash.WriteInt((int)(accel.y*10000));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Write a navigation tuning packet. Total length : 18 bytes
|
||||
void Log_Write_Nav_Tuning()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_NAV_TUNING_MSG);
|
||||
DataFlash.WriteInt((uint16_t)dcm.yaw_sensor);
|
||||
DataFlash.WriteInt((int)wp_distance);
|
||||
DataFlash.WriteInt((uint16_t)target_bearing);
|
||||
DataFlash.WriteInt((uint16_t)nav_bearing);
|
||||
DataFlash.WriteInt(altitude_error);
|
||||
DataFlash.WriteInt((int)airspeed);
|
||||
DataFlash.WriteInt((int)(nav_gain_scaler*1000));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
// Write a mode packet. Total length : 5 bytes
|
||||
void Log_Write_Mode(byte mode)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_MODE_MSG);
|
||||
DataFlash.WriteByte(mode);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
// Write an GPS packet. Total length : 30 bytes
|
||||
void Log_Write_GPS( long log_Time, long log_Lattitude, long log_Longitude, long log_mix_alt, long log_gps_alt,
|
||||
long log_Ground_Speed, long log_Ground_Course, byte log_Fix, byte log_NumSats)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_GPS_MSG);
|
||||
DataFlash.WriteLong(log_Time);
|
||||
DataFlash.WriteByte(log_Fix);
|
||||
DataFlash.WriteByte(log_NumSats);
|
||||
DataFlash.WriteLong(log_Lattitude);
|
||||
DataFlash.WriteLong(log_Longitude);
|
||||
DataFlash.WriteLong(log_mix_alt);
|
||||
DataFlash.WriteLong(log_gps_alt);
|
||||
DataFlash.WriteLong(log_Ground_Speed);
|
||||
DataFlash.WriteLong(log_Ground_Course);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
// Write an raw accel/gyro data packet. Total length : 28 bytes
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
void Log_Write_Raw()
|
||||
{
|
||||
Vector3f gyro = imu.get_gyro();
|
||||
Vector3f accel = imu.get_accel();
|
||||
gyro *= t7; // Scale up for storage as long integers
|
||||
accel *= t7;
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_RAW_MSG);
|
||||
|
||||
DataFlash.WriteLong((long)gyro.x);
|
||||
DataFlash.WriteLong((long)gyro.y);
|
||||
DataFlash.WriteLong((long)gyro.z);
|
||||
DataFlash.WriteLong((long)accel.x);
|
||||
DataFlash.WriteLong((long)accel.y);
|
||||
DataFlash.WriteLong((long)accel.z);
|
||||
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Read an control tuning packet
|
||||
void Log_Read_Control_Tuning()
|
||||
{
|
||||
float logvar;
|
||||
|
||||
Serial.print("CTUN:");
|
||||
for (int y=1;y<10;y++) {
|
||||
logvar = DataFlash.ReadInt();
|
||||
if(y < 8) logvar = logvar/100.f;
|
||||
if(y == 9) logvar = logvar/10000.f;
|
||||
Serial.print(logvar);
|
||||
Serial.print(comma);
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
|
||||
// Read a nav tuning packet
|
||||
void Log_Read_Nav_Tuning()
|
||||
{
|
||||
Serial.print("NTUN:");
|
||||
Serial.print((float)((uint16_t)DataFlash.ReadInt())/100.0); // Yaw from IMU
|
||||
Serial.print(comma);
|
||||
Serial.print(DataFlash.ReadInt()); // wp_distance
|
||||
Serial.print(comma);
|
||||
Serial.print((float)((uint16_t)DataFlash.ReadInt())/100.0); // target_bearing - Bearing to Target
|
||||
Serial.print(comma);
|
||||
Serial.print((float)((uint16_t)DataFlash.ReadInt())/100.0); // nav_bearing - Bearing to steer
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadInt()/100.0); // Altitude error
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadInt()/100.0); // Airspeed
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadInt()/1000.0); // nav_gain_scaler
|
||||
Serial.println(comma);
|
||||
}
|
||||
|
||||
// Read a performance packet
|
||||
void Log_Read_Performance()
|
||||
{
|
||||
long pm_time;
|
||||
int logvar;
|
||||
|
||||
Serial.print("PM:");
|
||||
pm_time = DataFlash.ReadLong();
|
||||
Serial.print(pm_time);
|
||||
Serial.print(comma);
|
||||
for (int y=1;y<9;y++) {
|
||||
if(y<3 || y>7) logvar = DataFlash.ReadInt();
|
||||
else logvar = DataFlash.ReadByte();
|
||||
//if(y > 7) logvar = logvar/1000.f;
|
||||
Serial.print(logvar);
|
||||
Serial.print(comma);
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
|
||||
// Read a command processing packet
|
||||
void Log_Read_Cmd()
|
||||
{
|
||||
byte logvarb;
|
||||
long logvarl;
|
||||
|
||||
Serial.print("CMD:");
|
||||
for(int i=1;i<4;i++) {
|
||||
logvarb = DataFlash.ReadByte();
|
||||
Serial.print(logvarb,DEC);
|
||||
Serial.print(comma);
|
||||
}
|
||||
for(int i=1;i<4;i++) {
|
||||
logvarl = DataFlash.ReadLong();
|
||||
Serial.print(logvarl,DEC);
|
||||
Serial.print(comma);
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
|
||||
void Log_Read_Startup()
|
||||
{
|
||||
byte logbyte = DataFlash.ReadByte();
|
||||
if (logbyte == TYPE_AIRSTART_MSG)
|
||||
Serial.print("AIR START - ");
|
||||
else if (logbyte == TYPE_GROUNDSTART_MSG)
|
||||
Serial.print("GROUND START - ");
|
||||
else
|
||||
Serial.print("UNKNOWN STARTUP TYPE -");
|
||||
Serial.print(DataFlash.ReadByte(), DEC);
|
||||
Serial.println(" commands in memory");
|
||||
}
|
||||
|
||||
// Read an attitude packet
|
||||
void Log_Read_Attitude()
|
||||
{
|
||||
int log_roll;
|
||||
int log_pitch;
|
||||
uint16_t log_yaw;
|
||||
|
||||
log_roll = DataFlash.ReadInt();
|
||||
log_pitch = DataFlash.ReadInt();
|
||||
log_yaw = (uint16_t)DataFlash.ReadInt();
|
||||
|
||||
Serial.print("ATT:");
|
||||
Serial.print(log_roll);
|
||||
Serial.print(comma);
|
||||
Serial.print(log_pitch);
|
||||
Serial.print(comma);
|
||||
Serial.print(log_yaw);
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
// Read a mode packet
|
||||
void Log_Read_Mode()
|
||||
{
|
||||
byte mode;
|
||||
|
||||
mode = DataFlash.ReadByte();
|
||||
Serial.print("MOD:");
|
||||
switch (mode) {
|
||||
case 0:
|
||||
Serial.println("Manual");
|
||||
break;
|
||||
case 1:
|
||||
Serial.println("Stab");
|
||||
break;
|
||||
case 5:
|
||||
Serial.println("FBW_A");
|
||||
break;
|
||||
case 6:
|
||||
Serial.println("FBW_B");
|
||||
break;
|
||||
case 10:
|
||||
Serial.println("AUTO");
|
||||
break;
|
||||
case 11:
|
||||
Serial.println("RTL");
|
||||
break;
|
||||
case 12:
|
||||
Serial.println("Loiter");
|
||||
break;
|
||||
case 98:
|
||||
Serial.println("AS_COM");
|
||||
break;
|
||||
case 99:
|
||||
Serial.println("GS_COM");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Read a GPS packet
|
||||
void Log_Read_GPS()
|
||||
{
|
||||
|
||||
Serial.print("GPS:");
|
||||
Serial.print(DataFlash.ReadLong()); // Time
|
||||
Serial.print(comma);
|
||||
Serial.print((int)DataFlash.ReadByte()); // Fix
|
||||
Serial.print(comma);
|
||||
Serial.print((int)DataFlash.ReadByte()); // Num of Sats
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadLong()/t7, 7); // Lattitude
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadLong()/t7, 7); // Longitude
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadLong()/100.0); // Baro/gps altitude mix
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadLong()/100.0); // GPS altitude
|
||||
Serial.print(comma);
|
||||
Serial.print((float)DataFlash.ReadLong()/100.0); // Ground Speed
|
||||
Serial.print(comma);
|
||||
Serial.println((float)DataFlash.ReadLong()/100.0); // Ground Course
|
||||
|
||||
}
|
||||
|
||||
// Read a raw accel/gyro packet
|
||||
void Log_Read_Raw()
|
||||
{
|
||||
float logvar;
|
||||
Serial.print("RAW:");
|
||||
for (int y=0;y<6;y++) {
|
||||
logvar = (float)DataFlash.ReadLong()/t7;
|
||||
Serial.print(logvar);
|
||||
Serial.print(comma);
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
|
||||
// Read the DataFlash log memory : Packet Parser
|
||||
void Log_Read(int start_page, int end_page)
|
||||
{
|
||||
byte data;
|
||||
byte log_step=0;
|
||||
int packet_count=0;
|
||||
int page = start_page;
|
||||
|
||||
|
||||
DataFlash.StartRead(start_page);
|
||||
while (page < end_page && page != -1)
|
||||
{
|
||||
data = DataFlash.ReadByte();
|
||||
switch(log_step) //This is a state machine to read the packets
|
||||
{
|
||||
case 0:
|
||||
if(data==HEAD_BYTE1) // Head byte 1
|
||||
log_step++;
|
||||
break;
|
||||
case 1:
|
||||
if(data==HEAD_BYTE2) // Head byte 2
|
||||
log_step++;
|
||||
else
|
||||
log_step = 0;
|
||||
break;
|
||||
case 2:
|
||||
if(data==LOG_ATTITUDE_MSG){
|
||||
Log_Read_Attitude();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_MODE_MSG){
|
||||
Log_Read_Mode();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_CONTROL_TUNING_MSG){
|
||||
Log_Read_Control_Tuning();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_NAV_TUNING_MSG){
|
||||
Log_Read_Nav_Tuning();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_PERFORMANCE_MSG){
|
||||
Log_Read_Performance();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_RAW_MSG){
|
||||
Log_Read_Raw();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_CMD_MSG){
|
||||
Log_Read_Cmd();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_STARTUP_MSG){
|
||||
Log_Read_Startup();
|
||||
log_step++;
|
||||
}else {
|
||||
if(data==LOG_GPS_MSG){
|
||||
Log_Read_GPS();
|
||||
log_step++;
|
||||
} else {
|
||||
Serial.print("Error Reading Packet: ");
|
||||
Serial.print(packet_count);
|
||||
log_step=0; // Restart, we have a problem...
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
if(data==END_BYTE){
|
||||
packet_count++;
|
||||
}else{
|
||||
Serial.print("Error Reading END_BYTE ");
|
||||
Serial.println(data,DEC);
|
||||
}
|
||||
log_step=0; // Restart sequence: new packet...
|
||||
break;
|
||||
}
|
||||
page = DataFlash.GetPage();
|
||||
}
|
||||
Serial.print("Number of packets read: ");
|
||||
Serial.println(packet_count);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,219 @@
|
|||
#ifndef Mavlink_Common_H
|
||||
#define Mavlink_Common_H
|
||||
|
||||
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLIK || GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
||||
|
||||
uint16_t system_type = MAV_FIXED_WING;
|
||||
|
||||
static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
||||
{
|
||||
if (sysid != mavlink_system.sysid)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
else if (compid != mavlink_system.compid)
|
||||
{
|
||||
gcs.send_text(SEVERITY_LOW,"component id mismatch");
|
||||
return 0; // XXX currently not receiving correct compid from gcs
|
||||
}
|
||||
else return 0; // no error
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send low-priority messages at a maximum rate of xx Hertz
|
||||
*
|
||||
* This function sends messages at a lower rate to not exceed the wireless
|
||||
* bandwidth. It sends one message each time it is called until the buffer is empty.
|
||||
* Call this function with xx Hertz to increase/decrease the bandwidth.
|
||||
*/
|
||||
static void mavlink_queued_send(mavlink_channel_t chan)
|
||||
{
|
||||
//send parameters one by one
|
||||
if (global_data.parameter_i < global_data.param_count)
|
||||
{
|
||||
char param_name[ONBOARD_PARAM_NAME_LENGTH]; /// XXX HACK
|
||||
strcpy_P(param_name, getParamName(global_data.parameter_i)); /// XXX HACK
|
||||
mavlink_msg_param_value_send(chan,
|
||||
(int8_t*)param_name,
|
||||
getParamAsFloat(global_data.parameter_i),
|
||||
global_data.param_count,global_data.parameter_i);
|
||||
global_data.parameter_i++;
|
||||
}
|
||||
|
||||
// request waypoints one by one
|
||||
if (global_data.waypoint_receiving &&
|
||||
global_data.waypoint_request_i < get(PARAM_WP_TOTAL))
|
||||
{
|
||||
mavlink_msg_waypoint_request_send(chan,
|
||||
global_data.waypoint_dest_sysid,
|
||||
global_data.waypoint_dest_compid ,global_data.waypoint_request_i);
|
||||
}
|
||||
}
|
||||
|
||||
void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, uint16_t packet_drops)
|
||||
{
|
||||
uint64_t timeStamp = micros();
|
||||
switch(id) {
|
||||
|
||||
case MSG_HEARTBEAT:
|
||||
mavlink_msg_heartbeat_send(chan,system_type,MAV_AUTOPILOT_ARDUPILOTMEGA);
|
||||
break;
|
||||
|
||||
case MSG_EXTENDED_STATUS:
|
||||
{
|
||||
uint8_t mode = MAV_MODE_UNINIT;
|
||||
uint8_t nav_mode = MAV_NAV_VECTOR;
|
||||
|
||||
switch(control_mode) {
|
||||
case MANUAL:
|
||||
mode = MAV_MODE_MANUAL;
|
||||
break;
|
||||
case CIRCLE:
|
||||
mode = MAV_MODE_TEST3;
|
||||
break;
|
||||
case STABILIZE:
|
||||
mode = MAV_MODE_GUIDED;
|
||||
break;
|
||||
case FLY_BY_WIRE_A:
|
||||
mode = MAV_MODE_TEST1;
|
||||
break;
|
||||
case FLY_BY_WIRE_B:
|
||||
mode = MAV_MODE_TEST2;
|
||||
break;
|
||||
case AUTO:
|
||||
mode = MAV_MODE_AUTO;
|
||||
nav_mode = MAV_NAV_WAYPOINT;
|
||||
break;
|
||||
case RTL:
|
||||
mode = MAV_MODE_AUTO;
|
||||
nav_mode = MAV_NAV_RETURNING;
|
||||
break;
|
||||
case LOITER:
|
||||
mode = MAV_MODE_AUTO;
|
||||
nav_mode = MAV_NAV_HOLD;
|
||||
break;
|
||||
case TAKEOFF:
|
||||
mode = MAV_MODE_AUTO;
|
||||
nav_mode = MAV_NAV_LIFTOFF;
|
||||
break;
|
||||
case LAND:
|
||||
mode = MAV_MODE_AUTO;
|
||||
nav_mode = MAV_NAV_LANDING;
|
||||
break;
|
||||
}
|
||||
uint8_t status = MAV_STATE_ACTIVE;
|
||||
uint8_t motor_block = false;
|
||||
|
||||
mavlink_msg_sys_status_send(chan,mode,nav_mode,status,load*1000,
|
||||
battery_voltage1*1000,motor_block,packet_drops);
|
||||
break;
|
||||
}
|
||||
|
||||
case MSG_ATTITUDE:
|
||||
{
|
||||
Vector3f omega = dcm.get_gyro();
|
||||
mavlink_msg_attitude_send(chan,timeStamp,dcm.roll,dcm.pitch,dcm.yaw,
|
||||
omega.x,omega.y,omega.z);
|
||||
break;
|
||||
}
|
||||
case MSG_LOCATION:
|
||||
{
|
||||
float gamma = dcm.pitch; // neglecting angle of attack for now
|
||||
float yaw = dcm.yaw;
|
||||
mavlink_msg_global_position_send(chan,timeStamp,current_loc.lat/1.0e7,
|
||||
current_loc.lng/1.0e7,current_loc.alt/1.0e2,gps.ground_speed/1.0e2*cos(gamma)*cos(yaw),
|
||||
gps.ground_speed/1.0e2*cos(gamma)*sin(yaw),gps.ground_speed/1.0e2*sin(gamma));
|
||||
break;
|
||||
}
|
||||
case MSG_LOCAL_LOCATION:
|
||||
{
|
||||
float gamma = dcm.pitch; // neglecting angle of attack for now
|
||||
float yaw = dcm.yaw;
|
||||
mavlink_msg_local_position_send(chan,timeStamp,ToRad((current_loc.lat-home.lat)/1.0e7)*radius_of_earth,
|
||||
ToRad((current_loc.lng-home.lng)/1.0e7)*radius_of_earth*cos(ToRad(home.lat/1.0e7)),
|
||||
(current_loc.alt-home.alt)/1.0e2, gps.ground_speed/1.0e2*cos(gamma)*cos(yaw),
|
||||
gps.ground_speed/1.0e2*cos(gamma)*sin(yaw),gps.ground_speed/1.0e2*sin(gamma));
|
||||
break;
|
||||
}
|
||||
case MSG_GPS_RAW:
|
||||
{
|
||||
mavlink_msg_gps_raw_send(chan,timeStamp,gps.status(),
|
||||
gps.latitude/1.0e7,gps.longitude/1.0e7,gps.altitude/100.0,
|
||||
2.0,10.0,gps.ground_speed/100.0,gps.ground_course/100.0);
|
||||
break;
|
||||
}
|
||||
case MSG_AIRSPEED:
|
||||
{
|
||||
mavlink_msg_airspeed_send(chan,float(airspeed)/100.0);
|
||||
break;
|
||||
}
|
||||
case MSG_SERVO_OUT:
|
||||
{
|
||||
uint8_t rssi = 1; // TODO: can we calculated this?
|
||||
// receive signal strength 0(0%)-255(100%)
|
||||
Serial.printf_P(PSTR("sending servo out: %d %d %d %d\n"),
|
||||
servo_out[0],servo_out[1], servo_out[2], servo_out[3]);
|
||||
mavlink_msg_rc_channels_scaled_send(chan,
|
||||
servo_out[0],servo_out[1],
|
||||
servo_out[2]*100, // account for throttle scaling 0-100
|
||||
servo_out[3],servo_out[4],servo_out[5],
|
||||
servo_out[6],servo_out[7],rssi);
|
||||
break;
|
||||
}
|
||||
case MSG_RADIO_OUT:
|
||||
{
|
||||
uint8_t rssi = 1; // TODO: can we calculated this?
|
||||
// receive signal strength 0(0%)-255(100%)
|
||||
mavlink_msg_rc_channels_raw_send(chan,
|
||||
radio_out[0],radio_out[1],radio_out[2],
|
||||
radio_out[3],radio_out[4],radio_out[5],
|
||||
radio_out[6],radio_out[7],rssi);
|
||||
break;
|
||||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
case MSG_RAW_IMU:
|
||||
{
|
||||
Vector3f accel = imu.get_accel();
|
||||
Vector3f gyro = imu.get_gyro();
|
||||
//Serial.printf_P(PSTR("sending accel: %f %f %f\n"), accel.x, accel.y, accel.z);
|
||||
//Serial.printf_P(PSTR("sending gyro: %f %f %f\n"), gyro.x, gyro.y, gyro.z);
|
||||
mavlink_msg_raw_imu_send(chan,timeStamp,
|
||||
accel.x*1000.0/gravity,accel.y*1000.0/gravity,accel.z*1000.0/gravity,
|
||||
gyro.x*1000.0,gyro.y*1000.0,gyro.z*1000.0,
|
||||
compass.mag_x,compass.mag_y,compass.mag_z);
|
||||
mavlink_msg_raw_pressure_send(chan,timeStamp,
|
||||
adc.Ch(AIRSPEED_CH),pitot.RawPress,0);
|
||||
break;
|
||||
}
|
||||
#endif // HIL_PROTOCOL != HIL_PROTOCOL_ATTITUDE
|
||||
|
||||
case MSG_GPS_STATUS:
|
||||
{
|
||||
mavlink_msg_gps_status_send(chan,gps.num_sats,NULL,NULL,NULL,NULL,NULL);
|
||||
break;
|
||||
}
|
||||
|
||||
case MSG_CURRENT_WAYPOINT:
|
||||
{
|
||||
mavlink_msg_waypoint_current_send(chan,get(PARAM_WP_INDEX));
|
||||
break;
|
||||
}
|
||||
|
||||
defualt:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void mavlink_send_text(mavlink_channel_t chan, uint8_t severity, const char *str)
|
||||
{
|
||||
mavlink_msg_statustext_send(chan,severity,(const int8_t*)str);
|
||||
}
|
||||
|
||||
void mavlink_acknowledge(mavlink_channel_t chan, uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
}
|
||||
|
||||
#endif // mavlink in use
|
||||
|
||||
#endif // inclusion guard
|
|
@ -0,0 +1,118 @@
|
|||
<PID> = {servoroll|servopitch|servorudder|navroll|navpitchasp|navpitchalt|throttlete|throttlealt}
|
||||
show
|
||||
heartbeat
|
||||
attitude
|
||||
location
|
||||
command
|
||||
severity <N>
|
||||
hide
|
||||
heartbeat
|
||||
attitude
|
||||
location
|
||||
command
|
||||
all
|
||||
copy cmd <src> <target>
|
||||
echo <text>
|
||||
groundstart
|
||||
inithome
|
||||
k -?
|
||||
print
|
||||
altitude
|
||||
altmaxcruiseerr
|
||||
aspmaxcruiseerr
|
||||
attitude
|
||||
commands
|
||||
ctrlmode
|
||||
curwaypts
|
||||
flightmodes
|
||||
holdalt
|
||||
imax <PID>
|
||||
kp <PID>
|
||||
ki <PID>
|
||||
kd <PID>
|
||||
kff {pitchcomp|ruddermix|pitchtothrottle}
|
||||
kpitchcruise
|
||||
location
|
||||
navrolllimit
|
||||
navsettings
|
||||
pitchmax
|
||||
pitchmin
|
||||
pitchtarget
|
||||
pressure
|
||||
rlocation [home]
|
||||
speed
|
||||
targetaxis1
|
||||
targetaxis2
|
||||
targetneutral
|
||||
throttlecruise
|
||||
throttlemax
|
||||
throttlemin
|
||||
tuning
|
||||
release
|
||||
all
|
||||
ctrlmode
|
||||
rcin
|
||||
reset commands
|
||||
rtl
|
||||
set
|
||||
altmaxcruiseerr <X>
|
||||
aspmaxcruiseerr <X>
|
||||
cmd <commandindex> <commandtype> <param1> {here|{<alt> <lat> <lng>}}
|
||||
commandtype = {waypoint|takeoff|land|landoptions|loiter|loiternturns|loitertime|delay|resetindex|airspeedcruise|throttlecruise|resethome|index|rtl|relay|servo}
|
||||
cmdcount <N>
|
||||
cmdindex <N>
|
||||
cruise <X>
|
||||
ctrlmode {manual|circle|stabilize|fbwa|fbwb|auto|rtl|loiter|takeoff|land|radio}
|
||||
holdalt <X>
|
||||
imax <PID>
|
||||
kp <PID>
|
||||
ki <PID>
|
||||
kd <PID>
|
||||
kff {pitchcomp|ruddermix|pitchtothrottle} <X>
|
||||
kpitchcruise <X>
|
||||
loiterradius <X>
|
||||
navrolllimit <X>
|
||||
pitchmax <X>
|
||||
pitchmin <X>
|
||||
pitchtarget <X>
|
||||
rcin<N> <X>
|
||||
rcout<N> <X>
|
||||
target alt <X>
|
||||
target here
|
||||
targetaxis1 <X> <Y> <Z>
|
||||
targetaxis2 <X> <Y> <Z>
|
||||
targetmode <N>
|
||||
targetneutral <X> <Y> <Z>
|
||||
target <X> <Y> <Z>
|
||||
throttlecruise <X>
|
||||
throttlefailsafe <N>
|
||||
throttlefailsafeaction <N>
|
||||
throttlemax <X>
|
||||
throttlemin <X>
|
||||
wpradius <X>
|
||||
xtrackentryangle <X>
|
||||
xtrackgain <X>
|
||||
status
|
||||
climb
|
||||
control
|
||||
cruise
|
||||
gps
|
||||
landing
|
||||
loiter
|
||||
mixing
|
||||
navigation
|
||||
navpitch
|
||||
navroll
|
||||
pid <PID>
|
||||
rc
|
||||
rcinputch
|
||||
rcin
|
||||
rcout
|
||||
rcpwm
|
||||
rctrim
|
||||
system
|
||||
takeoff
|
||||
telemetry
|
||||
throttle
|
||||
waypoints
|
||||
|
|
@ -0,0 +1,92 @@
|
|||
struct DataPoint {
|
||||
unsigned long x;
|
||||
long y;
|
||||
};
|
||||
|
||||
DataPoint history[ALTITUDE_HISTORY_LENGTH]; // Collection of (x,y) points to regress a rate of change from
|
||||
unsigned char index; // Index in history for the current data point
|
||||
|
||||
unsigned long xoffset;
|
||||
unsigned char n;
|
||||
|
||||
// Intermediate variables for regression calculation
|
||||
long xi;
|
||||
long yi;
|
||||
long xiyi;
|
||||
unsigned long xi2;
|
||||
|
||||
|
||||
void add_altitude_data(unsigned long xl, long y)
|
||||
{
|
||||
unsigned char i;
|
||||
int dx;
|
||||
|
||||
//Reset the regression if our X variable overflowed
|
||||
if (xl < xoffset)
|
||||
n = 0;
|
||||
|
||||
//To allow calculation of sum(xi*yi), make sure X hasn't exceeded 2^32/2^15/length
|
||||
if (xl - xoffset > 131072/ALTITUDE_HISTORY_LENGTH)
|
||||
n = 0;
|
||||
|
||||
if (n == ALTITUDE_HISTORY_LENGTH) {
|
||||
xi -= history[index].x;
|
||||
yi -= history[index].y;
|
||||
xiyi -= (long)history[index].x * history[index].y;
|
||||
xi2 -= history[index].x * history[index].x;
|
||||
} else {
|
||||
if (n == 0) {
|
||||
xoffset = xl;
|
||||
xi = 0;
|
||||
yi = 0;
|
||||
xiyi = 0;
|
||||
xi2 = 0;
|
||||
}
|
||||
n++;
|
||||
}
|
||||
|
||||
history[index].x = xl - xoffset;
|
||||
history[index].y = y;
|
||||
|
||||
xi += history[index].x;
|
||||
yi += history[index].y;
|
||||
xiyi += (long)history[index].x * history[index].y;
|
||||
xi2 += history[index].x * history[index].x;
|
||||
|
||||
if (++index >= ALTITUDE_HISTORY_LENGTH)
|
||||
index = 0;
|
||||
}
|
||||
|
||||
void recalc_climb_rate()
|
||||
{
|
||||
float slope = ((float)xi*(float)yi - ALTITUDE_HISTORY_LENGTH*(float)xiyi) / ((float)xi*(float)xi - ALTITUDE_HISTORY_LENGTH*(float)xi2);
|
||||
climb_rate = (int)(slope*100);
|
||||
}
|
||||
|
||||
void print_climb_debug_info()
|
||||
{
|
||||
unsigned char i, j;
|
||||
recalc_climb_rate();
|
||||
SendDebugln_P("Climb rate:");
|
||||
for (i=0; i<ALTITUDE_HISTORY_LENGTH; i++) {
|
||||
j = i + index;
|
||||
if (j >= ALTITUDE_HISTORY_LENGTH) j -= ALTITUDE_HISTORY_LENGTH;
|
||||
SendDebug_P(" ");
|
||||
SendDebug(j,DEC);
|
||||
SendDebug_P(": ");
|
||||
SendDebug(history[j].x,DEC);
|
||||
SendDebug_P(", ");
|
||||
SendDebugln(history[j].y,DEC);
|
||||
}
|
||||
SendDebug_P(" sum(xi) = ");
|
||||
SendDebugln(xi,DEC);
|
||||
SendDebug_P(" sum(yi) = ");
|
||||
SendDebugln(yi,DEC);
|
||||
SendDebug_P(" sum(xi*yi) = ");
|
||||
SendDebugln(xiyi,DEC);
|
||||
SendDebug_P(" sum(xi^2) = ");
|
||||
SendDebugln(xi2,DEC);
|
||||
SendDebug_P(" Climb rate = ");
|
||||
SendDebug((float)climb_rate/100,2);
|
||||
SendDebugln_P(" m/s");
|
||||
}
|
|
@ -0,0 +1,76 @@
|
|||
ArduPilotMega 1.0.0 Commands
|
||||
|
||||
Command Structure in bytes
|
||||
0 0x00 byte Command ID
|
||||
1 0x01 byte Parameter 1
|
||||
2 0x02 int Parameter 2
|
||||
3 0x03 ..
|
||||
4 0x04 long Parameter 3
|
||||
5 0x05 ..
|
||||
6 0x06 ..
|
||||
7 0x07 ..
|
||||
8 0x08 long Parameter 4
|
||||
9 0x09 ..
|
||||
10 0x0A ..
|
||||
11 0x0B ..
|
||||
|
||||
0x00 Reserved
|
||||
....
|
||||
0x0F Reserved
|
||||
|
||||
***********************************
|
||||
Commands 0x10 to 0x2F are commands that have a end criteria, eg "reached waypoint" or "reached altitude"
|
||||
***********************************
|
||||
Command ID Name Parameter 1 Altitude Latitude Longitude
|
||||
0x10 CMD_WAYPOINT - altitude lat lon
|
||||
0x11 CMD_LOITER (indefinitely) - altitude lat lon
|
||||
0x12 CMD_LOITER_N_TURNS turns altitude lat lon
|
||||
0x13 CMD_LOITER_TIME time (seconds*10) altitude lat lon
|
||||
0x14 CMD_RTL - altitude lat lon
|
||||
0x15 CMD_LAND - altitude lat lon
|
||||
0x16 CMD_TAKEOFF takeoff pitch altitude - -
|
||||
NOTE: for command 0x16 the value takeoff pitch specifies the minimum pitch for the case with airspeed sensor and the target pitch for the case without.
|
||||
|
||||
|
||||
***********************************
|
||||
May Commands - these commands are optional to finish
|
||||
Command ID Name Parameter 1 Parameter 2 Parameter 3 Parameter 4
|
||||
0x20 CMD_DELAY - - time (milliseconds) -
|
||||
0x21 CMD_CLIMB rate (cm/sec) alt (finish) - -
|
||||
0x22 CMD_LAND_OPTIONS distance to WP airspeed m/s, throttle %, pitch deg
|
||||
|
||||
|
||||
|
||||
***********************************
|
||||
Unexecuted commands >= 0x20 are dropped when ready for the next command <= 0x1F so plan/queue commands accordingly!
|
||||
For example if you had a string of 0x21 commands following a 0x10 command that had not finished when the waypoint was
|
||||
reached, the unexecuted 0x21 commands would be skipped and the next command <= 0x1F would be loaded
|
||||
***********************************
|
||||
Now Commands - these commands are executed once until no more new now commands are available
|
||||
0x31 CMD_RESET_INDEX
|
||||
0x32 CMD_GOTO_INDEX index repeat count
|
||||
0x33 CMD_GETVAR_INDEX variable ID
|
||||
0x34 CMD_SENDVAR_INDEX off/on = 0/1
|
||||
0x35 CMD_TELEMETRY off/on = 0/1
|
||||
|
||||
0x40 CMD_THROTTLE_CRUISE speed
|
||||
0x41 CMD_AIRSPEED_CRUISE speed
|
||||
0x44 CMD_RESET_HOME altitude lat lon
|
||||
|
||||
0x60 CMD_KP_GAIN array index gain value*100,000
|
||||
0x61 CMD_KI_GAIN array index gain value*100,000
|
||||
0x62 CMD_KD_GAIN array index gain value*100,000
|
||||
0x63 CMD_KI_MAX array index gain value*100,000
|
||||
0x64 CMD_KFF_GAIN array index gain value*100,000
|
||||
|
||||
0x70 CMD_RADIO_TRIM array index value
|
||||
0x71 CMD_RADIO_MAX array index value
|
||||
0x72 CMD_RADIO_MIN array index value
|
||||
0x73 CMD_ELEVON_TRIM array index value (index 0 = elevon 1 trim, 1 = elevon 2 trim)
|
||||
0x75 CMD_INDEX index
|
||||
|
||||
0x80 CMD_REPEAT type value delay in sec repeat count
|
||||
0x81 CMD_RELAY (0,1 to change swicth position)
|
||||
0x82 CMD_SERVO number value
|
||||
|
||||
|
|
@ -0,0 +1,239 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
void init_commands()
|
||||
{
|
||||
//read_EEPROM_waypoint_info();
|
||||
set(PARAM_WP_INDEX,0);
|
||||
command_must_index = 0;
|
||||
command_may_index = 0;
|
||||
next_command.id = CMD_BLANK;
|
||||
}
|
||||
|
||||
void update_auto()
|
||||
{
|
||||
if (get(PARAM_WP_INDEX) == get(PARAM_WP_TOTAL)){
|
||||
return_to_launch();
|
||||
//wp_index = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void reload_commands()
|
||||
{
|
||||
init_commands();
|
||||
//read_command_index(); // Get wp_index = command_must_index from EEPROM
|
||||
if(get(PARAM_WP_INDEX) > 0){
|
||||
decrement_WP_index;
|
||||
}
|
||||
}
|
||||
|
||||
// Getters
|
||||
// -------
|
||||
struct Location get_wp_with_index(int i)
|
||||
{
|
||||
struct Location temp;
|
||||
long mem;
|
||||
|
||||
|
||||
// Find out proper location in memory by using the start_byte position + the index
|
||||
// --------------------------------------------------------------------------------
|
||||
if (i > get(PARAM_WP_TOTAL)) {
|
||||
temp.id = CMD_BLANK;
|
||||
}else{
|
||||
// read WP position
|
||||
mem = (WP_START_BYTE) + (i * WP_SIZE);
|
||||
temp.id = eeprom_read_byte((uint8_t*)mem);
|
||||
mem++;
|
||||
temp.p1 = eeprom_read_byte((uint8_t*)mem);
|
||||
mem++;
|
||||
temp.alt = (long)eeprom_read_dword((uint32_t*)mem);
|
||||
mem += 4;
|
||||
temp.lat = (long)eeprom_read_dword((uint32_t*)mem);
|
||||
mem += 4;
|
||||
temp.lng = (long)eeprom_read_dword((uint32_t*)mem);
|
||||
}
|
||||
return temp;
|
||||
}
|
||||
|
||||
// Setters
|
||||
// -------
|
||||
void set_wp_with_index(struct Location temp, int i)
|
||||
{
|
||||
|
||||
i = constrain(i,0,get(PARAM_WP_TOTAL));
|
||||
uint32_t mem = WP_START_BYTE + (i * WP_SIZE);
|
||||
|
||||
eeprom_write_byte((uint8_t *) mem, temp.id);
|
||||
|
||||
mem++;
|
||||
eeprom_write_byte((uint8_t *) mem, temp.p1);
|
||||
|
||||
mem++;
|
||||
eeprom_write_dword((uint32_t *) mem, temp.alt);
|
||||
|
||||
mem += 4;
|
||||
eeprom_write_dword((uint32_t *) mem, temp.lat);
|
||||
|
||||
mem += 4;
|
||||
eeprom_write_dword((uint32_t *) mem, temp.lng);
|
||||
}
|
||||
|
||||
void increment_WP_index()
|
||||
{
|
||||
if(get(PARAM_WP_INDEX) < get(PARAM_WP_TOTAL)){
|
||||
set(PARAM_WP_INDEX, get(PARAM_WP_INDEX) +1);
|
||||
SendDebug("MSG <increment_WP_index> WP index is incremented to ");
|
||||
SendDebugln(get(PARAM_WP_INDEX),DEC);
|
||||
}else{
|
||||
SendDebug("MSG <increment_WP_index> Failed to increment WP index of ");
|
||||
SendDebugln(get(PARAM_WP_INDEX),DEC);
|
||||
}
|
||||
}
|
||||
void decrement_WP_index()
|
||||
{
|
||||
if(get(PARAM_WP_INDEX) > 0){
|
||||
set(PARAM_WP_INDEX, get(PARAM_WP_INDEX) -1);
|
||||
}
|
||||
}
|
||||
|
||||
long read_alt_to_hold()
|
||||
{
|
||||
byte options = get(PARAM_CONFIG);
|
||||
|
||||
// save the alitude above home option
|
||||
if(options & HOLD_ALT_ABOVE_HOME){
|
||||
int32_t temp = get(PARAM_ALT_HOLD_HOME);
|
||||
return temp + home.alt;
|
||||
}else{
|
||||
return current_loc.alt;
|
||||
}
|
||||
}
|
||||
|
||||
void loiter_at_location()
|
||||
{
|
||||
next_WP = current_loc;
|
||||
}
|
||||
|
||||
// add a new command at end of command set to RTL.
|
||||
void return_to_launch(void)
|
||||
{
|
||||
//so we know where we are navigating from
|
||||
next_WP = current_loc;
|
||||
|
||||
// home is WP 0
|
||||
// ------------
|
||||
set(PARAM_WP_INDEX,0);
|
||||
|
||||
// Loads WP from Memory
|
||||
// --------------------
|
||||
set_next_WP(&home);
|
||||
|
||||
// Altitude to hold over home
|
||||
// Set by configuration tool
|
||||
// -------------------------
|
||||
next_WP.alt = read_alt_to_hold();
|
||||
}
|
||||
|
||||
struct Location get_LOITER_home_wp()
|
||||
{
|
||||
// read home position
|
||||
struct Location temp = get_wp_with_index(0);
|
||||
temp.id = CMD_LOITER;
|
||||
|
||||
temp.alt = read_alt_to_hold();
|
||||
return temp;
|
||||
}
|
||||
|
||||
/*
|
||||
This function stores waypoint commands
|
||||
It looks to see what the next command type is and finds the last command.
|
||||
*/
|
||||
void set_next_WP(struct Location *wp)
|
||||
{
|
||||
//GCS.send_text(SEVERITY_LOW,"load WP");
|
||||
SendDebug("MSG <set_next_wp> wp_index: ");
|
||||
SendDebugln(get(PARAM_WP_INDEX),DEC);
|
||||
gcs.send_message(MSG_COMMAND_LIST, get(PARAM_WP_INDEX));
|
||||
|
||||
// copy the current WP into the OldWP slot
|
||||
// ---------------------------------------
|
||||
prev_WP = next_WP;
|
||||
// Load the next_WP slot
|
||||
// ---------------------
|
||||
next_WP = *wp;
|
||||
// offset the altitude relative to home position
|
||||
// ---------------------------------------------
|
||||
next_WP.alt += home.alt;
|
||||
|
||||
// used to control FBW and limit the rate of climb
|
||||
// -----------------------------------------------
|
||||
target_altitude = current_loc.alt;
|
||||
if(prev_WP.id != CMD_TAKEOFF && (next_WP.id == CMD_WAYPOINT || next_WP.id == CMD_LAND))
|
||||
offset_altitude = next_WP.alt - prev_WP.alt;
|
||||
else
|
||||
offset_altitude = 0;
|
||||
|
||||
|
||||
// zero out our loiter vals to watch for missed waypoints
|
||||
loiter_delta = 0;
|
||||
loiter_sum = 0;
|
||||
loiter_total = 0;
|
||||
|
||||
float rads = (abs(next_WP.lat)/t7) * 0.0174532925;
|
||||
//377,173,810 / 10,000,000 = 37.717381 * 0.0174532925 = 0.658292482926943
|
||||
scaleLongDown = cos(rads);
|
||||
scaleLongUp = 1.0f/cos(rads);
|
||||
|
||||
// this is handy for the groundstation
|
||||
wp_totalDistance = getDistance(¤t_loc, &next_WP);
|
||||
wp_distance = wp_totalDistance;
|
||||
|
||||
gcs.print_current_waypoints();
|
||||
|
||||
target_bearing = get_bearing(¤t_loc, &next_WP);
|
||||
old_target_bearing = target_bearing;
|
||||
// this is used to offset the shrinking longitude as we go towards the poles
|
||||
|
||||
// set a new crosstrack bearing
|
||||
// ----------------------------
|
||||
reset_crosstrack();
|
||||
}
|
||||
|
||||
|
||||
// run this at setup on the ground
|
||||
// -------------------------------
|
||||
void init_home()
|
||||
{
|
||||
SendDebugln("MSG: <init_home> init home");
|
||||
|
||||
// Extra read just in case
|
||||
// -----------------------
|
||||
//gps.Read();
|
||||
|
||||
// block until we get a good fix
|
||||
// -----------------------------
|
||||
while (!gps.new_data || !gps.fix) {
|
||||
gps.update();
|
||||
}
|
||||
home.id = CMD_WAYPOINT;
|
||||
home.lng = gps.longitude; // Lon * 10**7
|
||||
home.lat = gps.latitude; // Lat * 10**7
|
||||
home.alt = gps.altitude;
|
||||
home_is_set = TRUE;
|
||||
|
||||
// ground altitude in centimeters for pressure alt calculations
|
||||
// ------------------------------------------------------------
|
||||
ground_alt = gps.altitude;
|
||||
press_alt = gps.altitude; // Set initial value for filter
|
||||
//save_pressure_data();
|
||||
|
||||
// Save Home to EEPROM
|
||||
// -------------------
|
||||
set_wp_with_index(home, 0);
|
||||
|
||||
// Save prev loc
|
||||
// -------------
|
||||
prev_WP = home;
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,466 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
// called by 10 Hz loop
|
||||
// --------------------
|
||||
void update_commands(void)
|
||||
{
|
||||
// This function loads commands into three buffers
|
||||
// when a new command is loaded, it is processed with process_XXX()
|
||||
// ----------------------------------------------------------------
|
||||
if((home_is_set == FALSE) || (control_mode != AUTO)){
|
||||
return; // don't do commands
|
||||
}
|
||||
|
||||
if(control_mode == AUTO){
|
||||
load_next_command();
|
||||
process_next_command();
|
||||
}
|
||||
|
||||
//verify_must();
|
||||
//verify_may();
|
||||
}
|
||||
|
||||
|
||||
void load_next_command()
|
||||
{
|
||||
// fetch next command if it's empty
|
||||
// --------------------------------
|
||||
if(next_command.id == CMD_BLANK){
|
||||
next_command = get_wp_with_index(get(PARAM_WP_INDEX)+1);
|
||||
if(next_command.id != CMD_BLANK){
|
||||
//SendDebug("MSG <load_next_command> fetch found new cmd from list at index ");
|
||||
//SendDebug((get(PARAM_WP_INDEX)+1),DEC);
|
||||
//SendDebug(" with cmd id ");
|
||||
//SendDebugln(next_command.id,DEC);
|
||||
}
|
||||
}
|
||||
|
||||
// If the preload failed, return or just Loiter
|
||||
// generate a dynamic command for RTL
|
||||
// --------------------------------------------
|
||||
if(next_command.id == CMD_BLANK){
|
||||
// we are out of commands!
|
||||
gcs.send_text(SEVERITY_LOW,"out of commands!");
|
||||
//SendDebug("MSG <load_next_command> out of commands, get(PARAM_WP_INDEX): ");
|
||||
//SendDebugln(get(PARAM_WP_INDEX),DEC);
|
||||
|
||||
|
||||
switch (control_mode){
|
||||
case LAND:
|
||||
// don't get a new command
|
||||
break;
|
||||
|
||||
default:
|
||||
next_command = get_LOITER_home_wp();
|
||||
//SendDebug("MSG <load_next_command> Preload RTL cmd id: ");
|
||||
//SendDebugln(next_command.id,DEC);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void process_next_command()
|
||||
{
|
||||
// these are waypoint/Must commands
|
||||
// ---------------------------------
|
||||
if (command_must_index == 0){ // no current command loaded
|
||||
if (next_command.id >= 0x10 && next_command.id <= 0x1F ){
|
||||
increment_WP_index();
|
||||
//save_command_index(); // to Recover from in air Restart
|
||||
command_must_index = get(PARAM_WP_INDEX);
|
||||
|
||||
//SendDebug("MSG <process_next_command> new command_must_id ");
|
||||
//SendDebug(next_command.id,DEC);
|
||||
//SendDebug(" index:");
|
||||
//SendDebugln(command_must_index,DEC);
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_CMD)
|
||||
Log_Write_Cmd(get(PARAM_WP_INDEX), &next_command);
|
||||
process_must();
|
||||
}
|
||||
}
|
||||
|
||||
// these are May commands
|
||||
// ----------------------
|
||||
if (command_may_index == 0){
|
||||
if (next_command.id >= 0x20 && next_command.id <= 0x2F ){
|
||||
increment_WP_index();// this command is from the command list in EEPROM
|
||||
command_may_index = get(PARAM_WP_INDEX);
|
||||
//Serial.print("new command_may_index ");
|
||||
//Serial.println(command_may_index,DEC);
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_CMD)
|
||||
Log_Write_Cmd(get(PARAM_WP_INDEX), &next_command);
|
||||
process_may();
|
||||
}
|
||||
}
|
||||
|
||||
// these are do it now commands
|
||||
// ---------------------------
|
||||
if (next_command.id >= 0x30){
|
||||
increment_WP_index();// this command is from the command list in EEPROM
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_CMD)
|
||||
Log_Write_Cmd(get(PARAM_WP_INDEX), &next_command);
|
||||
process_now();
|
||||
}
|
||||
|
||||
}
|
||||
/*
|
||||
These functions implement the waypoint commands.
|
||||
*/
|
||||
void process_must()
|
||||
{
|
||||
//SendDebug("process must index: ");
|
||||
//SendDebugln(command_must_index,DEC);
|
||||
|
||||
gcs.send_text(SEVERITY_LOW,"New cmd: <process_must>");
|
||||
gcs.send_message(MSG_COMMAND_LIST, get(PARAM_WP_INDEX));
|
||||
|
||||
// clear May indexes
|
||||
command_may_index = 0;
|
||||
command_may_ID = 0;
|
||||
|
||||
command_must_ID = next_command.id;
|
||||
|
||||
// loads the waypoint into Next_WP struct
|
||||
// --------------------------------------
|
||||
set_next_WP(&next_command);
|
||||
|
||||
// invalidate command so a new one is loaded
|
||||
// -----------------------------------------
|
||||
next_command.id = 0;
|
||||
|
||||
// reset navigation integrators
|
||||
// -------------------------
|
||||
reset_I();
|
||||
|
||||
switch(command_must_ID){
|
||||
|
||||
case CMD_TAKEOFF: // TAKEOFF!
|
||||
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
|
||||
takeoff_pitch = (int)next_command.p1 * 100;
|
||||
takeoff_altitude = (int)next_command.alt;
|
||||
next_WP.lat = home.lat + 1000; // so we don't have bad calcs
|
||||
next_WP.lng = home.lng + 1000; // so we don't have bad calcs
|
||||
takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction
|
||||
break;
|
||||
|
||||
case CMD_WAYPOINT: // Navigate to Waypoint
|
||||
break;
|
||||
|
||||
case CMD_LAND: // LAND to Waypoint
|
||||
break;
|
||||
|
||||
case CMD_LOITER: // Loiter indefinitely
|
||||
break;
|
||||
|
||||
case CMD_LOITER_N_TURNS: // Loiter N Times
|
||||
loiter_total = next_command.p1 * 360;
|
||||
break;
|
||||
|
||||
case CMD_LOITER_TIME:
|
||||
loiter_time = millis();
|
||||
loiter_time_max = next_command.p1 * 10000; // seconds * 10 * 1000
|
||||
break;
|
||||
|
||||
case CMD_RTL:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void process_may()
|
||||
{
|
||||
//Serial.print("process_may cmd# ");
|
||||
//Serial.println(get(PARAM_WP_INDEX),DEC);
|
||||
command_may_ID = next_command.id;
|
||||
|
||||
// invalidate command so a new one is loaded
|
||||
// -----------------------------------------
|
||||
next_command.id = 0;
|
||||
|
||||
gcs.send_text(SEVERITY_LOW,"<process_may> New may command loaded:");
|
||||
gcs.send_message(MSG_COMMAND_LIST, get(PARAM_WP_INDEX));
|
||||
// do the command
|
||||
// --------------
|
||||
switch(command_may_ID){
|
||||
|
||||
case CMD_DELAY: // Navigate to Waypoint
|
||||
delay_start = millis();
|
||||
delay_timeout = next_command.lat;
|
||||
break;
|
||||
|
||||
case CMD_LAND_OPTIONS: // Land this puppy
|
||||
gcs.send_text(SEVERITY_LOW,"Landing options set");
|
||||
|
||||
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
|
||||
landing_pitch = next_command.lng * 100;
|
||||
set(PARAM_TRIM_AIRSPEED, next_command.alt * 100);
|
||||
set(PARAM_TRIM_THROTTLE,next_command.lat);
|
||||
landing_distance = next_command.p1;
|
||||
//landing_roll = command.lng;
|
||||
|
||||
SendDebug("MSG: throttle_cruise = ");
|
||||
SendDebugln(get(PARAM_TRIM_THROTTLE),DEC);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void process_now()
|
||||
{
|
||||
const float t5 = 100000.0;
|
||||
//Serial.print("process_now cmd# ");
|
||||
//Serial.println(get(PARAM_WP_INDEX),DEC);
|
||||
|
||||
byte id = next_command.id;
|
||||
|
||||
// invalidate command so a new one is loaded
|
||||
// -----------------------------------------
|
||||
next_command.id = 0;
|
||||
|
||||
gcs.send_text(SEVERITY_LOW, "<process_now> New now command loaded: ");
|
||||
gcs.send_message(MSG_COMMAND_LIST, get(PARAM_WP_INDEX));
|
||||
|
||||
// do the command
|
||||
// --------------
|
||||
switch(id){
|
||||
|
||||
//case CMD_AP_MODE:
|
||||
//next_command.p1 = constrain(next_command.p1, MANUAL, LAND);
|
||||
//set_mode(next_command.p1);
|
||||
//break;
|
||||
|
||||
case CMD_RESET_INDEX:
|
||||
init_commands();
|
||||
break;
|
||||
|
||||
case CMD_GETVAR_INDEX:
|
||||
//
|
||||
break;
|
||||
|
||||
case CMD_SENDVAR_INDEX:
|
||||
//
|
||||
break;
|
||||
|
||||
case CMD_TELEMETRY:
|
||||
//
|
||||
break;
|
||||
|
||||
case CMD_AIRSPEED_CRUISE:
|
||||
set(PARAM_TRIM_AIRSPEED,next_command.p1 * 100);
|
||||
break;
|
||||
|
||||
case CMD_THROTTLE_CRUISE:
|
||||
set(PARAM_TRIM_THROTTLE,next_command.p1);
|
||||
break;
|
||||
|
||||
case CMD_RESET_HOME:
|
||||
init_home();
|
||||
break;
|
||||
|
||||
case CMD_KP_GAIN:
|
||||
pid_index[next_command.p1]->kP(next_command.alt/t5);
|
||||
pid_index[next_command.p1]->save_gains();
|
||||
break;
|
||||
case CMD_KI_GAIN:
|
||||
pid_index[next_command.p1]->kI(next_command.alt/t5);
|
||||
pid_index[next_command.p1]->save_gains();
|
||||
break;
|
||||
case CMD_KD_GAIN:
|
||||
pid_index[next_command.p1]->kD(next_command.alt/t5);
|
||||
pid_index[next_command.p1]->save_gains();
|
||||
break;
|
||||
|
||||
case CMD_KI_MAX:
|
||||
pid_index[next_command.p1]->imax(next_command.alt/t5);
|
||||
pid_index[next_command.p1]->save_gains();
|
||||
break;
|
||||
|
||||
case CMD_KFF_GAIN:
|
||||
{
|
||||
float val = next_command.alt/t5;
|
||||
switch(next_command.p1)
|
||||
{
|
||||
case CASE_PITCH_COMP: set(PARAM_KFF_PTCHCOMP,val); break;
|
||||
case CASE_RUDDER_MIX: set(PARAM_KFF_RDDRMIX,val); break;
|
||||
case CASE_P_TO_T: set(PARAM_KFF_PTCH2THR,val); break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case CMD_RADIO_TRIM:
|
||||
set_radio_trim(next_command.p1,next_command.alt);
|
||||
break;
|
||||
|
||||
case CMD_RADIO_MAX:
|
||||
set_radio_max(next_command.p1,next_command.alt);
|
||||
break;
|
||||
|
||||
case CMD_RADIO_MIN:
|
||||
set_radio_min(next_command.p1,next_command.alt);
|
||||
break;
|
||||
|
||||
case CMD_REPEAT:
|
||||
new_event(&next_command);
|
||||
break;
|
||||
|
||||
case CMD_SERVO:
|
||||
//Serial.print("CMD_SERVO ");
|
||||
//Serial.print(next_command.p1,DEC);
|
||||
//Serial.print(" PWM: ");
|
||||
//Serial.println(next_command.alt,DEC);
|
||||
APM_RC.OutputCh(next_command.p1, next_command.alt);
|
||||
break;
|
||||
|
||||
case CMD_INDEX:
|
||||
command_must_index = 0;
|
||||
command_may_index = 0;
|
||||
set(PARAM_WP_INDEX,next_command.p1 - 1);
|
||||
break;
|
||||
|
||||
case CMD_RELAY:
|
||||
if (next_command.p1 == 0) {
|
||||
relay_on();
|
||||
} else if (next_command.p1 == 1) {
|
||||
relay_off();
|
||||
}else{
|
||||
relay_toggle();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Verify commands
|
||||
// ---------------
|
||||
void verify_must()
|
||||
{
|
||||
float power;
|
||||
|
||||
switch(command_must_ID) {
|
||||
|
||||
case CMD_TAKEOFF: // Takeoff!
|
||||
//Serial.print("verify_must cmd# ");
|
||||
//Serial.println(command_must_index,DEC);
|
||||
|
||||
if (gps.ground_speed > 300){
|
||||
if(hold_course == -1){
|
||||
// save our current course to take off
|
||||
#if MAGNETOMETER == ENABLED
|
||||
hold_course = dcm.yaw_sensor;
|
||||
#else
|
||||
hold_course = gps.ground_course;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
if(hold_course > -1){
|
||||
// recalc bearing error with hold_course;
|
||||
nav_bearing = hold_course;
|
||||
// recalc bearing error
|
||||
calc_bearing_error();
|
||||
}
|
||||
if (current_loc.alt > (home.alt + takeoff_altitude)) {
|
||||
command_must_index = 0;
|
||||
hold_course = -1;
|
||||
takeoff_complete = true;
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
|
||||
case CMD_LAND:
|
||||
// we don't verify landing - we never go to a new Must command after Land.
|
||||
if ( ((wp_distance > 0) && (wp_distance <= (2*gps.ground_speed/100))) || (current_loc.alt <= next_WP.alt + 300) )
|
||||
{
|
||||
land_complete = 1; //Set land_complete if we are within 2 seconds distance or within 3 meters altitude
|
||||
if(hold_course == -1){
|
||||
// save our current course to land
|
||||
//hold_course = yaw_sensor;
|
||||
// save the course line of the runway to land
|
||||
hold_course = crosstrack_bearing;
|
||||
}
|
||||
}
|
||||
if(hold_course > -1){
|
||||
// recalc bearing error with hold_course;
|
||||
nav_bearing = hold_course;
|
||||
// recalc bearing error
|
||||
calc_bearing_error();
|
||||
}
|
||||
update_crosstrack();
|
||||
|
||||
break;
|
||||
|
||||
case CMD_WAYPOINT: // reach a waypoint
|
||||
hold_course == -1;
|
||||
update_crosstrack();
|
||||
if ((wp_distance > 0) && (wp_distance <= get(PARAM_WP_RADIUS))) {
|
||||
SendDebug("MSG <verify_must: CMD_WAYPOINT> REACHED_WAYPOINT #");
|
||||
SendDebugln(command_must_index,DEC);
|
||||
// clear the command queue;
|
||||
command_must_index = 0;
|
||||
}
|
||||
// add in a more complex case
|
||||
// Doug to do
|
||||
if(loiter_sum > 300){
|
||||
gcs.send_text(SEVERITY_MEDIUM,"<verify_must: CMD_WAYPOINT> Missed WP");
|
||||
command_must_index = 0;
|
||||
}
|
||||
break;
|
||||
|
||||
case CMD_LOITER_N_TURNS: // LOITER N times
|
||||
update_loiter();
|
||||
calc_bearing_error();
|
||||
if(loiter_sum > loiter_total) {
|
||||
loiter_total = 0;
|
||||
gcs.send_text(SEVERITY_LOW,"<verify_must: CMD_LOITER_N_TURNS> LOITER orbits complete ");
|
||||
// clear the command queue;
|
||||
command_must_index = 0;
|
||||
}
|
||||
break;
|
||||
|
||||
case CMD_LOITER_TIME: // loiter N milliseconds
|
||||
update_loiter();
|
||||
calc_bearing_error();
|
||||
if ((millis() - loiter_time) > loiter_time_max) {
|
||||
gcs.send_text(SEVERITY_LOW,"<verify_must: CMD_LOITER_TIME> LOITER time complete ");
|
||||
command_must_index = 0;
|
||||
}
|
||||
break;
|
||||
|
||||
case CMD_RTL:
|
||||
if (wp_distance <= 30) {
|
||||
//Serial.println("REACHED_HOME");
|
||||
command_must_index = 0;
|
||||
}
|
||||
break;
|
||||
|
||||
case CMD_LOITER: // Just plain LOITER
|
||||
update_loiter();
|
||||
calc_bearing_error();
|
||||
break;
|
||||
|
||||
default:
|
||||
gcs.send_text(SEVERITY_HIGH,"<verify_must: default> No current Must commands");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void verify_may()
|
||||
{
|
||||
switch(command_may_ID) {
|
||||
case CMD_DELAY:
|
||||
if ((millis() - delay_start) > delay_timeout){
|
||||
command_may_index = 0;
|
||||
delay_timeout = 0;
|
||||
}
|
||||
|
||||
case CMD_LAND_OPTIONS:
|
||||
if ((wp_distance > 0) && (wp_distance <= landing_distance)) {
|
||||
//Serial.print("XXX REACHED_WAYPOINT #");
|
||||
//Serial.println(command_must_index,DEC);
|
||||
// clear the command queue;
|
||||
command_may_index = 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,609 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
//
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
||||
//
|
||||
// DO NOT EDIT this file to adjust your configuration. Create your own
|
||||
// APM_Config.h and use APM_Config.h.example as a reference.
|
||||
//
|
||||
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
||||
///
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// Default and automatic configuration details.
|
||||
//
|
||||
// Notes for maintainers:
|
||||
//
|
||||
// - Try to keep this file organised in the same order as APM_Config.h.example
|
||||
//
|
||||
|
||||
#include "defines.h"
|
||||
|
||||
///
|
||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||
/// change in your local copy of APM_Config.h.
|
||||
///
|
||||
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
||||
///
|
||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||
/// change in your local copy of APM_Config.h.
|
||||
///
|
||||
|
||||
// Just so that it's completely clear...
|
||||
#define ENABLED 1
|
||||
#define DISABLED 0
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HARDWARE CONFIGURATION AND CONNECTIONS
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AIRSPEED_SENSOR
|
||||
// AIRSPEED_RATIO
|
||||
//
|
||||
#ifndef AIRSPEED_SENSOR
|
||||
# define AIRSPEED_SENSOR DISABLED
|
||||
#endif
|
||||
#ifndef AIRSPEED_RATIO
|
||||
# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HIL_PROTOCOL OPTIONAL
|
||||
// HIL_MODE OPTIONAL
|
||||
// HIL_PORT OPTIONAL
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
# undef GPS_PROTOCOL
|
||||
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
|
||||
|
||||
#ifndef HIL_PROTOCOL
|
||||
# error Must define HIL_PROTOCOL if HIL_MODE is not disabled
|
||||
#endif
|
||||
|
||||
#ifndef HIL_PORT
|
||||
# error Must define HIL_PORT if HIL_PROTOCOL is set
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
// check xplane settings
|
||||
#if HIL_PROTOCOL == HIL_PROTOCOL_XPLANE
|
||||
// MAGNETOMETER not supported by XPLANE
|
||||
# undef MAGNETOMETER
|
||||
# define MAGNETOMETER DISABLED
|
||||
# if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
# error HIL_PROTOCOL_XPLANE requires HIL_MODE_ATTITUDE
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#endif // HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GPS_PROTOCOL
|
||||
//
|
||||
// Note that this test must follow the HIL_PROTOCOL block as the HIL
|
||||
// setup may override the GPS configuration.
|
||||
//
|
||||
#ifndef GPS_PROTOCOL
|
||||
# error XXX
|
||||
# error XXX You must define GPS_PROTOCOL in APM_Config.h, or select a HIL configuration.
|
||||
# error XXX
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GCS_PROTOCOL
|
||||
// GCS_PORT
|
||||
//
|
||||
#ifndef GCS_PROTOCOL
|
||||
# define GCS_PROTOCOL GCS_PROTOCOL_NONE
|
||||
#endif
|
||||
|
||||
#ifndef DEBUGTERMINAL_VERBOSE
|
||||
# define DEBUGTERMINAL_VERBOSE 1 //Set this to 1 to get more detail in DEBUGTERMINAL messages, or 0 to save flash space
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Serial port speeds.
|
||||
//
|
||||
#ifndef SERIAL0_BAUD
|
||||
# define SERIAL0_BAUD 115200
|
||||
#endif
|
||||
#ifndef SERIAL3_BAUD
|
||||
# define SERIAL3_BAUD 57600
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Battery monitoring
|
||||
//
|
||||
#ifndef BATTERY_EVENT
|
||||
# define BATTERY_EVENT DISABLED
|
||||
#endif
|
||||
#ifndef BATTERY_TYPE
|
||||
# define BATTERY_TYPE 0
|
||||
#endif
|
||||
#ifndef LOW_VOLTAGE
|
||||
# define LOW_VOLTAGE 11.4
|
||||
#endif
|
||||
#ifndef VOLT_DIV_RATIO
|
||||
# define VOLT_DIV_RATIO 3.0
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// INPUT_VOLTAGE
|
||||
//
|
||||
#ifndef INPUT_VOLTAGE
|
||||
# define INPUT_VOLTAGE 5.0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MAGNETOMETER
|
||||
// NOTE - There is no support for using the magnetometer in v1.0
|
||||
#ifndef MAGNETOMETER
|
||||
# define MAGNETOMETER DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RADIO CONFIGURATION
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Radio channel limits
|
||||
//
|
||||
// Note that these are not called out in APM_Config.h.example as there
|
||||
// is currently no configured behaviour for these channels.
|
||||
//
|
||||
#ifndef CH5_MIN
|
||||
# define CH5_MIN 1000
|
||||
#endif
|
||||
#ifndef CH5_MAX
|
||||
# define CH5_MAX 2000
|
||||
#endif
|
||||
#ifndef CH6_MIN
|
||||
# define CH6_MIN 1000
|
||||
#endif
|
||||
#ifndef CH6_MAX
|
||||
# define CH6_MAX 2000
|
||||
#endif
|
||||
#ifndef CH7_MIN
|
||||
# define CH7_MIN 1000
|
||||
#endif
|
||||
#ifndef CH7_MAX
|
||||
# define CH7_MAX 2000
|
||||
#endif
|
||||
#ifndef CH8_MIN
|
||||
# define CH8_MIN 1000
|
||||
#endif
|
||||
#ifndef CH8_MAX
|
||||
# define CH8_MAX 2000
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT_MODE
|
||||
// FLIGHT_MODE_CHANNEL
|
||||
//
|
||||
#ifndef FLIGHT_MODE_CHANNEL
|
||||
# define FLIGHT_MODE_CHANNEL 8
|
||||
#endif
|
||||
#if (FLIGHT_MODE_CHANNEL != 5) && (FLIGHT_MODE_CHANNEL != 6) && (FLIGHT_MODE_CHANNEL != 7) && (FLIGHT_MODE_CHANNEL != 8)
|
||||
# error XXX
|
||||
# error XXX You must set FLIGHT_MODE_CHANNEL to 5, 6, 7 or 8
|
||||
# error XXX
|
||||
#endif
|
||||
|
||||
#if !defined(FLIGHT_MODE_1)
|
||||
# define FLIGHT_MODE_1 FLY_BY_WIRE_A
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_2)
|
||||
# define FLIGHT_MODE_2 FLY_BY_WIRE_A
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_3)
|
||||
# define FLIGHT_MODE_3 STABILIZE
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_4)
|
||||
# define FLIGHT_MODE_4 STABILIZE
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_5)
|
||||
# define FLIGHT_MODE_5 MANUAL
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_6)
|
||||
# define FLIGHT_MODE_6 MANUAL
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_FAILSAFE
|
||||
// THROTTLE_FS_VALUE
|
||||
// THROTTLE_FAILSAFE_ACTION
|
||||
//
|
||||
#ifndef THROTTLE_FAILSAFE
|
||||
# define THROTTLE_FAILSAFE DISABLED
|
||||
#endif
|
||||
#ifndef THROTTE_FS_VALUE
|
||||
# define THROTTLE_FS_VALUE 975
|
||||
#endif
|
||||
#ifndef THROTTLE_FAILSAFE_ACTION
|
||||
# define THROTTLE_FAILSAFE_ACTION 2
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AUTO_TRIM
|
||||
//
|
||||
#ifndef AUTO_TRIM
|
||||
# define AUTO_TRIM ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_REVERSE
|
||||
//
|
||||
#ifndef THROTTLE_REVERSE
|
||||
# define THROTTLE_REVERSE DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_STICK_MIXING
|
||||
//
|
||||
#ifndef ENABLE_STICK_MIXING
|
||||
# define ENABLE_STICK_MIXING ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_OUT
|
||||
//
|
||||
#ifndef THROTTE_OUT
|
||||
# define THROTTLE_OUT ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// STARTUP BEHAVIOUR
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GROUND_START_DELAY
|
||||
//
|
||||
#ifndef GROUND_START_DELAY
|
||||
# define GROUND_START_DELAY 0
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_AIR_START
|
||||
//
|
||||
#ifndef ENABLE_AIR_START
|
||||
# define ENABLE_AIR_START DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE REVERSE_SWITCH
|
||||
//
|
||||
#ifndef REVERSE_SWITCH
|
||||
# define REVERSE_SWITCH ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT AND NAVIGATION CONTROL
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Altitude measurement and control.
|
||||
//
|
||||
#ifndef AOA
|
||||
# define AOA 100 // XXX still 100ths of a degree
|
||||
#endif
|
||||
#ifndef ALT_EST_GAIN
|
||||
# define ALT_EST_GAIN 0.01
|
||||
#endif
|
||||
#ifndef ALTITUDE_MIX
|
||||
# define ALTITUDE_MIX 0
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AIRSPEED_CRUISE
|
||||
//
|
||||
#ifndef AIRSPEED_CRUISE
|
||||
# define AIRSPEED_CRUISE 1000 // 10 m/s * 100
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLY_BY_WIRE_B airspeed control
|
||||
//
|
||||
#ifndef AIRSPEED_FBW_MIN
|
||||
# define AIRSPEED_FBW_MIN 6
|
||||
#endif
|
||||
#ifndef AIRSPEED_FBW_MAX
|
||||
# define AIRSPEED_FBW_MAX 30
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_P
|
||||
# define THROTTLE_ALT_P 0.32
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_I
|
||||
# define THROTTLE_ALT_I 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_D
|
||||
# define THROTTLE_ALT_D 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_INT_MAX
|
||||
# define THROTTLE_ALT_INT_MAX 20
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Throttle control
|
||||
//
|
||||
#ifndef THROTTLE_MIN
|
||||
# define THROTTLE_MIN 0
|
||||
#endif
|
||||
#ifndef THROTTLE_CRUISE
|
||||
# define THROTTLE_CRUISE 45
|
||||
#endif
|
||||
#ifndef THROTTLE_MAX
|
||||
# define THROTTLE_MAX 75
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Autopilot control limits
|
||||
//
|
||||
#ifndef HEAD_MAX
|
||||
# define HEAD_MAX 4500 // deg * 100
|
||||
#endif
|
||||
#ifndef PITCH_MAX
|
||||
# define PITCH_MAX 1500 // deg * 100
|
||||
#endif
|
||||
#ifndef PITCH_MIN
|
||||
# define PITCH_MIN -2500 // deg * 100
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Attitude control gains
|
||||
//
|
||||
#ifndef SERVO_ROLL_P
|
||||
# define SERVO_ROLL_P 0.4
|
||||
#endif
|
||||
#ifndef SERVO_ROLL_I
|
||||
# define SERVO_ROLL_I 0.0
|
||||
#endif
|
||||
#ifndef SERVO_ROLL_D
|
||||
# define SERVO_ROLL_D 0.0
|
||||
#endif
|
||||
#ifndef SERVO_ROLL_INT_MAX
|
||||
# define SERVO_ROLL_INT_MAX 5
|
||||
#endif
|
||||
#ifndef ROLL_SLEW_LIMIT
|
||||
# define ROLL_SLEW_LIMIT 0
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_P
|
||||
# define SERVO_PITCH_P 0.6
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_I
|
||||
# define SERVO_PITCH_I 0.0
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_D
|
||||
# define SERVO_PITCH_D 0.0
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_INT_MAX
|
||||
# define SERVO_PITCH_INT_MAX 5
|
||||
#endif
|
||||
#ifndef PITCH_COMP
|
||||
# define PITCH_COMP 0.2
|
||||
#endif
|
||||
#ifndef SERVO_YAW_P
|
||||
# define SERVO_YAW_P 0.0
|
||||
#endif
|
||||
#ifndef SERVO_YAW_I
|
||||
# define SERVO_YAW_I 0.0
|
||||
#endif
|
||||
#ifndef SERVO_YAW_D
|
||||
# define SERVO_YAW_D 0.0
|
||||
#endif
|
||||
#ifndef SERVO_YAW_INT_MAX
|
||||
# define SERVO_YAW_INT_MAX 5
|
||||
#endif
|
||||
#ifndef RUDDER_MIX
|
||||
# define RUDDER_MIX 0.5
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation control gains
|
||||
//
|
||||
#ifndef NAV_ROLL_P
|
||||
# define NAV_ROLL_P 0.7
|
||||
#endif
|
||||
#ifndef NAV_ROLL_I
|
||||
# define NAV_ROLL_I 0.0
|
||||
#endif
|
||||
#ifndef NAV_ROLL_D
|
||||
# define NAV_ROLL_D 0.02
|
||||
#endif
|
||||
#ifndef NAV_ROLL_INT_MAX
|
||||
# define NAV_ROLL_INT_MAX 5
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_P
|
||||
# define NAV_PITCH_ASP_P 0.65
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_I
|
||||
# define NAV_PITCH_ASP_I 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_D
|
||||
# define NAV_PITCH_ASP_D 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_INT_MAX
|
||||
# define NAV_PITCH_ASP_INT_MAX 5
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_P
|
||||
# define NAV_PITCH_ALT_P 0.65
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_I
|
||||
# define NAV_PITCH_ALT_I 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_D
|
||||
# define NAV_PITCH_ALT_D 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_INT_MAX
|
||||
# define NAV_PITCH_ALT_INT_MAX 5
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Energy/Altitude control gains
|
||||
//
|
||||
#ifndef THROTTLE_TE_P
|
||||
# define THROTTLE_TE_P 0.50
|
||||
#endif
|
||||
#ifndef THROTTLE_TE_I
|
||||
# define THROTTLE_TE_I 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_TE_D
|
||||
# define THROTTLE_TE_D 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_TE_INT_MAX
|
||||
# define THROTTLE_TE_INT_MAX 20
|
||||
#endif
|
||||
#ifndef THROTTLE_SLEW_LIMIT
|
||||
# define THROTTLE_SLEW_LIMIT 0
|
||||
#endif
|
||||
#ifndef P_TO_T
|
||||
# define P_TO_T 2.5
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Crosstrack compensation
|
||||
//
|
||||
#ifndef XTRACK_GAIN
|
||||
# define XTRACK_GAIN 10 // deg/m * 100
|
||||
#endif
|
||||
#ifndef XTRACK_ENTRY_ANGLE
|
||||
# define XTRACK_ENTRY_ANGLE 3000 // deg * 100
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// DEBUGGING
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// DEBUG_SUBSYSTEM
|
||||
//
|
||||
#ifndef DEBUG_SUBSYSTEM
|
||||
# define DEBUG_SUBSYSTEM 0
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// DEBUG_LEVEL
|
||||
//
|
||||
#ifndef DEBUG_LEVEL
|
||||
# define DEBUG_LEVEL SEVERITY_LOW
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Dataflash logging control
|
||||
//
|
||||
#ifndef LOG_ATTITUDE_FAST
|
||||
# define LOG_ATTITUDE_FAST DISABLED
|
||||
#endif
|
||||
#ifndef LOG_ATTITUDE_MED
|
||||
# define LOG_ATTITUDE_MED ENABLED
|
||||
#endif
|
||||
#ifndef LOG_GPS
|
||||
# define LOG_GPS ENABLED
|
||||
#endif
|
||||
#ifndef LOG_PM
|
||||
# define LOG_PM ENABLED
|
||||
#endif
|
||||
#ifndef LOG_CTUN
|
||||
# define LOG_CTUN DISABLED
|
||||
#endif
|
||||
#ifndef LOG_NTUN
|
||||
# define LOG_NTUN DISABLED
|
||||
#endif
|
||||
#ifndef LOG_MODE
|
||||
# define LOG_MODE ENABLED
|
||||
#endif
|
||||
#ifndef LOG_RAW
|
||||
# define LOG_RAW DISABLED
|
||||
#endif
|
||||
#ifndef LOG_CMD
|
||||
# define LOG_CMD ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef DEBUG_PORT
|
||||
# define DEBUG_PORT 0
|
||||
#endif
|
||||
|
||||
#if DEBUG_PORT == 0
|
||||
# define SendDebug_P(a) Serial.print_P(PSTR(a))
|
||||
# define SendDebugln_P(a) Serial.println_P(PSTR(a))
|
||||
# define SendDebug Serial.print
|
||||
# define SendDebugln Serial.println
|
||||
#elif DEBUG_PORT == 1
|
||||
# define SendDebug_P(a) Serial1.print_P(PSTR(a))
|
||||
# define SendDebugln_P(a) Serial1.println_P(PSTR(a))
|
||||
# define SendDebug Serial1.print
|
||||
# define SendDebugln Serial1.println
|
||||
#elif DEBUG_PORT == 2
|
||||
# define SendDebug_P(a) Serial2.print_P(PSTR(a))
|
||||
# define SendDebugln_P(a) Serial2.println_P(PSTR(a))
|
||||
# define SendDebug Serial2.print
|
||||
# define SendDebugln Serial2.println
|
||||
#elif DEBUG_PORT == 3
|
||||
# define SendDebug_P(a) Serial3.print_P(PSTR(a))
|
||||
# define SendDebugln_P(a) Serial3.println_P(PSTR(a))
|
||||
# define SendDebug Serial3.print
|
||||
# define SendDebugln Serial3.println
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation defaults
|
||||
//
|
||||
#ifndef WP_RADIUS_DEFAULT
|
||||
# define WP_RADIUS_DEFAULT 20
|
||||
#endif
|
||||
#ifndef LOITER_RADIUS_DEFAULT
|
||||
# define LOITER_RADIUS_DEFAULT 60
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Developer Items
|
||||
//
|
||||
|
||||
#ifndef STANDARD_SPEED
|
||||
# define STANDARD_SPEED 15.0
|
||||
#endif
|
||||
#define STANDARD_SPEED_SQUARED (STANDARD_SPEED * STANDARD_SPEED)
|
||||
#define STANDARD_THROTTLE_SQUARED (THROTTLE_CRUISE * THROTTLE_CRUISE)
|
||||
#define THROTTLE2SPEED_SCALER
|
|
@ -0,0 +1,48 @@
|
|||
void read_control_switch()
|
||||
{
|
||||
byte switchPosition = readSwitch();
|
||||
if (oldSwitchPosition != switchPosition){
|
||||
|
||||
set_mode(flight_mode(switchPosition));
|
||||
|
||||
oldSwitchPosition = switchPosition;
|
||||
|
||||
// reset navigation integrators
|
||||
// -------------------------
|
||||
reset_I();
|
||||
}
|
||||
}
|
||||
|
||||
byte readSwitch(void){
|
||||
uint16_t pulsewidth = APM_RC.InputCh(get(PARAM_FLIGHT_MODE_CH) - 1);
|
||||
if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
|
||||
if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
|
||||
if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
|
||||
if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual
|
||||
if (pulsewidth >= 1750) return 5; // Hardware Manual
|
||||
return 0;
|
||||
}
|
||||
|
||||
void reset_control_switch()
|
||||
{
|
||||
oldSwitchPosition = 0;
|
||||
read_control_switch();
|
||||
SendDebug("MSG: reset_control_switch");
|
||||
SendDebugln(oldSwitchPosition , DEC);
|
||||
}
|
||||
|
||||
void update_servo_switches()
|
||||
{
|
||||
// up is reverse
|
||||
// up is elevon
|
||||
mix_mode = (PINL & 128) ? 1 : 0;
|
||||
if (mix_mode == 0) {
|
||||
reverse_roll = (PINE & 128) ? 1 : -1;
|
||||
reverse_pitch = (PINE & 64) ? 1 : -1;
|
||||
reverse_rudder = (PINL & 64) ? 1 : -1;
|
||||
} else {
|
||||
reverse_elevons = (PINE & 128) ? 1 : -1;
|
||||
reverse_ch1_elevon = (PINE & 64) ? 1 : -1;
|
||||
reverse_ch2_elevon = (PINL & 64) ? 1 : -1;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,68 @@
|
|||
#!/bin/bash
|
||||
#" Autocompletion enabled vim for arduino pde's
|
||||
|
||||
ctags -RV --language-force=C++ --c++-kinds=+p --fields=+iaS --extra=+q \
|
||||
. \
|
||||
../libraries/* \
|
||||
/usr/lib/avr/include
|
||||
|
||||
# sample vimrc file
|
||||
# you'll need to have omnicpp plugin for vim
|
||||
|
||||
#"set compatible
|
||||
|
||||
#" Vim5 and later versions support syntax highlighting. Uncommenting the next
|
||||
#" line enables syntax highlighting by default.
|
||||
#syntax on
|
||||
#filetype on
|
||||
#au BufNewFile,BufRead *.pde set filetype=cpp
|
||||
|
||||
#" If using a dark background within the editing area and syntax highlighting
|
||||
#" turn on this option as well
|
||||
#"set background=dark
|
||||
|
||||
#" Uncomment the following to have Vim jump to the last position when
|
||||
#" reopening a file
|
||||
#if has("autocmd")
|
||||
#au BufReadPost * if line("'\"") > 1 && line("'\"") <= line("$") | exe "normal! g'\"" | endif
|
||||
#endif
|
||||
|
||||
#" Uncomment the following to have Vim load indentation rules and plugins
|
||||
#" according to the detected filetype.
|
||||
#if has("autocmd")
|
||||
#filetype plugin indent on
|
||||
#endif
|
||||
|
||||
#" The following are commented out as they cause vim to behave a lot
|
||||
#" differently from regular Vi. They are highly recommended though.
|
||||
#set showcmd " Show (partial) command in status line.
|
||||
#set showmatch " Show matching brackets.
|
||||
#set ignorecase " Do case insensitive matching
|
||||
#set smartcase " Do smart case matching
|
||||
#set incsearch " Incremental search
|
||||
#set autowrite " Automatically save before commands like :next and :make
|
||||
#set hidden " Hide buffers when they are abandoned
|
||||
#set mouse=a " Enable mouse usage (all modes)
|
||||
#set vb
|
||||
|
||||
#" build tags of your own project with Ctrl-F12
|
||||
#map <C-F12> :!ctags -R --sort=yes --c++-kinds=+p --fields=+iaS --extra=+q .<CR>
|
||||
|
||||
#" OmniCppComplete
|
||||
#let OmniCpp_NamespaceSearch = 1
|
||||
#let OmniCpp_GlobalScopeSearch = 1
|
||||
#let OmniCpp_ShowAccess = 1
|
||||
#let OmniCpp_ShowPrototypeInAbbr = 1 " show function parameters
|
||||
#let OmniCpp_MayCompleteDot = 1 " autocomplete after .
|
||||
#let OmniCpp_MayCompleteArrow = 1 " autocomplete after ->
|
||||
#let OmniCpp_MayCompleteScope = 1 " autocomplete after ::
|
||||
#let OmniCpp_DefaultNamespaces = ["std", "_GLIBCXX_STD"]
|
||||
|
||||
#" arduino syntax
|
||||
#au BufNewFile,BufRead *.pde setf arduino
|
||||
|
||||
#" automatically open and close the popup menu / preview window
|
||||
#"au CursorMovedI,InsertLeave * if pumvisible() == 0|silent! pclose|endif
|
||||
#"set completeopt=menuone,menu,longest,preview
|
||||
#set ts=4
|
||||
#set sw=4
|
|
@ -0,0 +1,70 @@
|
|||
#if DEBUG_SUBSYSTEM == 1
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("GPS Subsystem, RAW OUTPUT");
|
||||
|
||||
while(1){
|
||||
if(Serial1.available() > 0) // Ok, let me see, the buffer is empty?
|
||||
{
|
||||
delay(60); // wait for it all
|
||||
while(Serial1.available() > 0){
|
||||
byte incoming = Serial1.read();
|
||||
//Serial.print(incoming,DEC);
|
||||
Serial.print(incoming, BYTE); // will output Hex values
|
||||
//Serial.print(",");
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 2
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Control Switch");
|
||||
|
||||
Serial.print("Control CH ");
|
||||
Serial.println(flight_mode_channel, DEC);
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
byte switchPosition = readSwitch();
|
||||
if (oldSwitchPosition != switchPosition){
|
||||
Serial.printf_P(PSTR("Position %d\n"), i, switchPosition);
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 3
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("DIP Switch Test");
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
update_servo_switches();
|
||||
if (mix_mode == 0) {
|
||||
Serial.print("Mix:standard ");
|
||||
Serial.print("\t reverse_roll: ");
|
||||
Serial.print(reverse_roll, DEC);
|
||||
Serial.print("\t reverse_pitch: ");
|
||||
Serial.print(reverse_pitch, DEC);
|
||||
Serial.print("\t reverse_rudder: ");
|
||||
Serial.println(reverse_rudder, DEC);
|
||||
} else {
|
||||
Serial.print("Mix:elevons ");
|
||||
Serial.print("\t reverse_elevons: ");
|
||||
Serial.print(reverse_elevons, DEC);
|
||||
Serial.print("\t reverse_ch1_elevon: ");
|
||||
Serial.print(reverse_ch1_elevon, DEC);
|
||||
Serial.print("\t reverse_ch2_elevon: ");
|
||||
Serial.println(reverse_ch2_elevon, DEC);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
@ -0,0 +1,310 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
// Internal defines, don't edit and expect things to work
|
||||
// -------------------------------------------------------
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 30 // for calculating power outside of loiter radius
|
||||
|
||||
// GPS baud rates
|
||||
// --------------
|
||||
#define NO_GPS 38400
|
||||
#define NMEA_GPS 38400
|
||||
#define EM406_GPS 57600
|
||||
#define UBLOX_GPS 38400
|
||||
#define ARDU_IMU 38400
|
||||
#define MTK_GPS 38400
|
||||
#define SIM_GPS 38400
|
||||
|
||||
// GPS type codes - use the names, not the numbers
|
||||
#define GPS_PROTOCOL_NONE -1
|
||||
#define GPS_PROTOCOL_NMEA 0
|
||||
#define GPS_PROTOCOL_SIRF 1
|
||||
#define GPS_PROTOCOL_UBLOX 2
|
||||
#define GPS_PROTOCOL_IMU 3
|
||||
#define GPS_PROTOCOL_MTK 4
|
||||
#define GPS_PROTOCOL_HIL 5
|
||||
|
||||
// Radio channels
|
||||
// Note channels are from 0!
|
||||
//
|
||||
// XXX these should be CH_n defines from RC.h at some point.
|
||||
#define CH_ROLL 0
|
||||
#define CH_PITCH 1
|
||||
#define CH_THROTTLE 2
|
||||
#define CH_RUDDER 3
|
||||
#define CH_1 0
|
||||
#define CH_2 1
|
||||
#define CH_3 2
|
||||
#define CH_4 3
|
||||
#define CH_5 4
|
||||
#define CH_6 5
|
||||
#define CH_7 6
|
||||
#define CH_8 7
|
||||
|
||||
#define WP_SIZE 14
|
||||
|
||||
// HIL enumerations
|
||||
#define HIL_PROTOCOL_XPLANE 1
|
||||
#define HIL_PROTOCOL_MAVLINK 2
|
||||
|
||||
#define HIL_MODE_DISABLED 0
|
||||
#define HIL_MODE_ATTITUDE 1
|
||||
#define HIL_MODE_SENSORS 2
|
||||
|
||||
// GCS enumeration
|
||||
#define GCS_PROTOCOL_STANDARD 0 // standard APM protocol
|
||||
#define GCS_PROTOCOL_LEGACY 1 // legacy ArduPilot protocol
|
||||
#define GCS_PROTOCOL_XPLANE 2 // X-Plane HIL simulation
|
||||
#define GCS_PROTOCOL_DEBUGTERMINAL 3 //Human-readable debug interface for use with a dumb terminal
|
||||
#define GCS_PROTOCOL_MAVLINK 4 // binary protocol for qgroundcontrol
|
||||
#define GCS_PROTOCOL_NONE -1 // No GCS output
|
||||
|
||||
// PID enumeration
|
||||
// ---------------
|
||||
#define CASE_SERVO_ROLL 0
|
||||
#define CASE_SERVO_PITCH 1
|
||||
#define CASE_SERVO_RUDDER 2
|
||||
#define CASE_NAV_ROLL 3
|
||||
#define CASE_NAV_PITCH_ASP 4
|
||||
#define CASE_NAV_PITCH_ALT 5
|
||||
#define CASE_TE_THROTTLE 6
|
||||
#define CASE_ALT_THROTTLE 7
|
||||
|
||||
// Feedforward cases
|
||||
// ----------------
|
||||
#define CASE_PITCH_COMP 0
|
||||
#define CASE_RUDDER_MIX 1
|
||||
#define CASE_P_TO_T 2
|
||||
|
||||
// Auto Pilot modes
|
||||
// ----------------
|
||||
#define MANUAL 0
|
||||
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
|
||||
#define STABILIZE 2
|
||||
|
||||
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle
|
||||
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed
|
||||
// Fly By Wire B = Fly By Wire A if you have AIRSPEED_SENSOR 0
|
||||
#define AUTO 10
|
||||
#define RTL 11
|
||||
#define LOITER 12
|
||||
#define TAKEOFF 13
|
||||
#define LAND 14
|
||||
|
||||
|
||||
// Command IDs - Must
|
||||
#define CMD_BLANK 0x00 // there is no command stored in the mem location requested
|
||||
#define CMD_WAYPOINT 0x10
|
||||
#define CMD_LOITER 0x11
|
||||
#define CMD_LOITER_N_TURNS 0x12
|
||||
#define CMD_LOITER_TIME 0x13
|
||||
#define CMD_RTL 0x14
|
||||
#define CMD_LAND 0x15
|
||||
#define CMD_TAKEOFF 0x16
|
||||
|
||||
// Command IDs - May
|
||||
#define CMD_DELAY 0x20
|
||||
#define CMD_CLIMB 0x21 // NOT IMPLEMENTED
|
||||
#define CMD_LAND_OPTIONS 0x22 // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
|
||||
|
||||
// Command IDs - Now
|
||||
//#define CMD_AP_MODE 0x30
|
||||
#define CMD_RESET_INDEX 0x31
|
||||
#define CMD_GOTO_INDEX 0x32 // NOT IMPLEMENTED
|
||||
#define CMD_GETVAR_INDEX 0x33
|
||||
#define CMD_SENDVAR_INDEX 0x34
|
||||
#define CMD_TELEMETRY 0x35
|
||||
|
||||
#define CMD_THROTTLE_CRUISE 0x40
|
||||
#define CMD_AIRSPEED_CRUISE 0x41
|
||||
#define CMD_RESET_HOME 0x44
|
||||
|
||||
#define CMD_KP_GAIN 0x60
|
||||
#define CMD_KI_GAIN 0x61
|
||||
#define CMD_KD_GAIN 0x62
|
||||
#define CMD_KI_MAX 0x63
|
||||
#define CMD_KFF_GAIN 0x64
|
||||
|
||||
#define CMD_RADIO_TRIM 0x70
|
||||
#define CMD_RADIO_MAX 0x71
|
||||
#define CMD_RADIO_MIN 0x72
|
||||
#define CMD_RADIO_MIN 0x72
|
||||
#define CMD_ELEVON_TRIM 0x73
|
||||
|
||||
#define CMD_INDEX 0x75 // sets the current Must index
|
||||
#define CMD_REPEAT 0x80
|
||||
#define CMD_RELAY 0x81
|
||||
#define CMD_SERVO 0x82 // move servo N to PWM value
|
||||
|
||||
//repeating events
|
||||
#define NO_REPEAT 0
|
||||
#define CH_4_TOGGLE 1
|
||||
#define CH_5_TOGGLE 2
|
||||
#define CH_6_TOGGLE 3
|
||||
#define CH_7_TOGGLE 4
|
||||
#define RELAY_TOGGLE 5
|
||||
#define STOP_REPEAT 10
|
||||
|
||||
// GCS Message ID's
|
||||
#define MSG_ACKNOWLEDGE 0x00
|
||||
#define MSG_HEARTBEAT 0x01
|
||||
#define MSG_ATTITUDE 0x02
|
||||
#define MSG_LOCATION 0x03
|
||||
#define MSG_PRESSURE 0x04
|
||||
#define MSG_STATUS_TEXT 0x05
|
||||
#define MSG_PERF_REPORT 0x06
|
||||
#define MSG_MODE_CHANGE 0x07 //This is different than HEARTBEAT because it occurs only when the mode is actually changed
|
||||
#define MSG_VERSION_REQUEST 0x08
|
||||
#define MSG_VERSION 0x09
|
||||
#define MSG_EXTENDED_STATUS 0x0a
|
||||
#define MSG_CPU_LOAD 0x0b
|
||||
|
||||
#define MSG_COMMAND_REQUEST 0x20
|
||||
#define MSG_COMMAND_UPLOAD 0x21
|
||||
#define MSG_COMMAND_LIST 0x22
|
||||
#define MSG_COMMAND_MODE_CHANGE 0x23
|
||||
#define MSG_CURRENT_WAYPOINT 0x24
|
||||
|
||||
#define MSG_VALUE_REQUEST 0x30
|
||||
#define MSG_VALUE_SET 0x31
|
||||
#define MSG_VALUE 0x32
|
||||
|
||||
#define MSG_PID_REQUEST 0x40
|
||||
#define MSG_PID_SET 0x41
|
||||
#define MSG_PID 0x42
|
||||
|
||||
#define MSG_TRIM_STARTUP 0x50
|
||||
#define MSG_TRIM_MIN 0x51
|
||||
#define MSG_TRIM_MAX 0x52
|
||||
#define MSG_RADIO_OUT 0x53
|
||||
|
||||
#define MSG_RAW_IMU 0x60
|
||||
#define MSG_GPS_STATUS 0x61
|
||||
#define MSG_GPS_RAW 0x62
|
||||
#define MSG_AIRSPEED 0x63
|
||||
|
||||
#define MSG_SERVO_OUT 0x70
|
||||
|
||||
#define MSG_PIN_REQUEST 0x80
|
||||
#define MSG_PIN_SET 0x81
|
||||
|
||||
#define MSG_DATAFLASH_REQUEST 0x90
|
||||
#define MSG_DATAFLASH_SET 0x91
|
||||
|
||||
#define MSG_EEPROM_REQUEST 0xa0
|
||||
#define MSG_EEPROM_SET 0xa1
|
||||
|
||||
#define MSG_POSITION_CORRECT 0xb0
|
||||
#define MSG_ATTITUDE_CORRECT 0xb1
|
||||
#define MSG_POSITION_SET 0xb2
|
||||
#define MSG_ATTITUDE_SET 0xb3
|
||||
#define MSG_LOCAL_LOCATION 0xb4
|
||||
|
||||
#define SEVERITY_LOW 1
|
||||
#define SEVERITY_MEDIUM 2
|
||||
#define SEVERITY_HIGH 3
|
||||
#define SEVERITY_CRITICAL 4
|
||||
|
||||
// Logging parameters
|
||||
#define LOG_ATTITUDE_MSG 0x01
|
||||
#define LOG_GPS_MSG 0x02
|
||||
#define LOG_MODE_MSG 0X03
|
||||
#define LOG_CONTROL_TUNING_MSG 0X04
|
||||
#define LOG_NAV_TUNING_MSG 0X05
|
||||
#define LOG_PERFORMANCE_MSG 0X06
|
||||
#define LOG_RAW_MSG 0x07
|
||||
#define LOG_CMD_MSG 0x08
|
||||
#define LOG_STARTUP_MSG 0x09
|
||||
#define TYPE_AIRSTART_MSG 0x00
|
||||
#define TYPE_GROUNDSTART_MSG 0x01
|
||||
|
||||
#define MASK_LOG_ATTITUDE_FAST 0
|
||||
#define MASK_LOG_ATTITUDE_MED 2
|
||||
#define MASK_LOG_GPS 4
|
||||
#define MASK_LOG_PM 8
|
||||
#define MASK_LOG_CTUN 16
|
||||
#define MASK_LOG_NTUN 32
|
||||
#define MASK_LOG_MODE 64
|
||||
#define MASK_LOG_RAW 128
|
||||
#define MASK_LOG_CMD 256
|
||||
|
||||
// Yaw modes
|
||||
#define YAW_MODE_COORDINATE_TURNS 0
|
||||
#define YAW_MODE_HOLD_HEADING 1
|
||||
#define YAW_MODE_SLIP 2
|
||||
|
||||
// Waypoint Modes
|
||||
// ----------------
|
||||
#define ABS_WP 0
|
||||
#define REL_WP 1
|
||||
|
||||
// Command Queues
|
||||
// ---------------
|
||||
#define COMMAND_MUST 0
|
||||
#define COMMAND_MAY 1
|
||||
#define COMMAND_NOW 2
|
||||
|
||||
// Events
|
||||
// ------
|
||||
#define EVENT_WILL_REACH_WAYPOINT 1
|
||||
#define EVENT_SET_NEW_WAYPOINT_INDEX 2
|
||||
#define EVENT_LOADED_WAYPOINT 3
|
||||
#define EVENT_LOOP 4
|
||||
|
||||
//GPS_fix
|
||||
#define VALID_GPS 0x00
|
||||
#define BAD_GPS 0x01
|
||||
#define FAILED_GPS 0x03
|
||||
|
||||
// Climb rate calculations
|
||||
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
|
||||
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
|
||||
|
||||
#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor
|
||||
#define BATTERY_PIN1 0 // These are the pins for the voltage dividers
|
||||
#define BATTERY_PIN2 1
|
||||
#define BATTERY_PIN3 2
|
||||
#define BATTERY_PIN4 3
|
||||
#define RELAY_PIN 47
|
||||
|
||||
// Hardware Parameters
|
||||
#define SLIDE_SWITCH_PIN 40
|
||||
#define PUSHBUTTON_PIN 41
|
||||
|
||||
#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C
|
||||
#define B_LED_PIN 36
|
||||
#define C_LED_PIN 35
|
||||
|
||||
#define HOLD_ALT_ABOVE_HOME 8 // bitmask value
|
||||
|
||||
#define SPEEDFILT 400 // centimeters/second; the speed below which a groundstart will be triggered
|
||||
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
|
||||
// log
|
||||
#define EE_END_OF_PARAMS getAddress(PARAM_LAST_UINT32)
|
||||
#define EE_LAST_LOG_PAGE EE_END_OF_PARAMS+1
|
||||
#define EE_LAST_LOG_NUM EE_END_OF_PARAMS+3
|
||||
#define EE_LOG_1_START EE_END_OF_PARAMS+5
|
||||
#define WP_START_BYTE EE_END_OF_PARAMS+45 // where in memory home WP is stored + all other WP
|
||||
// add 19 to account for log files
|
||||
|
||||
// bits in log_bitmask
|
||||
#define LOGBIT_ATTITUDE_FAST (1<<0)
|
||||
#define LOGBIT_ATTITUDE_MED (1<<1)
|
||||
#define LOGBIT_GPS (1<<2)
|
||||
#define LOGBIT_PM (1<<3)
|
||||
#define LOGBIT_CTUN (1<<4)
|
||||
#define LOGBIT_NTUN (1<<5)
|
||||
#define LOGBIT_MODE (1<<6)
|
||||
#define LOGBIT_RAW (1<<7)
|
||||
#define LOGBIT_CMD (1<<8)
|
||||
|
|
@ -0,0 +1,225 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/*
|
||||
This event will be called when the failsafe changes
|
||||
boolean failsafe reflects the current state
|
||||
*/
|
||||
void failsafe_event()
|
||||
{
|
||||
if (failsafe == true){
|
||||
|
||||
// This is how to handle a failsafe.
|
||||
switch(control_mode)
|
||||
{
|
||||
case MANUAL: // First position
|
||||
set_mode(STABILIZE);
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
case FLY_BY_WIRE_A: // middle position
|
||||
case FLY_BY_WIRE_B: // middle position
|
||||
set_mode(RTL);
|
||||
set(PARAM_TRIM_THROTTLE,THROTTLE_CRUISE);
|
||||
|
||||
case CIRCLE: // middle position
|
||||
break;
|
||||
|
||||
case AUTO: // middle position
|
||||
case LOITER: // middle position
|
||||
if (get(PARAM_THR_FS_ACTION)== 1){
|
||||
set_mode(RTL);
|
||||
set(PARAM_TRIM_THROTTLE,THROTTLE_CRUISE);
|
||||
}
|
||||
// 2 = Stay in AUTO and ignore failsafe
|
||||
break;
|
||||
|
||||
case RTL: // middle position
|
||||
break;
|
||||
|
||||
default:
|
||||
set_mode(RTL);
|
||||
set(PARAM_TRIM_THROTTLE,THROTTLE_CRUISE);
|
||||
break;
|
||||
}
|
||||
}else{
|
||||
reset_I();
|
||||
}
|
||||
}
|
||||
|
||||
void low_battery_event(void)
|
||||
{
|
||||
gcs.send_text(SEVERITY_HIGH,"Low Battery!");
|
||||
set_mode(RTL);
|
||||
set(PARAM_TRIM_THROTTLE,THROTTLE_CRUISE);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
4 simultaneous events
|
||||
int event_original - original time in seconds
|
||||
int event_countdown - count down to zero
|
||||
byte event_countdown - ID for what to do
|
||||
byte event_countdown - how many times to loop, 0 = indefinite
|
||||
byte event_value - specific information for an event like PWM value
|
||||
byte counterEvent - undo the event if nescessary
|
||||
|
||||
count down each one
|
||||
|
||||
|
||||
new event
|
||||
undo_event
|
||||
*/
|
||||
|
||||
void new_event(struct Location *cmd)
|
||||
{
|
||||
SendDebug("New Event Loaded ");
|
||||
SendDebugln(cmd->p1,DEC);
|
||||
|
||||
|
||||
if(cmd->p1 == STOP_REPEAT){
|
||||
SendDebugln("STOP repeat ");
|
||||
event_id = NO_REPEAT;
|
||||
event_timer = -1;
|
||||
undo_event = 0;
|
||||
event_value = 0;
|
||||
event_delay = 0;
|
||||
event_repeat = 0; // convert seconds to millis
|
||||
event_undo_value = 0;
|
||||
repeat_forever = 0;
|
||||
}else{
|
||||
// reset the event timer
|
||||
event_timer = millis();
|
||||
event_id = cmd->p1;
|
||||
event_value = cmd->alt;
|
||||
event_delay = cmd->lat;
|
||||
event_repeat = cmd->lng; // convert seconds to millis
|
||||
event_undo_value = 0;
|
||||
repeat_forever = (event_repeat == 0) ? 1:0;
|
||||
}
|
||||
|
||||
/*
|
||||
Serial.print("event_id: ");
|
||||
Serial.println(event_id,DEC);
|
||||
Serial.print("event_value: ");
|
||||
Serial.println(event_value,DEC);
|
||||
Serial.print("event_delay: ");
|
||||
Serial.println(event_delay,DEC);
|
||||
Serial.print("event_repeat: ");
|
||||
Serial.println(event_repeat,DEC);
|
||||
Serial.print("event_undo_value: ");
|
||||
Serial.println(event_undo_value,DEC);
|
||||
Serial.print("repeat_forever: ");
|
||||
Serial.println(repeat_forever,DEC);
|
||||
Serial.print("Event_timer: ");
|
||||
Serial.println(event_timer,DEC);
|
||||
*/
|
||||
perform_event();
|
||||
}
|
||||
|
||||
void perform_event()
|
||||
{
|
||||
if (event_repeat > 0){
|
||||
event_repeat --;
|
||||
}
|
||||
switch(event_id) {
|
||||
case CH_4_TOGGLE:
|
||||
event_undo_value = readOutputCh(4);
|
||||
|
||||
APM_RC.OutputCh(4, event_value); // send to Servos
|
||||
undo_event = 2;
|
||||
break;
|
||||
case CH_5_TOGGLE:
|
||||
event_undo_value = readOutputCh(5);
|
||||
APM_RC.OutputCh(5, event_value); // send to Servos
|
||||
undo_event = 2;
|
||||
break;
|
||||
case CH_6_TOGGLE:
|
||||
event_undo_value = readOutputCh(6);
|
||||
APM_RC.OutputCh(6, event_value); // send to Servos
|
||||
undo_event = 2;
|
||||
break;
|
||||
case CH_7_TOGGLE:
|
||||
event_undo_value = readOutputCh(7);
|
||||
APM_RC.OutputCh(7, event_value); // send to Servos
|
||||
undo_event = 2;
|
||||
event_undo_value = 1;
|
||||
break;
|
||||
case RELAY_TOGGLE:
|
||||
|
||||
event_undo_value = PORTL & B00000100 ? 1:0;
|
||||
relay_toggle();
|
||||
SendDebug("toggle relay ");
|
||||
SendDebugln(PORTL,BIN);
|
||||
undo_event = 2;
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void relay_on()
|
||||
{
|
||||
PORTL |= B00000100;
|
||||
}
|
||||
|
||||
void relay_off()
|
||||
{
|
||||
PORTL &= ~B00000100;
|
||||
}
|
||||
|
||||
void relay_toggle()
|
||||
{
|
||||
PORTL ^= B00000100;
|
||||
}
|
||||
|
||||
void update_events()
|
||||
{
|
||||
// repeating events
|
||||
if(undo_event == 1){
|
||||
perform_event_undo();
|
||||
undo_event = 0;
|
||||
}else if(undo_event > 1){
|
||||
undo_event --;
|
||||
}
|
||||
|
||||
if(event_timer == -1)
|
||||
return;
|
||||
|
||||
if((millis() - event_timer) > event_delay){
|
||||
perform_event();
|
||||
|
||||
if(event_repeat > 0 || repeat_forever == 1){
|
||||
event_repeat--;
|
||||
event_timer = millis();
|
||||
}else{
|
||||
event_timer = -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void perform_event_undo()
|
||||
{
|
||||
switch(event_id) {
|
||||
case CH_4_TOGGLE:
|
||||
APM_RC.OutputCh(4, event_undo_value); // send to Servos
|
||||
break;
|
||||
|
||||
case CH_5_TOGGLE:
|
||||
APM_RC.OutputCh(5, event_undo_value); // send to Servos
|
||||
break;
|
||||
|
||||
case CH_6_TOGGLE:
|
||||
APM_RC.OutputCh(6, event_undo_value); // send to Servos
|
||||
break;
|
||||
|
||||
case CH_7_TOGGLE:
|
||||
APM_RC.OutputCh(7, event_undo_value); // send to Servos
|
||||
break;
|
||||
|
||||
case RELAY_TOGGLE:
|
||||
|
||||
relay_toggle();
|
||||
SendDebug("untoggle relay ");
|
||||
SendDebugln(PORTL,BIN);
|
||||
break;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,58 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#ifndef __GLOBAL_DATA_H
|
||||
#define __GLOBAL_DATA_H
|
||||
|
||||
#include "param_table.h"
|
||||
|
||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||
#define MAX_WAYPOINTS 20
|
||||
|
||||
#define FIRMWARE_VERSION 12 // <-- change on param data struct modifications
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
///
|
||||
// global data structure
|
||||
// This structure holds all the vehicle parameters.
|
||||
// TODO: bring in varibles floating around in ArduPilotMega.pde
|
||||
//
|
||||
struct global_struct
|
||||
{
|
||||
// parameters
|
||||
uint16_t parameter_i; // parameter index
|
||||
uint16_t param_count; // number of params
|
||||
|
||||
// waypoints
|
||||
uint16_t waypoint_request_i; // request index
|
||||
uint16_t waypoint_dest_sysid; // where to send requests
|
||||
uint16_t waypoint_dest_compid; // "
|
||||
bool waypoint_sending; // currently in send process
|
||||
bool waypoint_receiving; // currently receiving
|
||||
uint16_t waypoint_count;
|
||||
uint32_t waypoint_timelast_send; // milliseconds
|
||||
uint32_t waypoint_timelast_receive; // milliseconds
|
||||
uint16_t waypoint_send_timeout; // milliseconds
|
||||
uint16_t waypoint_receive_timeout; // milliseconds
|
||||
float junk; //used to return a junk value for interface
|
||||
|
||||
// data stream rates
|
||||
uint16_t streamRateRawSensors;
|
||||
uint16_t streamRateExtendedStatus;
|
||||
uint16_t streamRateRCChannels;
|
||||
uint16_t streamRateRawController;
|
||||
uint16_t streamRateRawSensorFusion;
|
||||
uint16_t streamRatePosition;
|
||||
uint16_t streamRateExtra1;
|
||||
uint16_t streamRateExtra2;
|
||||
uint16_t streamRateExtra3;
|
||||
|
||||
// struct constructor
|
||||
global_struct();
|
||||
} global_data;
|
||||
|
||||
extern "C" const char *param_nametab[];
|
||||
|
||||
#endif // __cplusplus
|
||||
|
||||
#endif // __GLOBAL_DATA_H
|
|
@ -0,0 +1,188 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// parameter get/set functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
// calculate memory starting location for eeprom
|
||||
static uint16_t floatMemStart = 0;
|
||||
static uint16_t uint8MemStart = floatMemStart + PARAM_FLOAT_COUNT * sizeof(float);
|
||||
static uint16_t uint16MemStart = uint8MemStart + PARAM_UINT8_COUNT * sizeof(uint8_t);
|
||||
static uint16_t int16MemStart = uint16MemStart + PARAM_UINT16_COUNT * sizeof(uint16_t);
|
||||
static uint16_t uint32MemStart = int16MemStart + PARAM_INT16_COUNT * sizeof(int16_t);
|
||||
|
||||
// read parameters
|
||||
static uint8_t get(uint8_param_t id) __attribute__((noinline));
|
||||
static uint8_t get(uint8_param_t id)
|
||||
{
|
||||
return eeprom_read_byte((uint8_t *)((id-PARAM_FIRST_UINT8)*sizeof(uint8_t)+uint8MemStart));
|
||||
}
|
||||
|
||||
static uint16_t get(uint16_param_t id) __attribute__((noinline));
|
||||
static uint16_t get(uint16_param_t id)
|
||||
{
|
||||
return eeprom_read_word((uint16_t *)((id-PARAM_FIRST_UINT16)*sizeof(uint16_t)+uint16MemStart));
|
||||
}
|
||||
|
||||
static int16_t get(int16_param_t id) __attribute__((noinline));
|
||||
static int16_t get(int16_param_t id)
|
||||
{
|
||||
return (int16_t)eeprom_read_word((uint16_t *)((id-PARAM_FIRST_INT16)*sizeof(int16_t)+int16MemStart));
|
||||
}
|
||||
|
||||
static float get(float_param_t id) __attribute__((noinline));
|
||||
static float get(float_param_t id)
|
||||
{
|
||||
float value;
|
||||
eeprom_read_block((void*)&value,(const void*)((id-PARAM_FIRST_FLOAT)*sizeof(float)+floatMemStart),sizeof(value));
|
||||
return value;
|
||||
}
|
||||
|
||||
static float get(uint32_param_t id) __attribute__((noinline));
|
||||
static float get(uint32_param_t id)
|
||||
{
|
||||
uint32_t value;
|
||||
eeprom_read_block((void*)&value,(const void*)((id-PARAM_FIRST_UINT32)*sizeof(uint32_t)+uint32MemStart),sizeof(value));
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
|
||||
// write parameters
|
||||
static void set(uint8_param_t id, uint8_t val) __attribute__((noinline));
|
||||
static void set(uint8_param_t id, uint8_t val)
|
||||
{
|
||||
eeprom_write_byte((uint8_t *)((id-PARAM_FIRST_UINT8)*sizeof(uint8_t)+uint8MemStart),val);
|
||||
}
|
||||
|
||||
static void set(uint16_param_t id, uint16_t val) __attribute__((noinline));
|
||||
static void set(uint16_param_t id, uint16_t val)
|
||||
{
|
||||
eeprom_write_word((uint16_t *)((id-PARAM_FIRST_UINT16)*sizeof(uint16_t)+uint16MemStart),val);
|
||||
}
|
||||
|
||||
static void set(int16_param_t id, int16_t val) __attribute__((noinline));
|
||||
static void set(int16_param_t id, int16_t val)
|
||||
{
|
||||
eeprom_write_word((uint16_t *)((id-PARAM_FIRST_INT16)*sizeof(int16_t)+int16MemStart),(uint16_t)val);
|
||||
}
|
||||
|
||||
static void set(float_param_t id, float val) __attribute__((noinline));
|
||||
static void set(float_param_t id, float val)
|
||||
{
|
||||
eeprom_write_block((const void *)&val,(void *)((id-PARAM_FIRST_FLOAT)*sizeof(float)+floatMemStart),sizeof(val));
|
||||
}
|
||||
|
||||
static void set(uint32_param_t id, uint32_t val) __attribute__((noinline));
|
||||
static void set(uint32_param_t id, uint32_t val)
|
||||
{
|
||||
eeprom_write_block((const void *)&val,(void *)((id-PARAM_FIRST_UINT32)*sizeof(uint32_t)+uint32MemStart),sizeof(val));
|
||||
}
|
||||
|
||||
static void setParamAsFloat(uint16_t id, float value)
|
||||
{
|
||||
if (id < PARAM_FIRST_UINT8) set((float_param_t)id,value);
|
||||
else if (id < PARAM_FIRST_UINT16) set((uint8_param_t)id,(uint8_t)value);
|
||||
else if (id < PARAM_FIRST_INT16) set((uint16_param_t)id,(uint16_t)value);
|
||||
else if (id < PARAM_FIRST_UINT32) set((int16_param_t)id,(int16_t)value);
|
||||
else if (id < PARAM_COUNT) set((uint32_param_t)id,(uint32_t)value);
|
||||
// XXX: uint32 won't have full bitwise precision
|
||||
}
|
||||
|
||||
static float getParamAsFloat(uint16_t id)
|
||||
{
|
||||
// name
|
||||
if (id < PARAM_FIRST_UINT8) return (float)get((float_param_t)id);
|
||||
else if (id < PARAM_FIRST_UINT16) return (float)get((uint8_param_t)id);
|
||||
else if (id < PARAM_FIRST_INT16) return (float)get((uint16_param_t)id);
|
||||
else if (id < PARAM_FIRST_UINT32) return (float)get((int16_param_t)id);
|
||||
else if (id < PARAM_COUNT) return (float)get((uint32_param_t)id);
|
||||
// XXX: uint32 won't have full bitwise precision
|
||||
}
|
||||
|
||||
static const prog_char *getParamName(uint16_t id)
|
||||
{
|
||||
return (const prog_char *)pgm_read_word(¶m_nametab[id]);
|
||||
}
|
||||
|
||||
global_struct::global_struct() :
|
||||
// parameters
|
||||
// note, all values not explicitly initialised here are zeroed
|
||||
param_count(PARAM_COUNT),
|
||||
waypoint_send_timeout(1000), // 1 second
|
||||
waypoint_receive_timeout(1000), // 1 second
|
||||
|
||||
// stream rates
|
||||
streamRateRawSensors(1),
|
||||
streamRateExtendedStatus(1),
|
||||
streamRateRCChannels(1),
|
||||
streamRateRawController(1),
|
||||
streamRateRawSensorFusion(1),
|
||||
streamRatePosition(1),
|
||||
streamRateExtra1(1),
|
||||
streamRateExtra2(1),
|
||||
streamRateExtra3(1)
|
||||
{
|
||||
}
|
||||
|
||||
// Print
|
||||
static void printParam(BetterStream & serial, uint16_t id)
|
||||
{
|
||||
serial.printf_P(PSTR("id %d %S, %f addr %d\n"), id, getParamName(id), getParamAsFloat(id), getAddress(id));
|
||||
}
|
||||
|
||||
static void printAllParams(BetterStream & serial)
|
||||
{
|
||||
for (int i=0;i<global_data.param_count;i++)
|
||||
printParam(serial,i);
|
||||
}
|
||||
|
||||
static uint16_t getAddress(int id)
|
||||
{
|
||||
if (id < PARAM_FIRST_UINT8) return (id - PARAM_FIRST_FLOAT) * sizeof(float) + floatMemStart;
|
||||
if (id < PARAM_FIRST_UINT16) return (id - PARAM_FIRST_UINT8) * sizeof(uint8_t) + uint8MemStart;
|
||||
if (id < PARAM_FIRST_INT16) return (id - PARAM_FIRST_UINT16) * sizeof(uint16_t) + uint16MemStart;
|
||||
if (id < PARAM_FIRST_UINT32) return (id - PARAM_FIRST_INT16) * sizeof(int16_t) + int16MemStart;
|
||||
/*if (id < PARAM_COUNT)*/ return (id - PARAM_FIRST_UINT32) * sizeof(uint32_t) + uint32MemStart;
|
||||
}
|
||||
|
||||
// Array interfaces
|
||||
static uint8_t flight_mode(int i)
|
||||
{
|
||||
return get(uint8_param_t(PARAM_FLIGHT_MODE_1+i));
|
||||
}
|
||||
|
||||
static void set_flight_mode(int i, uint8_t value)
|
||||
{
|
||||
set(uint8_param_t(PARAM_FLIGHT_MODE_1+i),value);
|
||||
}
|
||||
|
||||
static uint16_t radio_min(int i)
|
||||
{
|
||||
return get(uint16_param_t(PARAM_RADIOMIN_CH1+i));
|
||||
}
|
||||
|
||||
static void set_radio_min(int i, uint16_t value)
|
||||
{
|
||||
set(uint16_param_t(PARAM_RADIOMIN_CH1+i),value);
|
||||
}
|
||||
|
||||
static uint16_t radio_max(int i)
|
||||
{
|
||||
return get(uint16_param_t(PARAM_RADIOMAX_CH1+i));
|
||||
}
|
||||
|
||||
static void set_radio_max(int i, uint16_t value)
|
||||
{
|
||||
set(uint16_param_t(PARAM_RADIOMAX_CH1+i),value);
|
||||
}
|
||||
|
||||
static uint16_t radio_trim(int i)
|
||||
{
|
||||
return get(uint16_param_t(PARAM_RADIOTRIM_CH1+i));
|
||||
}
|
||||
|
||||
static void set_radio_trim(int i, uint16_t value)
|
||||
{
|
||||
set(uint16_param_t(PARAM_RADIOTRIM_CH1+i),value);
|
||||
}
|
|
@ -0,0 +1,241 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
//****************************************************************
|
||||
// Function that will calculate the desired direction to fly and altitude error
|
||||
//****************************************************************
|
||||
void navigate()
|
||||
{
|
||||
|
||||
// do not navigate with corrupt data
|
||||
// ---------------------------------
|
||||
if (gps.fix == 0)
|
||||
{
|
||||
gps.new_data = false;
|
||||
return;
|
||||
}
|
||||
if(next_WP.lat == 0){
|
||||
return;
|
||||
}
|
||||
// We only perform most nav computations if we have new gps data to work with
|
||||
// --------------------------------------------------------------------------
|
||||
if(gps.new_data){
|
||||
gps.new_data = false;
|
||||
|
||||
// target_bearing is where we should be heading
|
||||
// --------------------------------------------
|
||||
target_bearing = get_bearing(¤t_loc, &next_WP);
|
||||
|
||||
// nav_bearing will includes xtrac correction
|
||||
// ------------------------------------------
|
||||
nav_bearing = target_bearing;
|
||||
|
||||
// waypoint distance from plane
|
||||
// ----------------------------
|
||||
wp_distance = getDistance(¤t_loc, &next_WP);
|
||||
|
||||
if (wp_distance < 0){
|
||||
gcs.send_text(SEVERITY_HIGH,"<navigate> WP error - distance < 0");
|
||||
//Serial.println(wp_distance,DEC);
|
||||
//print_current_waypoints();
|
||||
return;
|
||||
}
|
||||
|
||||
// check if we have missed the WP
|
||||
loiter_delta = (target_bearing - old_target_bearing)/100;
|
||||
|
||||
// reset the old value
|
||||
old_target_bearing = target_bearing;
|
||||
|
||||
// wrap values
|
||||
if (loiter_delta > 180) loiter_delta -= 360;
|
||||
if (loiter_delta < -180) loiter_delta += 360;
|
||||
loiter_sum += abs(loiter_delta);
|
||||
|
||||
calc_bearing_error();
|
||||
|
||||
// control mode specific updates to nav_bearing
|
||||
update_navigation();
|
||||
}
|
||||
}
|
||||
|
||||
void update_navigation()
|
||||
{
|
||||
// wp_distance is in ACTUAL meters, not the *100 meters we get from the GPS
|
||||
// ------------------------------------------------------------------------
|
||||
|
||||
// distance and bearing calcs only
|
||||
if(control_mode == AUTO){
|
||||
verify_must();
|
||||
verify_may();
|
||||
}else{
|
||||
|
||||
switch(control_mode){
|
||||
case LOITER:
|
||||
update_loiter();
|
||||
calc_bearing_error();
|
||||
break;
|
||||
|
||||
case RTL:
|
||||
if(wp_distance <= (get(PARAM_LOITER_RADIUS)) + LOITER_RANGE) {
|
||||
set_mode(LOITER);
|
||||
}else{
|
||||
update_crosstrack();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Disabled for now
|
||||
void calc_distance_error()
|
||||
{
|
||||
//distance_estimate += (float)gps.ground_speed * .0002 * cos(radians(bearing_error * .01));
|
||||
//distance_estimate -= DST_EST_GAIN * (float)(distance_estimate - GPS_wp_distance);
|
||||
//wp_distance = max(distance_estimate,10);
|
||||
}
|
||||
*/
|
||||
|
||||
void calc_airspeed_errors()
|
||||
{
|
||||
if(control_mode>=AUTO && airspeed_nudge > 0) {
|
||||
airspeed_error = get(PARAM_TRIM_AIRSPEED) + airspeed_nudge - airspeed;
|
||||
airspeed_energy_error = (long)(((long)(get(PARAM_TRIM_AIRSPEED) + airspeed_nudge) * (long)(get(PARAM_TRIM_AIRSPEED) + airspeed_nudge)) - ((long)airspeed * (long)airspeed))/20000; //Changed 0.00005f * to / 20000 to avoid floating point calculation
|
||||
} else {
|
||||
airspeed_error = get(PARAM_TRIM_AIRSPEED) - airspeed;
|
||||
airspeed_energy_error = (long)(((long)get(PARAM_TRIM_AIRSPEED) * (long)get(PARAM_TRIM_AIRSPEED)) - ((long)airspeed * (long)airspeed))/20000; //Changed 0.00005f * to / 20000 to avoid floating point calculation
|
||||
}
|
||||
}
|
||||
|
||||
void calc_bearing_error()
|
||||
{
|
||||
if(takeoff_complete == true || MAGNETOMETER == ENABLED) {
|
||||
bearing_error = nav_bearing - dcm.yaw_sensor;
|
||||
} else {
|
||||
bearing_error = nav_bearing - gps.ground_course;
|
||||
}
|
||||
bearing_error = wrap_180(bearing_error);
|
||||
}
|
||||
|
||||
void calc_altitude_error()
|
||||
{
|
||||
// limit climb rates
|
||||
target_altitude = next_WP.alt - (long)(((float)((wp_distance -30) * offset_altitude) / (float)(wp_totalDistance - 30)));
|
||||
if(prev_WP.alt > next_WP.alt){
|
||||
target_altitude = constrain(target_altitude, next_WP.alt, prev_WP.alt);
|
||||
}else{
|
||||
target_altitude = constrain(target_altitude, prev_WP.alt, next_WP.alt);
|
||||
}
|
||||
|
||||
/*
|
||||
// Disabled for now
|
||||
#if AIRSPEED_SENSOR == 1
|
||||
// special thanks to Ryan Beall for this one
|
||||
float pitch_angle = pitch_sensor - AOA; // pitch_angle = pitch sensor - angle of attack of your plane at level *100 (50 = .5°)
|
||||
pitch_angle = constrain(pitch_angle, -2000, 2000);
|
||||
float scale = sin(radians(pitch_angle * .01));
|
||||
altitude_estimate += (float)airspeed * .0002 * scale;
|
||||
altitude_estimate -= ALT_EST_GAIN * (float)(altitude_estimate - current_loc.alt);
|
||||
|
||||
// compute altitude error for throttle control
|
||||
altitude_error = target_altitude - altitude_estimate;
|
||||
#else
|
||||
altitude_error = target_altitude - current_loc.alt;
|
||||
#endif
|
||||
*/
|
||||
|
||||
altitude_error = target_altitude - current_loc.alt;
|
||||
}
|
||||
|
||||
|
||||
long wrap_360(long error)
|
||||
{
|
||||
if (error > 36000) error -= 36000;
|
||||
if (error < 0) error += 36000;
|
||||
return error;
|
||||
}
|
||||
|
||||
long wrap_180(long error)
|
||||
{
|
||||
if (error > 18000) error -= 36000;
|
||||
if (error < -18000) error += 36000;
|
||||
return error;
|
||||
}
|
||||
|
||||
|
||||
void update_loiter()
|
||||
{
|
||||
float power;
|
||||
if (wp_distance <= get(PARAM_LOITER_RADIUS)){
|
||||
power = float(wp_distance) / float(get(PARAM_LOITER_RADIUS));
|
||||
nav_bearing += (int)(9000.0 * (2.0 + power));
|
||||
} else if (wp_distance < (get(PARAM_LOITER_RADIUS) + LOITER_RANGE)){
|
||||
power = -((float)(wp_distance - get(PARAM_LOITER_RADIUS) - LOITER_RANGE) / LOITER_RANGE);
|
||||
power = constrain(power, 0, 1);
|
||||
nav_bearing -= power * 9000;
|
||||
} else {
|
||||
update_crosstrack();
|
||||
}
|
||||
|
||||
nav_bearing = wrap_360(nav_bearing);
|
||||
|
||||
/* loiter_delta = (target_bearing - old_target_bearing)/100;
|
||||
// reset the old value
|
||||
old_target_bearing = target_bearing;
|
||||
// wrap values
|
||||
if (loiter_delta > 170) loiter_delta -= 360;
|
||||
if (loiter_delta < -170) loiter_delta += 360;
|
||||
loiter_sum += loiter_delta;
|
||||
*/
|
||||
}
|
||||
|
||||
void update_crosstrack(void)
|
||||
{
|
||||
// Crosstrack Error
|
||||
// ----------------
|
||||
if (abs(target_bearing - crosstrack_bearing) < 4500) { // If we are too far off or too close we don't do track following
|
||||
crosstrack_error = sin(radians((target_bearing - crosstrack_bearing)/100)) * wp_distance; // Meters we are off track line
|
||||
nav_bearing += constrain(crosstrack_error * get(PARAM_XTRACK_GAIN), -get(PARAM_XTRACK_ANGLE), get(PARAM_XTRACK_ANGLE));
|
||||
nav_bearing = wrap_360(nav_bearing);
|
||||
}
|
||||
}
|
||||
|
||||
void reset_crosstrack()
|
||||
{
|
||||
crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following
|
||||
}
|
||||
|
||||
long get_altitude_above_home(void)
|
||||
{
|
||||
// This is the altitude above the home location
|
||||
// The GPS gives us altitude at Sea Level
|
||||
// if you slope soar, you should see a negative number sometimes
|
||||
// -------------------------------------------------------------
|
||||
return current_loc.alt - home.alt;
|
||||
}
|
||||
|
||||
long getDistance(struct Location *loc1, struct Location *loc2)
|
||||
{
|
||||
if(loc1->lat == 0 || loc1->lng == 0)
|
||||
return -1;
|
||||
if(loc2->lat == 0 || loc2->lng == 0)
|
||||
return -1;
|
||||
float dlat = (float)(loc2->lat - loc1->lat);
|
||||
float dlong = ((float)(loc2->lng - loc1->lng)) * scaleLongDown;
|
||||
return sqrt(sq(dlat) + sq(dlong)) * .01113195;
|
||||
}
|
||||
|
||||
long get_alt_distance(struct Location *loc1, struct Location *loc2)
|
||||
{
|
||||
return abs(loc1->alt - loc2->alt);
|
||||
}
|
||||
|
||||
long get_bearing(struct Location *loc1, struct Location *loc2)
|
||||
{
|
||||
long off_x = loc2->lng - loc1->lng;
|
||||
long off_y = (loc2->lat - loc1->lat) * scaleLongUp;
|
||||
long bearing = 9000 + atan2(-off_y, off_x) * 5729.57795;
|
||||
if (bearing < 0) bearing += 36000;
|
||||
return bearing;
|
||||
}
|
|
@ -0,0 +1,114 @@
|
|||
//
|
||||
// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT
|
||||
//
|
||||
/// @file param_init.pde
|
||||
|
||||
void param_reset_defaults(void)
|
||||
{
|
||||
set(PARAM_HDNG2RLL_P, NAV_ROLL_P);
|
||||
set(PARAM_HDNG2RLL_I, NAV_ROLL_I);
|
||||
set(PARAM_HDNG2RLL_D, NAV_ROLL_D);
|
||||
set(PARAM_HDNG2RLL_IMAX, NAV_ROLL_INT_MAX);
|
||||
set(PARAM_RLL2SRV_P, SERVO_ROLL_P);
|
||||
set(PARAM_RLL2SRV_I, SERVO_ROLL_I);
|
||||
set(PARAM_RLL2SRV_D, SERVO_ROLL_D);
|
||||
set(PARAM_RLL2SRV_IMAX, SERVO_ROLL_INT_MAX);
|
||||
set(PARAM_PTCH2SRV_P, SERVO_PITCH_P);
|
||||
set(PARAM_PTCH2SRV_I, SERVO_PITCH_I);
|
||||
set(PARAM_PTCH2SRV_D, SERVO_PITCH_D);
|
||||
set(PARAM_PTCH2SRV_IMAX, SERVO_PITCH_INT_MAX);
|
||||
set(PARAM_ARSPD2PTCH_P, NAV_PITCH_ASP_P);
|
||||
set(PARAM_ARSPD2PTCH_I, NAV_PITCH_ASP_I);
|
||||
set(PARAM_ARSPD2PTCH_D, NAV_PITCH_ASP_D);
|
||||
set(PARAM_ARSPD2PTCH_IMAX, NAV_PITCH_ASP_INT_MAX);
|
||||
set(PARAM_YW2SRV_P, SERVO_YAW_P);
|
||||
set(PARAM_YW2SRV_I, SERVO_YAW_I);
|
||||
set(PARAM_YW2SRV_D, SERVO_YAW_D);
|
||||
set(PARAM_YW2SRV_IMAX, SERVO_YAW_INT_MAX);
|
||||
set(PARAM_ALT2THR_P, THROTTLE_ALT_P);
|
||||
set(PARAM_ALT2THR_I, THROTTLE_ALT_I);
|
||||
set(PARAM_ALT2THR_D, THROTTLE_ALT_D);
|
||||
set(PARAM_ALT2THR_IMAX, THROTTLE_ALT_INT_MAX);
|
||||
set(PARAM_ENRGY2THR_P, THROTTLE_TE_P);
|
||||
set(PARAM_ENRGY2THR_I, THROTTLE_TE_I);
|
||||
set(PARAM_ENRGY2THR_D, THROTTLE_TE_D);
|
||||
set(PARAM_ENRGY2THR_IMAX, THROTTLE_TE_INT_MAX);
|
||||
set(PARAM_ALT2PTCH_P, NAV_PITCH_ALT_P);
|
||||
set(PARAM_ALT2PTCH_I, NAV_PITCH_ALT_I);
|
||||
set(PARAM_ALT2PTCH_D, NAV_PITCH_ALT_D);
|
||||
set(PARAM_ALT2PTCH_IMAX, NAV_PITCH_ALT_INT_MAX);
|
||||
set(PARAM_KFF_PTCHCOMP, PITCH_COMP);
|
||||
set(PARAM_KFF_RDDRMIX, RUDDER_MIX);
|
||||
set(PARAM_KFF_PTCH2THR, P_TO_T);
|
||||
set(PARAM_GND_ALT, 0);
|
||||
set(PARAM_TRIM_AIRSPEED, AIRSPEED_CRUISE);
|
||||
set(PARAM_XTRACK_ANGLE, XTRACK_ENTRY_ANGLE);
|
||||
set(PARAM_LIM_ROLL, HEAD_MAX);
|
||||
set(PARAM_LIM_PITCH_MAX, PITCH_MAX);
|
||||
set(PARAM_LIM_PITCH_MIN, PITCH_MIN);
|
||||
set(PARAM_ALT_MIX, ALTITUDE_MIX);
|
||||
set(PARAM_ALT_HOLD_HOME, 0);
|
||||
set(PARAM_ARSPD_RATIO, AIRSPEED_RATIO);
|
||||
set(PARAM_IMU_OFFSET_0, 0);
|
||||
set(PARAM_IMU_OFFSET_1, 0);
|
||||
set(PARAM_IMU_OFFSET_2, 0);
|
||||
set(PARAM_IMU_OFFSET_3, 0);
|
||||
set(PARAM_IMU_OFFSET_4, 0);
|
||||
set(PARAM_IMU_OFFSET_5, 0);
|
||||
set(PARAM_YAW_MODE, 0);
|
||||
set(PARAM_WP_MODE, 0);
|
||||
set(PARAM_WP_TOTAL, WP_SIZE);
|
||||
set(PARAM_WP_INDEX, 0);
|
||||
set(PARAM_WP_RADIUS, WP_RADIUS_DEFAULT);
|
||||
set(PARAM_LOITER_RADIUS, LOITER_RADIUS_DEFAULT);
|
||||
set(PARAM_ARSPD_FBW_MIN, AIRSPEED_FBW_MIN);
|
||||
set(PARAM_ARSPD_FBW_MAX, AIRSPEED_FBW_MAX);
|
||||
set(PARAM_THR_MIN, THROTTLE_MIN);
|
||||
set(PARAM_THR_MAX, THROTTLE_MAX);
|
||||
set(PARAM_THR_FAILSAFE, THROTTLE_FAILSAFE);
|
||||
set(PARAM_THR_FS_ACTION, THROTTLE_FAILSAFE_ACTION);
|
||||
set(PARAM_TRIM_THROTTLE, THROTTLE_CRUISE);
|
||||
set(PARAM_CONFIG, 0);
|
||||
set(PARAM_TRIM_AUTO, AUTO_TRIM);
|
||||
set(PARAM_SWITCH_ENABLE, REVERSE_SWITCH);
|
||||
set(PARAM_FLIGHT_MODE_CH, FLIGHT_MODE_CHANNEL);
|
||||
set(PARAM_FLIGHT_MODE_1, FLIGHT_MODE_1);
|
||||
set(PARAM_FLIGHT_MODE_2, FLIGHT_MODE_2);
|
||||
set(PARAM_FLIGHT_MODE_3, FLIGHT_MODE_3);
|
||||
set(PARAM_FLIGHT_MODE_4, FLIGHT_MODE_4);
|
||||
set(PARAM_FLIGHT_MODE_5, FLIGHT_MODE_5);
|
||||
set(PARAM_FLIGHT_MODE_6, FLIGHT_MODE_6);
|
||||
set(PARAM_FIRMWARE_VER, FIRMWARE_VERSION);
|
||||
set(PARAM_RADIOTRIM_CH1, 1500);
|
||||
set(PARAM_RADIOTRIM_CH2, 1500);
|
||||
set(PARAM_RADIOTRIM_CH3, 1500);
|
||||
set(PARAM_RADIOTRIM_CH4, 1500);
|
||||
set(PARAM_RADIOTRIM_CH5, 1500);
|
||||
set(PARAM_RADIOTRIM_CH6, 1500);
|
||||
set(PARAM_RADIOTRIM_CH7, 1500);
|
||||
set(PARAM_RADIOTRIM_CH8, 1500);
|
||||
set(PARAM_RADIOMIN_CH1, 1000);
|
||||
set(PARAM_RADIOMIN_CH2, 1000);
|
||||
set(PARAM_RADIOMIN_CH3, 1000);
|
||||
set(PARAM_RADIOMIN_CH4, 1000);
|
||||
set(PARAM_RADIOMIN_CH5, CH5_MIN);
|
||||
set(PARAM_RADIOMIN_CH6, CH6_MIN);
|
||||
set(PARAM_RADIOMIN_CH7, CH7_MIN);
|
||||
set(PARAM_RADIOMIN_CH8, CH8_MIN);
|
||||
set(PARAM_RADIOMAX_CH1, 2000);
|
||||
set(PARAM_RADIOMAX_CH2, 2000);
|
||||
set(PARAM_RADIOMAX_CH3, 2000);
|
||||
set(PARAM_RADIOMAX_CH4, 2000);
|
||||
set(PARAM_RADIOMAX_CH5, CH5_MAX);
|
||||
set(PARAM_RADIOMAX_CH6, CH6_MAX);
|
||||
set(PARAM_RADIOMAX_CH7, CH7_MAX);
|
||||
set(PARAM_RADIOMAX_CH8, CH8_MAX);
|
||||
set(PARAM_LOG_BITMASK, 0);
|
||||
set(PARAM_TRIM_ELEVON, 1500);
|
||||
set(PARAM_THR_FS_VALUE, THROTTLE_FS_VALUE);
|
||||
set(PARAM_XTRACK_GAIN, XTRACK_GAIN);
|
||||
set(PARAM_GND_TEMP, 0);
|
||||
set(PARAM_AP_OFFSET, 0);
|
||||
set(PARAM_TRIM_PITCH, 0);
|
||||
set(PARAM_GND_ABS_PRESS, 0);
|
||||
}
|
|
@ -0,0 +1,230 @@
|
|||
//
|
||||
// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT
|
||||
//
|
||||
/// @file param_table.c
|
||||
|
||||
#pragma pack(push)
|
||||
#pragma pack(1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include "global_data.h"
|
||||
|
||||
#define PARAM_NAME(_name) static const char _param_ ## _name [] PROGMEM = #_name;
|
||||
#define PARAM_INDEX(_name) [PARAM_ ## _name] = _param_ ## _name
|
||||
|
||||
PARAM_NAME(THR_FS_VALUE);
|
||||
PARAM_NAME(XTRACK_GAIN);
|
||||
PARAM_NAME(GND_TEMP);
|
||||
PARAM_NAME(AP_OFFSET);
|
||||
PARAM_NAME(TRIM_PITCH);
|
||||
PARAM_NAME(GND_ABS_PRESS);
|
||||
PARAM_NAME(PTCH2SRV_D);
|
||||
PARAM_NAME(PTCH2SRV_IMAX);
|
||||
PARAM_NAME(ARSPD2PTCH_P);
|
||||
PARAM_NAME(ALT2THR_P);
|
||||
PARAM_NAME(ARSPD2PTCH_I);
|
||||
PARAM_NAME(ALT2THR_I);
|
||||
PARAM_NAME(ARSPD2PTCH_D);
|
||||
PARAM_NAME(ALT2THR_D);
|
||||
PARAM_NAME(ARSPD2PTCH_IMAX);
|
||||
PARAM_NAME(ALT2PTCH_D);
|
||||
PARAM_NAME(ALT2THR_IMAX);
|
||||
PARAM_NAME(YW2SRV_P);
|
||||
PARAM_NAME(ALT2PTCH_IMAX);
|
||||
PARAM_NAME(ENRGY2THR_P);
|
||||
PARAM_NAME(YW2SRV_I);
|
||||
PARAM_NAME(KFF_PTCHCOMP);
|
||||
PARAM_NAME(ENRGY2THR_I);
|
||||
PARAM_NAME(YW2SRV_D);
|
||||
PARAM_NAME(LIM_PITCH_MIN);
|
||||
PARAM_NAME(KFF_RDDRMIX);
|
||||
PARAM_NAME(ENRGY2THR_D);
|
||||
PARAM_NAME(YW2SRV_IMAX);
|
||||
PARAM_NAME(ALT_MIX);
|
||||
PARAM_NAME(KFF_PTCH2THR);
|
||||
PARAM_NAME(ENRGY2THR_IMAX);
|
||||
PARAM_NAME(ALT_HOLD_HOME);
|
||||
PARAM_NAME(GND_ALT);
|
||||
PARAM_NAME(ALT2PTCH_P);
|
||||
PARAM_NAME(YAW_MODE);
|
||||
PARAM_NAME(ARSPD_RATIO);
|
||||
PARAM_NAME(TRIM_AIRSPEED);
|
||||
PARAM_NAME(ALT2PTCH_I);
|
||||
PARAM_NAME(WP_MODE);
|
||||
PARAM_NAME(IMU_OFFSET_0);
|
||||
PARAM_NAME(XTRACK_ANGLE);
|
||||
PARAM_NAME(WP_TOTAL);
|
||||
PARAM_NAME(IMU_OFFSET_1);
|
||||
PARAM_NAME(LIM_ROLL);
|
||||
PARAM_NAME(THR_FAILSAFE);
|
||||
PARAM_NAME(WP_INDEX);
|
||||
PARAM_NAME(IMU_OFFSET_2);
|
||||
PARAM_NAME(LIM_PITCH_MAX);
|
||||
PARAM_NAME(THR_FS_ACTION);
|
||||
PARAM_NAME(WP_RADIUS);
|
||||
PARAM_NAME(IMU_OFFSET_3);
|
||||
PARAM_NAME(TRIM_THROTTLE);
|
||||
PARAM_NAME(LOITER_RADIUS);
|
||||
PARAM_NAME(IMU_OFFSET_4);
|
||||
PARAM_NAME(CONFIG);
|
||||
PARAM_NAME(ARSPD_FBW_MIN);
|
||||
PARAM_NAME(IMU_OFFSET_5);
|
||||
PARAM_NAME(FLIGHT_MODE_4);
|
||||
PARAM_NAME(ARSPD_FBW_MAX);
|
||||
PARAM_NAME(FLIGHT_MODE_5);
|
||||
PARAM_NAME(TRIM_AUTO);
|
||||
PARAM_NAME(THR_MIN);
|
||||
PARAM_NAME(FLIGHT_MODE_6);
|
||||
PARAM_NAME(SWITCH_ENABLE);
|
||||
PARAM_NAME(THR_MAX);
|
||||
PARAM_NAME(RADIOTRIM_CH7);
|
||||
PARAM_NAME(FIRMWARE_VER);
|
||||
PARAM_NAME(FLIGHT_MODE_CH);
|
||||
PARAM_NAME(RADIOTRIM_CH8);
|
||||
PARAM_NAME(RADIOTRIM_CH1);
|
||||
PARAM_NAME(FLIGHT_MODE_1);
|
||||
PARAM_NAME(RADIOMIN_CH1);
|
||||
PARAM_NAME(RADIOTRIM_CH2);
|
||||
PARAM_NAME(FLIGHT_MODE_2);
|
||||
PARAM_NAME(RADIOMAX_CH1);
|
||||
PARAM_NAME(RADIOMIN_CH2);
|
||||
PARAM_NAME(RADIOTRIM_CH3);
|
||||
PARAM_NAME(FLIGHT_MODE_3);
|
||||
PARAM_NAME(RADIOMAX_CH2);
|
||||
PARAM_NAME(RADIOMIN_CH3);
|
||||
PARAM_NAME(RADIOTRIM_CH4);
|
||||
PARAM_NAME(RADIOMAX_CH3);
|
||||
PARAM_NAME(RADIOMIN_CH4);
|
||||
PARAM_NAME(RADIOTRIM_CH5);
|
||||
PARAM_NAME(RADIOMAX_CH4);
|
||||
PARAM_NAME(RADIOMIN_CH5);
|
||||
PARAM_NAME(RADIOTRIM_CH6);
|
||||
PARAM_NAME(RADIOMAX_CH5);
|
||||
PARAM_NAME(RADIOMIN_CH6);
|
||||
PARAM_NAME(RADIOMAX_CH6);
|
||||
PARAM_NAME(RADIOMIN_CH7);
|
||||
PARAM_NAME(RADIOMAX_CH7);
|
||||
PARAM_NAME(RADIOMIN_CH8);
|
||||
PARAM_NAME(RADIOMAX_CH8);
|
||||
PARAM_NAME(LOG_BITMASK);
|
||||
PARAM_NAME(TRIM_ELEVON);
|
||||
PARAM_NAME(HDNG2RLL_P);
|
||||
PARAM_NAME(HDNG2RLL_I);
|
||||
PARAM_NAME(HDNG2RLL_D);
|
||||
PARAM_NAME(HDNG2RLL_IMAX);
|
||||
PARAM_NAME(RLL2SRV_P);
|
||||
PARAM_NAME(RLL2SRV_I);
|
||||
PARAM_NAME(RLL2SRV_D);
|
||||
PARAM_NAME(RLL2SRV_IMAX);
|
||||
PARAM_NAME(PTCH2SRV_P);
|
||||
PARAM_NAME(PTCH2SRV_I);
|
||||
|
||||
const char *param_nametab[] PROGMEM = {
|
||||
PARAM_INDEX(THR_FS_VALUE),
|
||||
PARAM_INDEX(XTRACK_GAIN),
|
||||
PARAM_INDEX(GND_TEMP),
|
||||
PARAM_INDEX(AP_OFFSET),
|
||||
PARAM_INDEX(TRIM_PITCH),
|
||||
PARAM_INDEX(GND_ABS_PRESS),
|
||||
PARAM_INDEX(PTCH2SRV_D),
|
||||
PARAM_INDEX(PTCH2SRV_IMAX),
|
||||
PARAM_INDEX(ARSPD2PTCH_P),
|
||||
PARAM_INDEX(ARSPD2PTCH_I),
|
||||
PARAM_INDEX(ALT2THR_P),
|
||||
PARAM_INDEX(ARSPD2PTCH_D),
|
||||
PARAM_INDEX(ALT2THR_I),
|
||||
PARAM_INDEX(ARSPD2PTCH_IMAX),
|
||||
PARAM_INDEX(ALT2THR_D),
|
||||
PARAM_INDEX(YW2SRV_P),
|
||||
PARAM_INDEX(ALT2THR_IMAX),
|
||||
PARAM_INDEX(ALT2PTCH_D),
|
||||
PARAM_INDEX(YW2SRV_I),
|
||||
PARAM_INDEX(ENRGY2THR_P),
|
||||
PARAM_INDEX(ALT2PTCH_IMAX),
|
||||
PARAM_INDEX(YW2SRV_D),
|
||||
PARAM_INDEX(ENRGY2THR_I),
|
||||
PARAM_INDEX(KFF_PTCHCOMP),
|
||||
PARAM_INDEX(YW2SRV_IMAX),
|
||||
PARAM_INDEX(ENRGY2THR_D),
|
||||
PARAM_INDEX(KFF_RDDRMIX),
|
||||
PARAM_INDEX(LIM_PITCH_MIN),
|
||||
PARAM_INDEX(ENRGY2THR_IMAX),
|
||||
PARAM_INDEX(KFF_PTCH2THR),
|
||||
PARAM_INDEX(ALT_MIX),
|
||||
PARAM_INDEX(ALT2PTCH_P),
|
||||
PARAM_INDEX(GND_ALT),
|
||||
PARAM_INDEX(ALT_HOLD_HOME),
|
||||
PARAM_INDEX(ALT2PTCH_I),
|
||||
PARAM_INDEX(TRIM_AIRSPEED),
|
||||
PARAM_INDEX(ARSPD_RATIO),
|
||||
PARAM_INDEX(YAW_MODE),
|
||||
PARAM_INDEX(XTRACK_ANGLE),
|
||||
PARAM_INDEX(IMU_OFFSET_0),
|
||||
PARAM_INDEX(WP_MODE),
|
||||
PARAM_INDEX(LIM_ROLL),
|
||||
PARAM_INDEX(IMU_OFFSET_1),
|
||||
PARAM_INDEX(WP_TOTAL),
|
||||
PARAM_INDEX(LIM_PITCH_MAX),
|
||||
PARAM_INDEX(IMU_OFFSET_2),
|
||||
PARAM_INDEX(WP_INDEX),
|
||||
PARAM_INDEX(THR_FAILSAFE),
|
||||
PARAM_INDEX(IMU_OFFSET_3),
|
||||
PARAM_INDEX(WP_RADIUS),
|
||||
PARAM_INDEX(THR_FS_ACTION),
|
||||
PARAM_INDEX(IMU_OFFSET_4),
|
||||
PARAM_INDEX(LOITER_RADIUS),
|
||||
PARAM_INDEX(TRIM_THROTTLE),
|
||||
PARAM_INDEX(FLIGHT_MODE_4),
|
||||
PARAM_INDEX(IMU_OFFSET_5),
|
||||
PARAM_INDEX(ARSPD_FBW_MIN),
|
||||
PARAM_INDEX(CONFIG),
|
||||
PARAM_INDEX(TRIM_AUTO),
|
||||
PARAM_INDEX(FLIGHT_MODE_5),
|
||||
PARAM_INDEX(ARSPD_FBW_MAX),
|
||||
PARAM_INDEX(SWITCH_ENABLE),
|
||||
PARAM_INDEX(FLIGHT_MODE_6),
|
||||
PARAM_INDEX(THR_MIN),
|
||||
PARAM_INDEX(FLIGHT_MODE_CH),
|
||||
PARAM_INDEX(FIRMWARE_VER),
|
||||
PARAM_INDEX(RADIOTRIM_CH7),
|
||||
PARAM_INDEX(THR_MAX),
|
||||
PARAM_INDEX(FLIGHT_MODE_1),
|
||||
PARAM_INDEX(RADIOTRIM_CH1),
|
||||
PARAM_INDEX(RADIOTRIM_CH8),
|
||||
PARAM_INDEX(FLIGHT_MODE_2),
|
||||
PARAM_INDEX(RADIOTRIM_CH2),
|
||||
PARAM_INDEX(RADIOMIN_CH1),
|
||||
PARAM_INDEX(FLIGHT_MODE_3),
|
||||
PARAM_INDEX(RADIOTRIM_CH3),
|
||||
PARAM_INDEX(RADIOMIN_CH2),
|
||||
PARAM_INDEX(RADIOMAX_CH1),
|
||||
PARAM_INDEX(RADIOTRIM_CH4),
|
||||
PARAM_INDEX(RADIOMIN_CH3),
|
||||
PARAM_INDEX(RADIOMAX_CH2),
|
||||
PARAM_INDEX(RADIOTRIM_CH5),
|
||||
PARAM_INDEX(RADIOMIN_CH4),
|
||||
PARAM_INDEX(RADIOMAX_CH3),
|
||||
PARAM_INDEX(RADIOTRIM_CH6),
|
||||
PARAM_INDEX(RADIOMIN_CH5),
|
||||
PARAM_INDEX(RADIOMAX_CH4),
|
||||
PARAM_INDEX(RADIOMIN_CH6),
|
||||
PARAM_INDEX(RADIOMAX_CH5),
|
||||
PARAM_INDEX(RADIOMIN_CH7),
|
||||
PARAM_INDEX(RADIOMAX_CH6),
|
||||
PARAM_INDEX(RADIOMIN_CH8),
|
||||
PARAM_INDEX(RADIOMAX_CH7),
|
||||
PARAM_INDEX(RADIOMAX_CH8),
|
||||
PARAM_INDEX(LOG_BITMASK),
|
||||
PARAM_INDEX(TRIM_ELEVON),
|
||||
PARAM_INDEX(HDNG2RLL_P),
|
||||
PARAM_INDEX(HDNG2RLL_I),
|
||||
PARAM_INDEX(HDNG2RLL_D),
|
||||
PARAM_INDEX(HDNG2RLL_IMAX),
|
||||
PARAM_INDEX(RLL2SRV_P),
|
||||
PARAM_INDEX(RLL2SRV_I),
|
||||
PARAM_INDEX(RLL2SRV_D),
|
||||
PARAM_INDEX(RLL2SRV_IMAX),
|
||||
PARAM_INDEX(PTCH2SRV_P),
|
||||
PARAM_INDEX(PTCH2SRV_I),
|
||||
};
|
|
@ -0,0 +1,142 @@
|
|||
//
|
||||
// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT
|
||||
//
|
||||
/// @file param_table.h
|
||||
|
||||
#define PARAM_FIRST_FLOAT 0
|
||||
enum float_param_t {
|
||||
PARAM_HDNG2RLL_P = PARAM_FIRST_FLOAT,
|
||||
PARAM_HDNG2RLL_I,
|
||||
PARAM_HDNG2RLL_D,
|
||||
PARAM_HDNG2RLL_IMAX,
|
||||
PARAM_RLL2SRV_P,
|
||||
PARAM_RLL2SRV_I,
|
||||
PARAM_RLL2SRV_D,
|
||||
PARAM_RLL2SRV_IMAX,
|
||||
PARAM_PTCH2SRV_P,
|
||||
PARAM_PTCH2SRV_I,
|
||||
PARAM_PTCH2SRV_D,
|
||||
PARAM_PTCH2SRV_IMAX,
|
||||
PARAM_ARSPD2PTCH_P,
|
||||
PARAM_ARSPD2PTCH_I,
|
||||
PARAM_ARSPD2PTCH_D,
|
||||
PARAM_ARSPD2PTCH_IMAX,
|
||||
PARAM_YW2SRV_P,
|
||||
PARAM_YW2SRV_I,
|
||||
PARAM_YW2SRV_D,
|
||||
PARAM_YW2SRV_IMAX,
|
||||
PARAM_ALT2THR_P,
|
||||
PARAM_ALT2THR_I,
|
||||
PARAM_ALT2THR_D,
|
||||
PARAM_ALT2THR_IMAX,
|
||||
PARAM_ENRGY2THR_P,
|
||||
PARAM_ENRGY2THR_I,
|
||||
PARAM_ENRGY2THR_D,
|
||||
PARAM_ENRGY2THR_IMAX,
|
||||
PARAM_ALT2PTCH_P,
|
||||
PARAM_ALT2PTCH_I,
|
||||
PARAM_ALT2PTCH_D,
|
||||
PARAM_ALT2PTCH_IMAX,
|
||||
PARAM_KFF_PTCHCOMP,
|
||||
PARAM_KFF_RDDRMIX,
|
||||
PARAM_KFF_PTCH2THR,
|
||||
PARAM_GND_ALT,
|
||||
PARAM_TRIM_AIRSPEED,
|
||||
PARAM_XTRACK_ANGLE,
|
||||
PARAM_LIM_ROLL,
|
||||
PARAM_LIM_PITCH_MAX,
|
||||
PARAM_LIM_PITCH_MIN,
|
||||
PARAM_ALT_MIX,
|
||||
PARAM_ALT_HOLD_HOME,
|
||||
PARAM_ARSPD_RATIO,
|
||||
PARAM_IMU_OFFSET_0,
|
||||
PARAM_IMU_OFFSET_1,
|
||||
PARAM_IMU_OFFSET_2,
|
||||
PARAM_IMU_OFFSET_3,
|
||||
PARAM_IMU_OFFSET_4,
|
||||
PARAM_IMU_OFFSET_5,
|
||||
PARAM_LAST_FLOAT
|
||||
};
|
||||
#define PARAM_FLOAT_COUNT (PARAM_LAST_FLOAT - PARAM_FIRST_FLOAT)
|
||||
|
||||
#define PARAM_FIRST_UINT8 PARAM_LAST_FLOAT
|
||||
enum uint8_param_t {
|
||||
PARAM_YAW_MODE = PARAM_FIRST_UINT8,
|
||||
PARAM_WP_MODE,
|
||||
PARAM_WP_TOTAL,
|
||||
PARAM_WP_INDEX,
|
||||
PARAM_WP_RADIUS,
|
||||
PARAM_LOITER_RADIUS,
|
||||
PARAM_ARSPD_FBW_MIN,
|
||||
PARAM_ARSPD_FBW_MAX,
|
||||
PARAM_THR_MIN,
|
||||
PARAM_THR_MAX,
|
||||
PARAM_THR_FAILSAFE,
|
||||
PARAM_THR_FS_ACTION,
|
||||
PARAM_TRIM_THROTTLE,
|
||||
PARAM_CONFIG,
|
||||
PARAM_TRIM_AUTO,
|
||||
PARAM_SWITCH_ENABLE,
|
||||
PARAM_FLIGHT_MODE_CH,
|
||||
PARAM_FLIGHT_MODE_1,
|
||||
PARAM_FLIGHT_MODE_2,
|
||||
PARAM_FLIGHT_MODE_3,
|
||||
PARAM_FLIGHT_MODE_4,
|
||||
PARAM_FLIGHT_MODE_5,
|
||||
PARAM_FLIGHT_MODE_6,
|
||||
PARAM_LAST_UINT8
|
||||
};
|
||||
#define PARAM_UINT8_COUNT (PARAM_LAST_UINT8 - PARAM_FIRST_UINT8)
|
||||
|
||||
#define PARAM_FIRST_UINT16 PARAM_LAST_UINT8
|
||||
enum uint16_param_t {
|
||||
PARAM_FIRMWARE_VER = PARAM_FIRST_UINT16,
|
||||
PARAM_RADIOTRIM_CH1,
|
||||
PARAM_RADIOTRIM_CH2,
|
||||
PARAM_RADIOTRIM_CH3,
|
||||
PARAM_RADIOTRIM_CH4,
|
||||
PARAM_RADIOTRIM_CH5,
|
||||
PARAM_RADIOTRIM_CH6,
|
||||
PARAM_RADIOTRIM_CH7,
|
||||
PARAM_RADIOTRIM_CH8,
|
||||
PARAM_RADIOMIN_CH1,
|
||||
PARAM_RADIOMIN_CH2,
|
||||
PARAM_RADIOMIN_CH3,
|
||||
PARAM_RADIOMIN_CH4,
|
||||
PARAM_RADIOMIN_CH5,
|
||||
PARAM_RADIOMIN_CH6,
|
||||
PARAM_RADIOMIN_CH7,
|
||||
PARAM_RADIOMIN_CH8,
|
||||
PARAM_RADIOMAX_CH1,
|
||||
PARAM_RADIOMAX_CH2,
|
||||
PARAM_RADIOMAX_CH3,
|
||||
PARAM_RADIOMAX_CH4,
|
||||
PARAM_RADIOMAX_CH5,
|
||||
PARAM_RADIOMAX_CH6,
|
||||
PARAM_RADIOMAX_CH7,
|
||||
PARAM_RADIOMAX_CH8,
|
||||
PARAM_LOG_BITMASK,
|
||||
PARAM_TRIM_ELEVON,
|
||||
PARAM_THR_FS_VALUE,
|
||||
PARAM_LAST_UINT16
|
||||
};
|
||||
#define PARAM_UINT16_COUNT (PARAM_LAST_UINT16 - PARAM_FIRST_UINT16)
|
||||
|
||||
#define PARAM_FIRST_INT16 PARAM_LAST_UINT16
|
||||
enum int16_param_t {
|
||||
PARAM_XTRACK_GAIN = PARAM_FIRST_INT16,
|
||||
PARAM_GND_TEMP,
|
||||
PARAM_AP_OFFSET,
|
||||
PARAM_TRIM_PITCH,
|
||||
PARAM_LAST_INT16
|
||||
};
|
||||
#define PARAM_INT16_COUNT (PARAM_LAST_INT16 - PARAM_FIRST_INT16)
|
||||
|
||||
#define PARAM_FIRST_UINT32 PARAM_LAST_INT16
|
||||
enum uint32_param_t {
|
||||
PARAM_GND_ABS_PRESS = PARAM_FIRST_UINT32,
|
||||
PARAM_LAST_UINT32
|
||||
};
|
||||
#define PARAM_UINT32_COUNT (PARAM_LAST_UINT32 - PARAM_FIRST_UINT32)
|
||||
|
||||
#define PARAM_COUNT PARAM_LAST_UINT32
|
|
@ -0,0 +1,126 @@
|
|||
#
|
||||
# Process the parameter specification and produce the parameter enumerations and
|
||||
# name table.
|
||||
#
|
||||
# See paramgen.in for details of the input format
|
||||
#
|
||||
|
||||
BEGIN {
|
||||
paramIndex = 0
|
||||
typeIndex = 0
|
||||
firstInType = 0
|
||||
|
||||
printf("//\n// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT\n//\n") > "param_table.h"
|
||||
printf("/// @file param_table.h\n\n") > "param_table.h"
|
||||
|
||||
printf("//\n// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT\n//\n") > "param_init.pde"
|
||||
printf("/// @file param_init.pde\n\n") > "param_init.pde"
|
||||
printf("void param_reset_defaults(void)\n") > "param_init.pde"
|
||||
printf("{\n") > "param_init.pde"
|
||||
|
||||
printf("//\n// THIS FILE WAS AUTOMATICALLY GENERATED - DO NOT EDIT\n//\n") > "param_table.c"
|
||||
printf("/// @file param_table.c\n\n") > "param_table.c"
|
||||
printf("#pragma pack(push)\n") > "param_table.c"
|
||||
printf("#pragma pack(1)\n\n") > "param_table.c"
|
||||
printf("#include <stdint.h>\n") > "param_table.c"
|
||||
printf("#include <avr/pgmspace.h>\n") > "param_table.c"
|
||||
printf("#include \"global_data.h\"\n\n") > "param_table.c"
|
||||
printf("#define PARAM_NAME(_name) static const char _param_ ## _name [] PROGMEM = #_name;\n") > "param_table.c"
|
||||
printf("#define PARAM_INDEX(_name) [PARAM_ ## _name] = _param_ ## _name\n\n") > "param_table.c"
|
||||
|
||||
|
||||
}
|
||||
|
||||
function END_ENUM() {
|
||||
printf(" PARAM_LAST_%s\n", currentType) > "param_table.h"
|
||||
printf("};\n") > "param_table.h"
|
||||
printf("#define PARAM_%s_COUNT (PARAM_LAST_%s - PARAM_FIRST_%s)\n\n",
|
||||
currentType, currentType, currentType) > "param_table.h"
|
||||
}
|
||||
|
||||
#
|
||||
# skip lines containing comments
|
||||
#
|
||||
$1=="#" { next }
|
||||
|
||||
#
|
||||
# process a type section change
|
||||
#
|
||||
$1=="type" {
|
||||
|
||||
newType = toupper($2)
|
||||
|
||||
# if there's a type already open, close it
|
||||
if (currentType == "") {
|
||||
# first enum opens at index zero
|
||||
printf("#define PARAM_FIRST_%s 0\n", newType) > "param_table.h"
|
||||
} else {
|
||||
# finalise the preceding enum
|
||||
END_ENUM()
|
||||
|
||||
# chain the next enum's starting value off the previous
|
||||
printf("#define PARAM_FIRST_%s PARAM_LAST_%s\n", newType, currentType) > "param_table.h"
|
||||
}
|
||||
printf("enum %s_param_t {\n", tolower(newType)) > "param_table.h"
|
||||
|
||||
currentType = newType
|
||||
firstInType = 1
|
||||
|
||||
next
|
||||
}
|
||||
|
||||
#
|
||||
# process a parameter name
|
||||
#
|
||||
NF >= 1 {
|
||||
|
||||
paramName = $1
|
||||
paramInitial = $2
|
||||
|
||||
# emit the parameter inside the enum for param_table.h
|
||||
if (firstInType) {
|
||||
printf(" PARAM_%s = PARAM_FIRST_%s,\n", paramName, currentType) > "param_table.h"
|
||||
firstInType = 0
|
||||
} else {
|
||||
printf(" PARAM_%s,\n", paramName) > "param_table.h"
|
||||
}
|
||||
|
||||
# emit the call to the initialiser for param_init.pde
|
||||
if (paramInitial != "") {
|
||||
printf(" set(PARAM_%s, %s);\n", paramName, paramInitial) > "param_init.pde"
|
||||
}
|
||||
|
||||
# save name for param_table.c
|
||||
paramNames[paramIndex] = paramName
|
||||
paramIndex++
|
||||
}
|
||||
|
||||
END {
|
||||
#
|
||||
# close out the current enum
|
||||
#
|
||||
END_ENUM()
|
||||
printf("#define PARAM_COUNT PARAM_LAST_%s\n", currentType) > "param_table.h"
|
||||
|
||||
#
|
||||
# close the initialiser function
|
||||
#
|
||||
printf("}\n") > "param_init.pde"
|
||||
|
||||
|
||||
#
|
||||
# Generate param_table.c
|
||||
#
|
||||
# emit the PARAM_NAME invocations
|
||||
for (name in paramNames) {
|
||||
printf("PARAM_NAME(%s);\n", paramNames[name]) > "param_table.c"
|
||||
}
|
||||
|
||||
# emit the PARAM_INDEX array
|
||||
printf("\nconst char *param_nametab[] PROGMEM = {\n") > "param_table.c"
|
||||
for (name in paramNames) {
|
||||
printf(" PARAM_INDEX(%s),\n", paramNames[name]) > "param_table.c"
|
||||
}
|
||||
printf("};\n") > "param_table.c"
|
||||
}
|
||||
|
|
@ -0,0 +1,257 @@
|
|||
#
|
||||
# Parameter database specification
|
||||
#
|
||||
# This file describes the global parameters used by the ArduPilot Mega software.
|
||||
# Definitions here are used to produce the param_table.h, param_table.c and
|
||||
# param_init.pde files.
|
||||
#
|
||||
# Process this file with "awk -f paramgen.awk paramgen.in"
|
||||
#
|
||||
|
||||
#
|
||||
# Parameters are grouped by type, with the software expecting that the types
|
||||
# will be presented in the order float, uint8, uint16, int16, uint32.
|
||||
#
|
||||
# The following line formats are recognised
|
||||
#
|
||||
# type <type-name>
|
||||
#
|
||||
# Announces the start of the section of the file conatining parameters
|
||||
# of the type <type-name>.
|
||||
#
|
||||
# <parameter-name>
|
||||
#
|
||||
# Defines a parameter with the name <parameter-name>. This will result in
|
||||
# the generation of an enumeration named PARAM_<parameter-name>, and the
|
||||
# creation of an entry in the global param_nametab array indexed by the
|
||||
# enumeration, pointing to a PROGMEM string containing <parameter-name>.
|
||||
#
|
||||
# <parameter-name> <default-value>
|
||||
#
|
||||
# As above, but additionally an entry will be added to the param_init()
|
||||
# function that will reset the parameter to <default_value>.
|
||||
#
|
||||
#
|
||||
# ------------------------------------------------------------------
|
||||
#
|
||||
# !!! CHANGE THE FIRMWARE VERSION IF YOU MODIFY THIS FILE !!!
|
||||
#
|
||||
# If the firmware version in ROM and the firmware version
|
||||
# in this file do not match it is assumed that the EEProm is
|
||||
# in an unknown state and a factory reset is forced.
|
||||
# This is to prevent the user from reading EEProm values that
|
||||
# have been remapped to different locations in memory.
|
||||
#
|
||||
|
||||
# ======================================================================
|
||||
type float
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Gains
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Roll Control
|
||||
|
||||
# heading error from commnd to roll command deviation from trim
|
||||
# (bank to turn strategy)
|
||||
HDNG2RLL_P NAV_ROLL_P
|
||||
HDNG2RLL_I NAV_ROLL_I
|
||||
HDNG2RLL_D NAV_ROLL_D
|
||||
HDNG2RLL_IMAX NAV_ROLL_INT_MAX
|
||||
|
||||
# roll error from command to roll servo deviation from trim
|
||||
# (tracks commanded bank angle)
|
||||
RLL2SRV_P SERVO_ROLL_P
|
||||
RLL2SRV_I SERVO_ROLL_I
|
||||
RLL2SRV_D SERVO_ROLL_D
|
||||
RLL2SRV_IMAX SERVO_ROLL_INT_MAX
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Pitch Control
|
||||
|
||||
# pitch error from command to pitch servo deviation from trim
|
||||
# (front-side strategy)
|
||||
PTCH2SRV_P SERVO_PITCH_P
|
||||
PTCH2SRV_I SERVO_PITCH_I
|
||||
PTCH2SRV_D SERVO_PITCH_D
|
||||
PTCH2SRV_IMAX SERVO_PITCH_INT_MAX
|
||||
|
||||
# airspeed error from commnd to pitch servo deviation from trim
|
||||
# (back-side strategy)
|
||||
ARSPD2PTCH_P NAV_PITCH_ASP_P
|
||||
ARSPD2PTCH_I NAV_PITCH_ASP_I
|
||||
ARSPD2PTCH_D NAV_PITCH_ASP_D
|
||||
ARSPD2PTCH_IMAX NAV_PITCH_ASP_INT_MAX
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Yaw Control
|
||||
|
||||
# yaw rate error from commnd to yaw servo deviation from trim
|
||||
# (stabilizes dutch roll)
|
||||
YW2SRV_P SERVO_YAW_P
|
||||
YW2SRV_I SERVO_YAW_I
|
||||
YW2SRV_D SERVO_YAW_D
|
||||
YW2SRV_IMAX SERVO_YAW_INT_MAX
|
||||
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Throttle Control
|
||||
|
||||
# altitude error from commnd to throttle servo deviation from trim
|
||||
# (throttle back-side strategy)
|
||||
ALT2THR_P THROTTLE_ALT_P
|
||||
ALT2THR_I THROTTLE_ALT_I
|
||||
ALT2THR_D THROTTLE_ALT_D
|
||||
ALT2THR_IMAX THROTTLE_ALT_INT_MAX
|
||||
|
||||
# total energy error from commnd to throttle servo deviation from trim
|
||||
# (throttle back-side strategy alternative)
|
||||
ENRGY2THR_P THROTTLE_TE_P
|
||||
ENRGY2THR_I THROTTLE_TE_I
|
||||
ENRGY2THR_D THROTTLE_TE_D
|
||||
ENRGY2THR_IMAX THROTTLE_TE_INT_MAX
|
||||
|
||||
# altitude error from commnd to pitch servo deviation from trim
|
||||
# (throttle front-side strategy alternative)
|
||||
ALT2PTCH_P NAV_PITCH_ALT_P
|
||||
ALT2PTCH_I NAV_PITCH_ALT_I
|
||||
ALT2PTCH_D NAV_PITCH_ALT_D
|
||||
ALT2PTCH_IMAX NAV_PITCH_ALT_INT_MAX
|
||||
|
||||
|
||||
# feed forward gains
|
||||
KFF_PTCHCOMP PITCH_COMP
|
||||
KFF_RDDRMIX RUDDER_MIX
|
||||
KFF_PTCH2THR P_TO_T
|
||||
|
||||
# misc
|
||||
GND_ALT 0
|
||||
TRIM_AIRSPEED AIRSPEED_CRUISE
|
||||
XTRACK_ANGLE XTRACK_ENTRY_ANGLE
|
||||
|
||||
# limits
|
||||
LIM_ROLL HEAD_MAX
|
||||
LIM_PITCH_MAX PITCH_MAX
|
||||
LIM_PITCH_MIN PITCH_MIN
|
||||
|
||||
# estimation
|
||||
ALT_MIX ALTITUDE_MIX
|
||||
ALT_HOLD_HOME 0
|
||||
ARSPD_RATIO AIRSPEED_RATIO
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# IMU Calibration
|
||||
|
||||
IMU_OFFSET_0 0
|
||||
IMU_OFFSET_1 0
|
||||
IMU_OFFSET_2 0
|
||||
IMU_OFFSET_3 0
|
||||
IMU_OFFSET_4 0
|
||||
IMU_OFFSET_5 0
|
||||
|
||||
# ======================================================================
|
||||
type uint8
|
||||
|
||||
# not used currently
|
||||
YAW_MODE 0
|
||||
|
||||
# waypoints
|
||||
WP_MODE 0
|
||||
WP_TOTAL WP_SIZE
|
||||
WP_INDEX 0
|
||||
WP_RADIUS WP_RADIUS_DEFAULT
|
||||
LOITER_RADIUS LOITER_RADIUS_DEFAULT
|
||||
|
||||
# fly by wire
|
||||
ARSPD_FBW_MIN AIRSPEED_FBW_MIN
|
||||
ARSPD_FBW_MAX AIRSPEED_FBW_MAX
|
||||
|
||||
# throttle
|
||||
THR_MIN THROTTLE_MIN
|
||||
THR_MAX THROTTLE_MAX
|
||||
THR_FAILSAFE THROTTLE_FAILSAFE
|
||||
THR_FS_ACTION THROTTLE_FAILSAFE_ACTION
|
||||
TRIM_THROTTLE THROTTLE_CRUISE
|
||||
|
||||
# misc
|
||||
CONFIG 0
|
||||
TRIM_AUTO AUTO_TRIM
|
||||
SWITCH_ENABLE REVERSE_SWITCH
|
||||
|
||||
# flight modes
|
||||
FLIGHT_MODE_CH FLIGHT_MODE_CHANNEL
|
||||
FLIGHT_MODE_1 FLIGHT_MODE_1
|
||||
FLIGHT_MODE_2 FLIGHT_MODE_2
|
||||
FLIGHT_MODE_3 FLIGHT_MODE_3
|
||||
FLIGHT_MODE_4 FLIGHT_MODE_4
|
||||
FLIGHT_MODE_5 FLIGHT_MODE_5
|
||||
FLIGHT_MODE_6 FLIGHT_MODE_6
|
||||
|
||||
# ======================================================================
|
||||
type uint16
|
||||
|
||||
FIRMWARE_VER FIRMWARE_VERSION
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Radio Settings
|
||||
#
|
||||
# all radio settings are uint16_t and represent the period of the
|
||||
# pulse width modulated signal. Typically 1000 ms is the lower limit,
|
||||
# 1500 is neutral, and 2000 is the upper limit
|
||||
|
||||
# trim (neutral setting)
|
||||
RADIOTRIM_CH1 1500
|
||||
RADIOTRIM_CH2 1500
|
||||
RADIOTRIM_CH3 1500
|
||||
RADIOTRIM_CH4 1500
|
||||
RADIOTRIM_CH5 1500
|
||||
RADIOTRIM_CH6 1500
|
||||
RADIOTRIM_CH7 1500
|
||||
RADIOTRIM_CH8 1500
|
||||
|
||||
# min (maps to 0%)
|
||||
RADIOMIN_CH1 1000
|
||||
RADIOMIN_CH2 1000
|
||||
RADIOMIN_CH3 1000
|
||||
RADIOMIN_CH4 1000
|
||||
RADIOMIN_CH5 CH5_MIN
|
||||
RADIOMIN_CH6 CH6_MIN
|
||||
RADIOMIN_CH7 CH7_MIN
|
||||
RADIOMIN_CH8 CH8_MIN
|
||||
|
||||
# max (maps to 100%)
|
||||
RADIOMAX_CH1 2000
|
||||
RADIOMAX_CH2 2000
|
||||
RADIOMAX_CH3 2000
|
||||
RADIOMAX_CH4 2000
|
||||
RADIOMAX_CH5 CH5_MAX
|
||||
RADIOMAX_CH6 CH6_MAX
|
||||
RADIOMAX_CH7 CH7_MAX
|
||||
RADIOMAX_CH8 CH8_MAX
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Misc
|
||||
|
||||
LOG_BITMASK 0
|
||||
TRIM_ELEVON 1500
|
||||
THR_FS_VALUE THROTTLE_FS_VALUE
|
||||
|
||||
# ======================================================================
|
||||
type int16
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Misc
|
||||
|
||||
XTRACK_GAIN XTRACK_GAIN
|
||||
GND_TEMP 0
|
||||
AP_OFFSET 0
|
||||
TRIM_PITCH 0
|
||||
|
||||
|
||||
# ======================================================================
|
||||
type uint32
|
||||
|
||||
# ------------------------------------------------------------------
|
||||
# Misc
|
||||
|
||||
GND_ABS_PRESS 0
|
|
@ -0,0 +1,199 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
//Function that will read the radio data, limit servos and trigger a failsafe
|
||||
// ----------------------------------------------------------------------------
|
||||
byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||
|
||||
void read_radio()
|
||||
{
|
||||
ch1_temp = APM_RC.InputCh(CH_ROLL);
|
||||
ch2_temp = APM_RC.InputCh(CH_PITCH);
|
||||
|
||||
if(mix_mode == 0){
|
||||
radio_in[CH_ROLL] = ch1_temp;
|
||||
radio_in[CH_PITCH] = ch2_temp;
|
||||
}else{
|
||||
radio_in[CH_ROLL] = reverse_elevons * (reverse_ch2_elevon * int(ch2_temp - elevon2_trim) - reverse_ch1_elevon * int(ch1_temp - elevon1_trim)) / 2 + 1500;
|
||||
radio_in[CH_PITCH] = (reverse_ch2_elevon * int(ch2_temp - elevon2_trim) + reverse_ch1_elevon * int(ch1_temp - elevon1_trim)) / 2 + 1500;
|
||||
}
|
||||
|
||||
for (int y = 2; y < 8; y++)
|
||||
radio_in[y] = APM_RC.InputCh(y);
|
||||
|
||||
#if THROTTLE_REVERSE == 1
|
||||
radio_in[CH_THROTTLE] = radio_max(CH_THROTTLE) + radio_min(CH_THROTTLE) - radio_in[CH_THROTTLE];
|
||||
#endif
|
||||
|
||||
throttle_failsafe(radio_in[CH_THROTTLE]);
|
||||
servo_out[CH_THROTTLE] = ((float)(radio_in[CH_THROTTLE] - radio_min(CH_THROTTLE)) /
|
||||
(float)(radio_max(CH_THROTTLE) - radio_min(CH_THROTTLE))) * 100;
|
||||
servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100);
|
||||
|
||||
if (servo_out[CH_THROTTLE] > 50) {
|
||||
if(AIRSPEED_SENSOR == 1) {
|
||||
airspeed_nudge = (get(PARAM_ARSPD_FBW_MAX) - get(PARAM_TRIM_AIRSPEED)) * ((servo_out[CH_THROTTLE]-50) * 2);
|
||||
} else {
|
||||
throttle_nudge = (get(PARAM_THR_MAX) - get(PARAM_TRIM_THROTTLE)) * ((servo_out[CH_THROTTLE]-50) * 2);
|
||||
}
|
||||
} else {
|
||||
airspeed_nudge = 0;
|
||||
throttle_nudge = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void throttle_failsafe(uint16_t pwm)
|
||||
{
|
||||
if(get(PARAM_THR_FAILSAFE)== 0)
|
||||
return;
|
||||
|
||||
//check for failsafe and debounce funky reads
|
||||
// ------------------------------------------
|
||||
if (pwm < get(PARAM_THR_FS_VALUE)){
|
||||
// we detect a failsafe from radio
|
||||
// throttle has dropped below the mark
|
||||
failsafeCounter++;
|
||||
if (failsafeCounter == 9){
|
||||
SendDebug("MSG FS ON ");
|
||||
SendDebugln(pwm, DEC);
|
||||
}else if(failsafeCounter == 10) {
|
||||
ch3_failsafe = true;
|
||||
//set_failsafe(true);
|
||||
//failsafeCounter = 10;
|
||||
}else if (failsafeCounter > 10){
|
||||
failsafeCounter = 11;
|
||||
}
|
||||
|
||||
}else if(failsafeCounter > 0){
|
||||
// we are no longer in failsafe condition
|
||||
// but we need to recover quickly
|
||||
failsafeCounter--;
|
||||
if (failsafeCounter > 3){
|
||||
failsafeCounter = 3;
|
||||
}
|
||||
if (failsafeCounter == 1){
|
||||
SendDebug("MSG FS OFF ");
|
||||
SendDebugln(pwm, DEC);
|
||||
}else if(failsafeCounter == 0) {
|
||||
ch3_failsafe = false;
|
||||
//set_failsafe(false);
|
||||
//failsafeCounter = -1;
|
||||
}else if (failsafeCounter <0){
|
||||
failsafeCounter = -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void trim_control_surfaces()
|
||||
{
|
||||
// Store control surface trim values
|
||||
// ---------------------------------
|
||||
if(mix_mode == 0){
|
||||
set_radio_trim(CH_ROLL,radio_in[CH_ROLL]);
|
||||
set_radio_trim(CH_PITCH,radio_in[CH_PITCH]);
|
||||
set_radio_trim(CH_RUDDER,radio_in[CH_RUDDER]);
|
||||
}else{
|
||||
elevon1_trim = ch1_temp;
|
||||
elevon2_trim = ch2_temp;
|
||||
//Recompute values here using new values for elevon1_trim and elevon2_trim
|
||||
//We cannot use radio_in[CH_ROLL] and radio_in[CH_PITCH] values from read_radio() because the elevon trim values have changed
|
||||
uint16_t center = 1500;
|
||||
set_radio_trim(CH_ROLL,center);
|
||||
set_radio_trim(CH_PITCH,center);
|
||||
}
|
||||
// disabled for now
|
||||
//save_EEPROM_trims();
|
||||
}
|
||||
|
||||
void trim_radio()
|
||||
{
|
||||
for (int y = 0; y < 50; y++) {
|
||||
read_radio();
|
||||
}
|
||||
|
||||
// Store the trim values
|
||||
// ---------------------
|
||||
if(mix_mode == 0){
|
||||
for (int y = 0; y < 8; y++) set_radio_trim(y,radio_in[y]);
|
||||
}else{
|
||||
elevon1_trim = ch1_temp;
|
||||
elevon2_trim = ch2_temp;
|
||||
uint16_t center = 1500;
|
||||
set_radio_trim(CH_ROLL,center);
|
||||
set_radio_trim(CH_PITCH,center);
|
||||
for (int y = 2; y < 8; y++) set_radio_trim(y,radio_in[y]);
|
||||
}
|
||||
//save_EEPROM_trims();
|
||||
}
|
||||
|
||||
|
||||
#if SET_RADIO_LIMITS == 1
|
||||
void read_radio_limits()
|
||||
{
|
||||
// set initial servo limits for calibration routine
|
||||
// -------------------------------------------------
|
||||
set_radio_min(CH_ROLL,radio_in[CH_ROLL] - 150);
|
||||
set_radio_max(CH_ROLL,radio_in[CH_ROLL] + 150);
|
||||
|
||||
set_radio_min(CH_PITCH,radio_in[CH_PITCH] - 150);
|
||||
set_radio_max(CH_PITCH,radio_in[CH_PITCH] + 150);
|
||||
|
||||
// vars for the radio config routine
|
||||
// ---------------------------------
|
||||
int counter = 0;
|
||||
long reminder;
|
||||
reminder = millis() - 10000;
|
||||
|
||||
uint16_t tempMin[2] = {radio_min(CH_ROLL), radio_min(CH_PITCH)} ;
|
||||
uint16_t tempMax[2] = {radio_max(CH_ROLL), radio_max(CH_PITCH)} ;
|
||||
|
||||
// Allows user to set stick limits and calibrate the IR
|
||||
// ----------------------------------------------------
|
||||
while(counter < 50){
|
||||
|
||||
if (millis() - reminder >= 10000) { // Remind user every 10 seconds what is going on
|
||||
GCS.send_text(SEVERITY_LOW,"Reading radio limits:");
|
||||
GCS.send_text(SEVERITY_LOW,"Move sticks to: upper right and lower Left");
|
||||
GCS.send_text(SEVERITY_LOW,"To Continue, hold the stick in the corner for 2 seconds.");
|
||||
GCS.send_text(SEVERITY_LOW," ");
|
||||
//print_radio();
|
||||
demo_servos(1);
|
||||
reminder = millis();
|
||||
}
|
||||
|
||||
delay(40);
|
||||
read_radio();
|
||||
|
||||
// AutoSet servo limits
|
||||
// --------------------
|
||||
if (radio_in[CH_ROLL] > 1000 && radio_in[CH_ROLL] < 2000){
|
||||
tempMin[CH_ROLL] = min(radio_in[CH_ROLL], tempMin[CH_ROLL]);
|
||||
tempMax[CH_ROLL] = max(radio_in[CH_ROLL], tempMax[CH_ROLL]);
|
||||
}
|
||||
|
||||
if (radio_in[CH_PITCH] > 1000 && radio_in[CH_PITCH]< 2000){
|
||||
tempMin[CH_PITCH] = min(radio_in[CH_PITCH], tempMin[CH_PITCH]);
|
||||
tempMax[CH_PITCH] = max(radio_in[CH_PITCH], tempMax[CH_PITCH]);
|
||||
}
|
||||
if(radio_in[CH_PITCH] < (tempMin[CH_PITCH] + 30) || tempMin[CH_PITCH] > (tempMax[CH_PITCH] -30)){
|
||||
SendDebug(".");
|
||||
counter++;
|
||||
}else{
|
||||
if (counter > 0)
|
||||
counter--;
|
||||
}
|
||||
}
|
||||
|
||||
// contstrain min values
|
||||
// ---------------------
|
||||
set_radio_min(CH_ROLL,constrain(tempMin[CH_ROLL], 800, 2200));
|
||||
set_radio_max(CH_ROLL,constrain(tempMax[CH_ROLL], 800, 2200));
|
||||
set_radio_min(CH_PITCH,constrain(tempMin[CH_PITCH], 800, 2200));
|
||||
set_radio_max(CH_PITCH,constrain(tempMax[CH_PITCH], 800, 2200));
|
||||
|
||||
SendDebugln(" ");
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,70 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
void ReadSCP1000(void) {}
|
||||
|
||||
// Sensors are not available in HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
||||
void read_airpressure(void){
|
||||
double x;
|
||||
|
||||
pitot.Read(); // Get new data from absolute pressure sensor
|
||||
abs_press = pitot.Press;
|
||||
abs_press_filt = (abs_press); // + 2l * abs_press_filt) / 3l; // Light filtering
|
||||
//temperature = (temperature * 9 + temp_unfilt) / 10; We will just use the ground temp for the altitude calculation
|
||||
|
||||
double p = (double)abs_press_gnd / (double)abs_press_filt;
|
||||
double temp = (float)ground_temperature / 10.f + 273.15f;
|
||||
x = log(p) * temp * 29271.267f;
|
||||
//x = log(p) * temp * 29.271267 * 1000;
|
||||
press_alt = (long)(x / 10) + ground_alt; // Pressure altitude in centimeters
|
||||
// Need to add comments for theory.....
|
||||
}
|
||||
|
||||
// in M/S * 100
|
||||
void read_airspeed(void)
|
||||
{
|
||||
#if GPS_PROTOCOL != GPS_PROTOCOL_IMU // Xplane will supply the airspeed
|
||||
airpressure_raw = ((float)adc.Ch(AIRSPEED_CH) * .25) + (airpressure_raw * .75);
|
||||
airpressure = (int)airpressure_raw - airpressure_offset;
|
||||
airpressure = max(airpressure, 0);
|
||||
airspeed = sqrt((float)airpressure * get(PARAM_ARSPD_RATIO)) * 100;
|
||||
#endif
|
||||
|
||||
calc_airspeed_errors();
|
||||
}
|
||||
|
||||
void zero_airspeed(void)
|
||||
{
|
||||
airpressure_raw = (float)adc.Ch(AIRSPEED_CH);
|
||||
for(int c = 0; c < 50; c++){
|
||||
delay(20);
|
||||
airpressure_raw = (airpressure_raw * .90) + ((float)adc.Ch(AIRSPEED_CH) * .10);
|
||||
}
|
||||
airpressure_offset = airpressure_raw;
|
||||
}
|
||||
|
||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
||||
#if BATTERY_EVENT == 1
|
||||
void read_battery(void)
|
||||
{
|
||||
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9;
|
||||
battery_voltage2 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9;
|
||||
battery_voltage3 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN3)) * .1 + battery_voltage3 * .9;
|
||||
battery_voltage4 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN4)) * .1 + battery_voltage4 * .9;
|
||||
|
||||
#if BATTERY_TYPE == 0
|
||||
if(battery_voltage3 < LOW_VOLTAGE)
|
||||
low_battery_event();
|
||||
battery_voltage = battery_voltage3; // set total battery voltage, for telemetry stream
|
||||
#endif
|
||||
|
||||
#if BATTERY_TYPE == 1
|
||||
if(battery_voltage4 < LOW_VOLTAGE)
|
||||
low_battery_event();
|
||||
battery_voltage = battery_voltage4; // set total battery voltage, for telemetry stream
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
|
@ -0,0 +1,229 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
// Functions called from the setup menu
|
||||
static int8_t setup_radio(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_show(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_factory(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_flightmodes(uint8_t argc, const Menu::arg *argv);
|
||||
|
||||
// Command/function table for the setup menu
|
||||
const struct Menu::command setup_menu_commands[] PROGMEM = {
|
||||
// command function called
|
||||
// ======= ===============
|
||||
{"reset", setup_factory},
|
||||
{"radio", setup_radio},
|
||||
{"modes", setup_flightmodes},
|
||||
{"show", setup_show},
|
||||
};
|
||||
|
||||
// Create the setup menu object.
|
||||
MENU(setup_menu, "setup", setup_menu_commands);
|
||||
|
||||
// Called from the top-level menu to run the setup menu.
|
||||
int8_t
|
||||
setup_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
// Give the user some guidance
|
||||
Serial.printf_P(PSTR("Setup Mode\n"
|
||||
"\n"
|
||||
"IMPORTANT: if you have not previously set this system up, use the\n"
|
||||
"'reset' command to initialize the EEPROM to sensible default values\n"
|
||||
"and then the 'radio' command to configure for your radio.\n"
|
||||
"\n"));
|
||||
|
||||
// Run the setup menu. When the menu exits, we will return to the main menu.
|
||||
setup_menu.run();
|
||||
}
|
||||
|
||||
// Print the current configuration.
|
||||
// Called by the setup menu 'show' command.
|
||||
static int8_t
|
||||
setup_show(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
printAllParams(Serial);
|
||||
return(0);
|
||||
}
|
||||
|
||||
// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults).
|
||||
// Called by the setup menu 'factoryreset' command.
|
||||
static int8_t
|
||||
setup_factory(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
|
||||
uint8_t i;
|
||||
int c;
|
||||
|
||||
Serial.printf_P(PSTR("\nType 'Y' and hit Enter to perform factory reset, any other key to abort: "));
|
||||
|
||||
do {
|
||||
c = Serial.read();
|
||||
} while (-1 == c);
|
||||
|
||||
if (('y' != c) && ('Y' != c))
|
||||
return(-1);
|
||||
|
||||
Serial.printf_P(PSTR("\nFACTORY RESET\n\n"));
|
||||
param_reset_defaults();
|
||||
return(0);
|
||||
}
|
||||
|
||||
// Perform radio setup.
|
||||
// Called by the setup menu 'radio' command.
|
||||
static int8_t
|
||||
setup_radio(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
Serial.println("\n\nRadio Setup:");
|
||||
uint8_t i;
|
||||
|
||||
for(i = 0; i < 100;i++){
|
||||
delay(20);
|
||||
read_radio();
|
||||
}
|
||||
|
||||
if(radio_in[CH_ROLL] < 500){
|
||||
while(1){
|
||||
Serial.print("Radio error");
|
||||
delay(1000);
|
||||
// stop here
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t tempMin[4], tempMax[4];
|
||||
for(i = 0; i < 4; i++){
|
||||
tempMin[i] = radio_in[i];
|
||||
tempMax[i] = radio_in[i];
|
||||
}
|
||||
|
||||
Serial.printf_P(PSTR("\nMove both sticks to each corner. Hit Enter to save: "));
|
||||
while(1){
|
||||
|
||||
delay(20);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
|
||||
for(i = 0; i < 4; i++){
|
||||
tempMin[i] = min(tempMin[i], radio_in[i]);
|
||||
tempMax[i] = max(tempMax[i], radio_in[i]);
|
||||
}
|
||||
|
||||
if(Serial.available() > 0){
|
||||
Serial.flush();
|
||||
Serial.println("Saving:");
|
||||
|
||||
for(i = 0; i < 4; i++)
|
||||
{
|
||||
set_radio_max(i, tempMax[i]);
|
||||
set_radio_min(i, tempMin[i]);
|
||||
}
|
||||
|
||||
for(i = 0; i < 8; i++)
|
||||
Serial.printf_P(PSTR("CH%d: %d | %d\n"), i + 1, radio_min(i), radio_max(i));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
||||
static int8_t
|
||||
setup_flightmodes(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
byte switchPosition, oldSwitchPosition, mode;
|
||||
|
||||
Serial.printf_P(PSTR("\nMove RC toggle switch to each position to edit, move aileron stick to select modes."));
|
||||
print_hit_enter();
|
||||
trim_radio();
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
read_radio();
|
||||
switchPosition = readSwitch();
|
||||
|
||||
|
||||
// look for control switch change
|
||||
if (oldSwitchPosition != switchPosition){
|
||||
// Override position 5
|
||||
if(switchPosition > 4){
|
||||
set_flight_mode(switchPosition,MANUAL);
|
||||
mode = MANUAL;
|
||||
}else{
|
||||
// update our current mode
|
||||
mode = flight_mode(switchPosition);
|
||||
}
|
||||
|
||||
// update the user
|
||||
print_switch(switchPosition, mode);
|
||||
|
||||
// Remember switch position
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
|
||||
// look for stick input
|
||||
int radioInputSwitch = radio_input_switch();
|
||||
|
||||
if (radioInputSwitch != 0){
|
||||
|
||||
mode += radioInputSwitch;
|
||||
|
||||
while (
|
||||
mode != MANUAL &&
|
||||
mode != CIRCLE &&
|
||||
mode != STABILIZE &&
|
||||
mode != FLY_BY_WIRE_A &&
|
||||
mode != FLY_BY_WIRE_B &&
|
||||
mode != AUTO &&
|
||||
mode != RTL &&
|
||||
mode != LOITER &&
|
||||
mode != TAKEOFF &&
|
||||
mode != LAND)
|
||||
{
|
||||
if (mode < MANUAL)
|
||||
mode = LAND;
|
||||
else if (mode >LAND)
|
||||
mode = MANUAL;
|
||||
else
|
||||
mode += radioInputSwitch;
|
||||
}
|
||||
|
||||
// Override position 5
|
||||
if(switchPosition > 4)
|
||||
mode = MANUAL;
|
||||
|
||||
// save new mode
|
||||
set_flight_mode(switchPosition,mode);
|
||||
|
||||
// print new mode
|
||||
print_switch(switchPosition, mode);
|
||||
}
|
||||
|
||||
// escape hatch
|
||||
if(Serial.available() > 0){
|
||||
//save_EEPROM_flight_modes();
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
print_switch(byte p, byte m)
|
||||
{
|
||||
Serial.printf_P(PSTR("Pos %d: "),p);
|
||||
Serial.println(flight_mode_strings[m]);
|
||||
}
|
||||
|
||||
int8_t
|
||||
radio_input_switch(void)
|
||||
{
|
||||
static int8_t bouncer = 0;
|
||||
|
||||
if (int16_t(radio_in[0] - radio_trim(0)) > 200) bouncer = 10;
|
||||
if (int16_t(radio_in[0] - radio_trim(0)) < -200) bouncer = -10;
|
||||
if (bouncer >0) bouncer --;
|
||||
if (bouncer <0) bouncer ++;
|
||||
|
||||
if (bouncer == 1 || bouncer == -1) return bouncer;
|
||||
else return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,511 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/*****************************************************************************
|
||||
The init_ardupilot function processes everything we need for an in - air restart
|
||||
We will determine later if we are actually on the ground and process a
|
||||
ground start in that case.
|
||||
|
||||
*****************************************************************************/
|
||||
|
||||
// Functions called from the top-level menu
|
||||
extern int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde
|
||||
extern int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde
|
||||
extern int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp
|
||||
|
||||
// This is the help function
|
||||
// PSTR is an AVR macro to read strings from flash memory
|
||||
// printf_P is a version of print_f that reads from flash memory
|
||||
static int8_t main_menu_help(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
Serial.printf_P(PSTR("Commands:\n"
|
||||
" logs log readback/setup mode\n"
|
||||
" setup setup mode\n"
|
||||
" test test mode\n"
|
||||
"\n"
|
||||
"Move the slide switch and reset to FLY.\n"
|
||||
"\n"));
|
||||
return(0);
|
||||
}
|
||||
|
||||
// Command/function table for the top-level menu.
|
||||
const struct Menu::command main_menu_commands[] PROGMEM = {
|
||||
// command function called
|
||||
// ======= ===============
|
||||
{"logs", process_logs},
|
||||
{"setup", setup_mode},
|
||||
{"test", test_mode},
|
||||
{"help", main_menu_help}
|
||||
};
|
||||
|
||||
// Create the top-level menu object.
|
||||
MENU(main_menu, "ArduPilotMega", main_menu_commands);
|
||||
|
||||
void init_ardupilot()
|
||||
{
|
||||
|
||||
byte last_log_num;
|
||||
int last_log_start;
|
||||
int last_log_end;
|
||||
|
||||
// Console serial port
|
||||
//
|
||||
// The console port buffers are defined to be sufficiently large to support
|
||||
// the console's use as a logging device, optionally as the GPS port when
|
||||
// GPS_PROTOCOL_IMU is selected, and as the telemetry port.
|
||||
//
|
||||
// XXX This could be optimised to reduce the buffer sizes in the cases
|
||||
// where they are not otherwise required.
|
||||
//
|
||||
Serial.begin(SERIAL0_BAUD, 128, 128);
|
||||
|
||||
// GPS serial port.
|
||||
//
|
||||
// Not used if the IMU/X-Plane GPS is in use.
|
||||
//
|
||||
// XXX currently the EM406 (SiRF receiver) is nominally configured
|
||||
// at 57600, however it's not been supported to date. We should
|
||||
// probably standardise on 38400.
|
||||
//
|
||||
// XXX the 128 byte receive buffer may be too small for NMEA, depending
|
||||
// on the message set configured.
|
||||
//
|
||||
#if HIL_MODE != HIL_MODE_DISABLED && HIL_PORT == 1 // TODO: figure out a better way to do this
|
||||
// Steal gps port for hardware in the loop
|
||||
Serial1.begin(115200, 128, 128);
|
||||
#else
|
||||
// standard gps running
|
||||
Serial1.begin(38400, 128, 16);
|
||||
#endif
|
||||
|
||||
// Telemetry port.
|
||||
//
|
||||
// Not used if telemetry is going to the console.
|
||||
//
|
||||
// XXX for unidirectional protocols, we could (should) minimize
|
||||
// the receive buffer, and the transmit buffer could also be
|
||||
// shrunk for protocols that don't send large messages.
|
||||
//
|
||||
Serial3.begin(SERIAL3_BAUD, 128, 128);
|
||||
|
||||
Serial.printf_P(PSTR("\n\n"
|
||||
"Init ArduPilotMega (unstable development version)\n\n"
|
||||
"Firmware Version: %d freeRAM: %lu\n"),
|
||||
FIRMWARE_VERSION, freeRAM());
|
||||
|
||||
// !!! Check firmware version before loading any
|
||||
// data from EEPROM !!!
|
||||
if (FIRMWARE_VERSION != get(PARAM_FIRMWARE_VER))
|
||||
{
|
||||
Serial.printf_P(PSTR("\n\n"
|
||||
"Firmware Mismatch! ROM Firmware Version: %d\n"
|
||||
"\nA factory reset is being performed."),get(PARAM_FIRMWARE_VER));
|
||||
|
||||
// If firmware mismatches a factory reset is forced
|
||||
param_reset_defaults();
|
||||
}
|
||||
|
||||
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
//read_EEPROM_startup(); // Read critical config information to start
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
adc.Init(); // APM ADC library initialization
|
||||
pitot.Init(); // APM Abs Pressure sensor initialization
|
||||
compass.init(); // I2C initialization
|
||||
#endif
|
||||
DataFlash.Init(); // DataFlash log initialization
|
||||
gps.init(); // GPS Initialization
|
||||
|
||||
// init the GCS
|
||||
#if GCS_PORT == 3
|
||||
gcs.init(&Serial3);
|
||||
#else
|
||||
gcs.init(&Serial);
|
||||
#endif
|
||||
|
||||
// init the HIL
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
#if HIL_PORT == 3
|
||||
hil.init(&Serial3);
|
||||
#elif HIL_PORT == 1
|
||||
hil.init(&Serial1);
|
||||
#else
|
||||
hil.init(&Serial);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
APM_RC.OutputCh(CH_ROLL, radio_trim(CH_ROLL)); // Initialization of servo outputs
|
||||
APM_RC.OutputCh(CH_PITCH, radio_trim(CH_PITCH));
|
||||
APM_RC.OutputCh(CH_THROTTLE, radio_trim(CH_THROTTLE));
|
||||
APM_RC.OutputCh(CH_RUDDER, radio_trim(CH_RUDDER));
|
||||
|
||||
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(A_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
|
||||
pinMode(PUSHBUTTON_PIN, INPUT); // unused
|
||||
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
|
||||
|
||||
// If the switch is in 'menu' mode, run the main menu.
|
||||
//
|
||||
// Since we can't be sure that the setup or test mode won't leave
|
||||
// the system in an odd state, we don't let the user exit the top
|
||||
// menu; they must reset in order to fly.
|
||||
//
|
||||
if (digitalRead(SLIDE_SWITCH_PIN) == 0) {
|
||||
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
|
||||
Serial.printf_P(PSTR("\n"
|
||||
"Entering interactive setup mode...\n"
|
||||
"\n"
|
||||
"If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n"
|
||||
"Type 'help' to list commands, 'exit' to leave a submenu.\n"
|
||||
"Visit the 'setup' menu for first-time configuration.\n"));
|
||||
for (;;) {
|
||||
Serial.printf_P(PSTR("\n"
|
||||
"Move the slide switch and reset to FLY.\n"
|
||||
"\n"));
|
||||
main_menu.run();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if(get(PARAM_LOG_BITMASK) > 0){
|
||||
// Here we will check on the length of the last log
|
||||
// We don't want to create a bunch of little logs due to powering on and off
|
||||
// XXX: TODO implement for new struct
|
||||
//last_log_num = eeprom_read_byte((uint8_t *) EE_LAST_LOG_NUM);
|
||||
//last_log_start = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(last_log_num - 1) * 0x02));
|
||||
//last_log_end = eeprom_read_word((uint16_t *) EE_LAST_LOG_PAGE);
|
||||
|
||||
if(last_log_num == 0) {
|
||||
// The log space is empty. Start a write session on page 1
|
||||
DataFlash.StartWrite(1);
|
||||
eeprom_write_byte((uint8_t *) EE_LAST_LOG_NUM, (1));
|
||||
eeprom_write_word((uint16_t *) EE_LOG_1_START, (1));
|
||||
|
||||
} else if (last_log_end <= last_log_start + 10) {
|
||||
// The last log is small. We consider it junk. Overwrite it.
|
||||
DataFlash.StartWrite(last_log_start);
|
||||
|
||||
} else {
|
||||
// The last log is valid. Start a new log
|
||||
if(last_log_num >= 19) {
|
||||
Serial.println("Number of log files exceeds max. Log 19 will be overwritten.");
|
||||
last_log_num --;
|
||||
}
|
||||
DataFlash.StartWrite(last_log_end + 1);
|
||||
eeprom_write_byte((uint8_t *) EE_LAST_LOG_NUM, (last_log_num + 1));
|
||||
eeprom_write_word((uint16_t *) (EE_LOG_1_START+(last_log_num)*0x02), (last_log_end + 1));
|
||||
}
|
||||
}
|
||||
|
||||
// read in the flight switches
|
||||
update_servo_switches();
|
||||
|
||||
if(DEBUG_SUBSYSTEM > 0){
|
||||
debug_subsystem();
|
||||
|
||||
} else if (ENABLE_AIR_START == 1) {
|
||||
// Perform an air start and get back to flying
|
||||
gcs.send_text(SEVERITY_LOW,"<init_ardupilot> AIR START");
|
||||
|
||||
// Get necessary data from EEPROM
|
||||
//----------------
|
||||
//read_EEPROM_airstart_critical();
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
imu.load_gyro_eeprom();
|
||||
imu.load_accel_eeprom();
|
||||
#endif
|
||||
|
||||
// This delay is important for the APM_RC library to work.
|
||||
// We need some time for the comm between the 328 and 1280 to be established.
|
||||
int old_pulse = 0;
|
||||
while (millis()<=1000 && (abs(old_pulse - APM_RC.InputCh(get(PARAM_FLIGHT_MODE_CH))) > 5 ||
|
||||
APM_RC.InputCh(get(PARAM_FLIGHT_MODE_CH)) == 1000 ||
|
||||
APM_RC.InputCh(get(PARAM_FLIGHT_MODE_CH)) == 1200)) {
|
||||
old_pulse = APM_RC.InputCh(get(PARAM_FLIGHT_MODE_CH));
|
||||
delay(25);
|
||||
}
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_CMD)
|
||||
Log_Write_Startup(TYPE_AIRSTART_MSG);
|
||||
reload_commands(); // Get set to resume AUTO from where we left off
|
||||
|
||||
}else {
|
||||
startup_ground();
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_CMD)
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
}
|
||||
|
||||
// set the correct flight mode
|
||||
// ---------------------------
|
||||
reset_control_switch();
|
||||
}
|
||||
|
||||
//********************************************************************************
|
||||
//This function does all the calibrations, etc. that we need during a ground start
|
||||
//********************************************************************************
|
||||
void startup_ground(void)
|
||||
{
|
||||
gcs.send_text(SEVERITY_LOW,"<startup_ground> GROUND START");
|
||||
|
||||
#if(GROUND_START_DELAY > 0)
|
||||
gcs.send_text(SEVERITY_LOW,"<startup_ground> With Delay");
|
||||
delay(GROUND_START_DELAY * 1000);
|
||||
#endif
|
||||
|
||||
// Output waypoints for confirmation
|
||||
// --------------------------------
|
||||
for(int i = 1; i < get(PARAM_WP_TOTAL) + 1; i++) {
|
||||
gcs.send_message(MSG_COMMAND_LIST, i);
|
||||
}
|
||||
|
||||
// Makes the servos wiggle
|
||||
// step 1 = 1 wiggle
|
||||
// -----------------------
|
||||
demo_servos(1);
|
||||
|
||||
//IMU ground start
|
||||
//------------------------
|
||||
//
|
||||
startup_IMU_ground();
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
trim_radio();
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
# if AIRSPEED_SENSOR == ENABLED
|
||||
// initialize airspeed sensor
|
||||
// --------------------------
|
||||
zero_airspeed();
|
||||
gcs.send_text(SEVERITY_LOW,"<startup_ground> zero airspeed calibrated");
|
||||
# else
|
||||
gcs.send_text(SEVERITY_LOW,"<startup_ground> NO airspeed");
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// Save the settings for in-air restart
|
||||
// ------------------------------------
|
||||
//save_EEPROM_groundstart();
|
||||
|
||||
// initialize commands
|
||||
// -------------------
|
||||
init_commands();
|
||||
|
||||
// Makes the servos wiggle - 3 times signals ready to fly
|
||||
// -----------------------
|
||||
demo_servos(3);
|
||||
|
||||
gcs.send_text(SEVERITY_LOW,"\n\n Ready to FLY.");
|
||||
}
|
||||
|
||||
void set_mode(byte mode)
|
||||
{
|
||||
if(control_mode == mode){
|
||||
// don't switch modes if we are already in the correct mode.
|
||||
return;
|
||||
}
|
||||
if(get(PARAM_TRIM_AUTO) > 0 || control_mode == MANUAL)
|
||||
trim_control_surfaces();
|
||||
|
||||
control_mode = mode;
|
||||
crash_timer = 0;
|
||||
|
||||
switch(control_mode)
|
||||
{
|
||||
case MANUAL:
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_A:
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_B:
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
update_auto();
|
||||
break;
|
||||
|
||||
case RTL:
|
||||
return_to_launch();
|
||||
break;
|
||||
|
||||
case LOITER:
|
||||
loiter_at_location();
|
||||
break;
|
||||
|
||||
case TAKEOFF:
|
||||
break;
|
||||
|
||||
case LAND:
|
||||
break;
|
||||
|
||||
default:
|
||||
return_to_launch();
|
||||
break;
|
||||
}
|
||||
|
||||
// output control mode to the ground station
|
||||
gcs.send_message(MSG_MODE_CHANGE);
|
||||
|
||||
if (get(PARAM_LOG_BITMASK) & MASK_LOG_MODE)
|
||||
Log_Write_Mode(control_mode);
|
||||
}
|
||||
|
||||
void set_failsafe(boolean mode)
|
||||
{
|
||||
// only act on changes
|
||||
// -------------------
|
||||
if(failsafe != mode){
|
||||
|
||||
// store the value so we don't trip the gate twice
|
||||
// -----------------------------------------------
|
||||
failsafe = mode;
|
||||
|
||||
if (failsafe == false){
|
||||
// We're back in radio contact
|
||||
// ---------------------------
|
||||
|
||||
// re-read the switch so we can return to our preferred mode
|
||||
reset_control_switch();
|
||||
|
||||
// Reset control integrators
|
||||
// ---------------------
|
||||
reset_I();
|
||||
|
||||
}else{
|
||||
// We've lost radio contact
|
||||
// ------------------------
|
||||
// nothing to do right now
|
||||
}
|
||||
|
||||
// Let the user know what's up so they can override the behavior
|
||||
// -------------------------------------------------------------
|
||||
failsafe_event();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void startup_IMU_ground(void)
|
||||
{
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
uint16_t store = 0;
|
||||
int flashcount = 0;
|
||||
SendDebugln("<startup_IMU_ground> Warming up ADC...");
|
||||
delay(500);
|
||||
|
||||
// Makes the servos wiggle twice - about to begin IMU calibration - HOLD LEVEL AND STILL!!
|
||||
// -----------------------
|
||||
demo_servos(2);
|
||||
SendDebugln("<startup_IMU_ground> Beginning IMU calibration; do not move plane");
|
||||
delay(1000);
|
||||
|
||||
imu.init_accel();
|
||||
imu.init_gyro();
|
||||
|
||||
# if HIL_MODE == HIL_MODE_SENSORS
|
||||
hil.update(); // look for inbound hil packets for initialization
|
||||
# endif
|
||||
|
||||
pitot.Read(); // Get initial data from absolute pressure sensor
|
||||
abs_press_gnd = pitot.Press;
|
||||
ground_temperature = pitot.Temp;
|
||||
delay(20);
|
||||
// ***********
|
||||
|
||||
for(int i = 0; i < 200; i++){ // We take some readings...
|
||||
|
||||
# if HIL_MODE == HIL_MODE_SENSORS
|
||||
hil.update(); // look for inbound hil packets
|
||||
# endif
|
||||
|
||||
pitot.Read(); // Get initial data from absolute pressure sensor
|
||||
abs_press_gnd = (abs_press_gnd * 9l + pitot.Press) / 10l;
|
||||
ground_temperature = (ground_temperature * 9 + pitot.Temp) / 10;
|
||||
|
||||
delay(20);
|
||||
if(flashcount == 5) {
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
digitalWrite(A_LED_PIN, HIGH);
|
||||
digitalWrite(B_LED_PIN, LOW);
|
||||
}
|
||||
if(flashcount >= 10) {
|
||||
flashcount = 0;
|
||||
digitalWrite(C_LED_PIN, HIGH);
|
||||
digitalWrite(A_LED_PIN, LOW);
|
||||
digitalWrite(B_LED_PIN, HIGH);
|
||||
}
|
||||
flashcount++;
|
||||
|
||||
}
|
||||
SendDebugln(" <startup_IMU_ground> Calibration complete.");
|
||||
#endif // HIL_MODE_ATTITUDE
|
||||
|
||||
digitalWrite(B_LED_PIN, HIGH); // Set LED B high to indicate IMU ready
|
||||
digitalWrite(A_LED_PIN, LOW);
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
}
|
||||
|
||||
|
||||
void update_GPS_light(void)
|
||||
{
|
||||
// GPS LED on if we have a fix or Blink GPS LED if we are receiving data
|
||||
// ---------------------------------------------------------------------
|
||||
switch (gps.status()) {
|
||||
case(2):
|
||||
digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix.
|
||||
break;
|
||||
|
||||
case(1):
|
||||
if (gps.valid_read == true){
|
||||
GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock
|
||||
if (GPS_light){
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
} else {
|
||||
digitalWrite(C_LED_PIN, HIGH);
|
||||
}
|
||||
gps.valid_read = false;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void resetPerfData(void) {
|
||||
mainLoop_count = 0;
|
||||
G_Dt_max = 0;
|
||||
gyro_sat_count = 0;
|
||||
adc_constraints = 0;
|
||||
renorm_sqrt_count = 0;
|
||||
renorm_blowup_count = 0;
|
||||
gps_fix_count = 0;
|
||||
perf_mon_timer = millis();
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* This function gets the current value of the heap and stack pointers.
|
||||
* The stack pointer starts at the top of RAM and grows downwards. The heap pointer
|
||||
* starts just above the static variables etc. and grows upwards. SP should always
|
||||
* be larger than HP or you'll be in big trouble! The smaller the gap, the more
|
||||
* careful you need to be. Julian Gall 6 - Feb - 2009.
|
||||
*/
|
||||
unsigned long freeRAM() {
|
||||
uint8_t * heapptr, * stackptr;
|
||||
stackptr = (uint8_t *)malloc(4); // use stackptr temporarily
|
||||
heapptr = stackptr; // save value of heap pointer
|
||||
free(stackptr); // free up the memory again (sets stackptr to 0)
|
||||
stackptr = (uint8_t *)(SP); // save value of stack pointer
|
||||
return stackptr - heapptr;
|
||||
}
|
||||
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,519 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
// These are function definitions so the Menu can be constructed before the functions
|
||||
// are defined below. Order matters to the compiler.
|
||||
static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_gyro(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_wp(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_airspeed(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_pressure(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_mag(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_dipswitches(uint8_t argc, const Menu::arg *argv);
|
||||
|
||||
// Creates a constant array of structs representing menu options
|
||||
// and stores them in Flash memory, not RAM.
|
||||
// User enters the string in the console to call the functions on the right.
|
||||
// See class Menu in AP_Common for implementation details
|
||||
const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||
{"radio", test_radio},
|
||||
{"battery", test_battery},
|
||||
{"relay", test_relay},
|
||||
{"waypoints", test_wp},
|
||||
{"xbee", test_xbee},
|
||||
{"eedump", test_eedump},
|
||||
{"modeswitch", test_modeswitch},
|
||||
{"dipswitches", test_dipswitches},
|
||||
|
||||
// Tests below here are for hardware sensors only present
|
||||
// when real sensors are attached or they are emulated
|
||||
#if HIL_MODE == HIL_MODE_DISABLED
|
||||
{"adc", test_adc},
|
||||
{"gps", test_gps},
|
||||
{"rawgps", test_rawgps},
|
||||
{"imu", test_imu},
|
||||
{"gyro", test_gyro},
|
||||
{"airspeed", test_airspeed},
|
||||
{"airpressure", test_pressure},
|
||||
{"compass", test_mag},
|
||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||
{"adc", test_adc},
|
||||
{"gps", test_gps},
|
||||
{"imu", test_imu},
|
||||
{"gyro", test_gyro},
|
||||
{"compass", test_mag},
|
||||
#elif HIL_MODE == HIL_MODE_ATTITUDE
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
// A Macro to create the Menu
|
||||
MENU(test_menu, "test", test_menu_commands);
|
||||
|
||||
int8_t
|
||||
test_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
Serial.printf_P(PSTR("Test Mode\n\n"));
|
||||
test_menu.run();
|
||||
}
|
||||
|
||||
void print_hit_enter()
|
||||
{
|
||||
Serial.printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_eedump(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
int i, j;
|
||||
|
||||
// hexdump the EEPROM
|
||||
for (i = 0; i < EEPROM_MAX_ADDR; i += 16) {
|
||||
Serial.printf_P(PSTR("%04x:"), i);
|
||||
for (j = 0; j < 16; j++)
|
||||
Serial.printf_P(PSTR(" %02x"), eeprom_read_byte((const uint8_t *)(i + j)));
|
||||
Serial.println();
|
||||
}
|
||||
return(0);
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
#if THROTTLE_REVERSE == 1
|
||||
Serial.println("Throttle is reversed in config: ");
|
||||
delay(1000);
|
||||
#endif
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
trim_radio();
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
update_servo_switches();
|
||||
|
||||
servo_out[CH_ROLL] = reverse_roll * int(radio_in[CH_ROLL] - radio_trim(CH_ROLL)) * 9;
|
||||
servo_out[CH_PITCH] = reverse_pitch * int(radio_in[CH_PITCH] - radio_trim(CH_PITCH)) * 9;
|
||||
servo_out[CH_RUDDER] = reverse_rudder * int(radio_in[CH_RUDDER] - radio_trim(CH_RUDDER)) * 9;
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
|
||||
|
||||
for(int y = 4; y < 8; y++) {
|
||||
radio_out[y] = constrain(radio_in[y], radio_min(y), radio_max(y));
|
||||
APM_RC.OutputCh(y, radio_out[y]); // send to Servos
|
||||
}
|
||||
Serial.printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\t"), radio_in[CH_1], radio_in[CH_2], radio_in[CH_3], radio_in[CH_4], radio_in[CH_5], radio_in[CH_6], radio_in[CH_7], radio_in[CH_8]);
|
||||
Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d\n"), (servo_out[CH_ROLL]/100), (servo_out[CH_PITCH]/100), servo_out[CH_THROTTLE], (servo_out[CH_RUDDER]/100));
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static int8_t
|
||||
test_battery(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#if BATTERY_EVENT == 1
|
||||
for (int i = 0; i < 20; i++){
|
||||
delay(20);
|
||||
read_battery();
|
||||
}
|
||||
Serial.printf_P(PSTR("Volts: 1:"));
|
||||
Serial.print(battery_voltage1, 4);
|
||||
Serial.print(" 2:");
|
||||
Serial.print(battery_voltage2, 4);
|
||||
Serial.print(" 3:");
|
||||
Serial.print(battery_voltage3, 4);
|
||||
Serial.print(" 4:");
|
||||
Serial.println(battery_voltage4, 4);
|
||||
#else
|
||||
Serial.printf_P(PSTR("Not enabled\n"));
|
||||
|
||||
#endif
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
static int8_t
|
||||
test_relay(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
Serial.println("Relay on");
|
||||
relay_on();
|
||||
delay(3000);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
|
||||
Serial.println("Relay off");
|
||||
relay_off();
|
||||
delay(3000);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
test_wp_print(struct Location *cmd, byte index)
|
||||
{
|
||||
Serial.print("command #: ");
|
||||
Serial.print(index, DEC);
|
||||
Serial.print(" id: ");
|
||||
Serial.print(cmd->id, DEC);
|
||||
Serial.print(" p1: ");
|
||||
Serial.print(cmd->p1, DEC);
|
||||
Serial.print(" p2: ");
|
||||
Serial.print(cmd->alt, DEC);
|
||||
Serial.print(" p3: ");
|
||||
Serial.print(cmd->lat, DEC);
|
||||
Serial.print(" p4: ");
|
||||
Serial.println(cmd->lng, DEC);
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_wp(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
delay(1000);
|
||||
ground_alt = 0;
|
||||
//read_EEPROM_waypoint_info();
|
||||
|
||||
// save the alitude above home option
|
||||
if(get(PARAM_CONFIG) & HOLD_ALT_ABOVE_HOME){
|
||||
Serial.printf_P(PSTR("Hold altitude of %ldm\n"), get(PARAM_ALT_HOLD_HOME)/100);
|
||||
}else{
|
||||
Serial.printf_P(PSTR("Hold current altitude\n"));
|
||||
}
|
||||
|
||||
Serial.printf_P(PSTR("%d waypoints\n"), get(PARAM_WP_TOTAL));
|
||||
Serial.printf_P(PSTR("Hit radius: %d\n"), get(PARAM_WP_RADIUS));
|
||||
Serial.printf_P(PSTR("Loiter radius: %d\n\n"), get(PARAM_LOITER_RADIUS));
|
||||
|
||||
for(byte i = 0; i <= get(PARAM_WP_TOTAL); i++){
|
||||
struct Location temp = get_wp_with_index(i);
|
||||
test_wp_print(&temp, i);
|
||||
}
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_xbee(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
Serial.printf_P(PSTR("Begin XBee X-CTU Range and RSSI Test:\n"));
|
||||
while(1){
|
||||
delay(250);
|
||||
// Timeout set high enough for X-CTU RSSI Calc over XBee @ 115200
|
||||
Serial3.printf_P(PSTR("0123456789:;<=>?@ABCDEFGHIJKLMNO\n"));
|
||||
//Serial.print("X");
|
||||
// Default 32bit data from X-CTU Range Test
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
Serial.print("Control CH ");
|
||||
Serial.println(FLIGHT_MODE_CHANNEL, DEC);
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
byte switchPosition = readSwitch();
|
||||
if (oldSwitchPosition != switchPosition){
|
||||
Serial.printf_P(PSTR("Position %d\n"), switchPosition);
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_dipswitches(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
update_servo_switches();
|
||||
if (mix_mode == 0) {
|
||||
Serial.print("Mix:standard ");
|
||||
Serial.print("\t reverse_roll: ");
|
||||
Serial.print(reverse_roll, DEC);
|
||||
Serial.print("\t reverse_pitch: ");
|
||||
Serial.print(reverse_pitch, DEC);
|
||||
Serial.print("\t reverse_rudder: ");
|
||||
Serial.println(reverse_rudder, DEC);
|
||||
} else {
|
||||
Serial.print("Mix:elevons ");
|
||||
Serial.print("\t reverse_elevons: ");
|
||||
Serial.print(reverse_elevons, DEC);
|
||||
Serial.print("\t reverse_ch1_elevon: ");
|
||||
Serial.print(reverse_ch1_elevon, DEC);
|
||||
Serial.print("\t reverse_ch2_elevon: ");
|
||||
Serial.println(reverse_ch2_elevon, DEC);
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// tests in this section are for real sensors or sensors that have been simulated
|
||||
|
||||
#if HIL_MODE == HIL_MODE_DISABLED || HIL_MODE == HIL_MODE_SENSORS
|
||||
static int8_t
|
||||
test_adc(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
adc.Init();
|
||||
delay(1000);
|
||||
Serial.printf_P(PSTR("ADC\n"));
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
for (int i=0;i<9;i++) Serial.printf_P(PSTR("%d\t"),adc.Ch(i));
|
||||
Serial.println();
|
||||
delay(100);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_gps(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
delay(333);
|
||||
|
||||
// Blink GPS LED if we don't have a fix
|
||||
// ------------------------------------
|
||||
update_GPS_light();
|
||||
|
||||
gps.update();
|
||||
|
||||
if (gps.new_data){
|
||||
Serial.print("Lat:");
|
||||
Serial.print((float)gps.latitude/10000000, 10);
|
||||
Serial.print(" Lon:");
|
||||
Serial.print((float)gps.longitude/10000000, 10);
|
||||
Serial.printf_P(PSTR("alt %ldm, #sats: %d\n"), gps.altitude/100, gps.num_sats);
|
||||
}else{
|
||||
Serial.print(".");
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
//Serial.printf_P(PSTR("Calibrating."));
|
||||
|
||||
imu.init_gyro();
|
||||
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
if (millis() - fast_loopTimer > 19) {
|
||||
deltaMiliSeconds = millis() - fast_loopTimer;
|
||||
G_Dt = (float)deltaMiliSeconds / 1000.f; // used by DCM integrator
|
||||
fast_loopTimer = millis();
|
||||
|
||||
// IMU
|
||||
// ---
|
||||
dcm.update_DCM(G_Dt);
|
||||
|
||||
#if MAGNETOMETER == 1
|
||||
medium_loopCounter++;
|
||||
if(medium_loopCounter == 5){
|
||||
compass.read(); // Read magnetometer
|
||||
compass.calculate(dcm.roll, dcm.pitch); // Calculate heading
|
||||
medium_loopCounter = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
// We are using the IMU
|
||||
// ---------------------
|
||||
Serial.printf_P(PSTR("r: %d\tp: %d\t y: %d\n"), ((int)dcm.roll_sensor/100), ((int)dcm.pitch_sensor/100), ((uint16_t)dcm.yaw_sensor/100));
|
||||
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static int8_t
|
||||
test_gyro(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
adc.Init();
|
||||
delay(1000);
|
||||
Serial.printf_P(PSTR("Gyro | Accel\n"));
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
Vector3f gyros = imu.get_gyro();
|
||||
Vector3f accels = imu.get_accel();
|
||||
Serial.printf_P(PSTR("%d\t%d\t%d\t|\t%d\t%d\t%d\n"), (int)gyros.x, (int)gyros.y, (int)gyros.z, (int)accels.x, (int)accels.y, (int)accels.z);
|
||||
delay(100);
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#if MAGNETOMETER == DISABLED
|
||||
Serial.printf_P(PSTR("Compass disabled\n"));
|
||||
return (0);
|
||||
#else
|
||||
print_hit_enter();
|
||||
|
||||
while(1){
|
||||
delay(250);
|
||||
compass.read();
|
||||
compass.calculate(0,0);
|
||||
Serial.printf_P(PSTR("Heading: ("));
|
||||
Serial.print(ToDeg(compass.heading));
|
||||
Serial.printf_P(PSTR(") XYZ: ("));
|
||||
Serial.print(compass.mag_x);
|
||||
Serial.print(comma);
|
||||
Serial.print(compass.mag_y);
|
||||
Serial.print(comma);
|
||||
Serial.print(compass.mag_z);
|
||||
Serial.println(")");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HIL_MODE == HIL_MODE_DISABLED || HIL_MODE == HIL_MODE_SENSORS
|
||||
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// real sensors that have not been simulated yet go here
|
||||
|
||||
#if HIL_MODE == HIL_MODE_DISABLED
|
||||
|
||||
static int8_t
|
||||
test_airspeed(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#if AIRSPEED_SENSOR == DISABLED
|
||||
Serial.printf_P(PSTR("airspeed disabled\n"));
|
||||
return (0);
|
||||
#else
|
||||
print_hit_enter();
|
||||
zero_airspeed();
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
read_airspeed();
|
||||
Serial.printf_P(PSTR("%dm/s\n"),airspeed/100);
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_pressure(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
uint32_t sum = 0;
|
||||
Serial.printf_P(PSTR("Uncalibrated Abs Airpressure\n"));
|
||||
Serial.printf_P(PSTR("Note - the altitude displayed is relative to the start of this test\n"));
|
||||
print_hit_enter();
|
||||
Serial.printf_P(PSTR("\nCalibrating....\n"));
|
||||
for (int i=1;i<301;i++) {
|
||||
read_airpressure();
|
||||
if(i>200)sum += abs_press_filt;
|
||||
delay(10);
|
||||
}
|
||||
abs_press_gnd = (double)sum/100.0;
|
||||
|
||||
ground_alt = 0;
|
||||
while(1){
|
||||
delay(100);
|
||||
read_airpressure();
|
||||
//Serial.printf_P(PSTR("Alt: %dm, Raw: %d\n"), press_alt / 100, abs_press_filt); // Someone needs to fix the formatting here for long integers
|
||||
Serial.print("Altitude: ");
|
||||
Serial.print(press_alt/100.0,2);
|
||||
Serial.print(" Raw pressure value: ");
|
||||
Serial.println(abs_press_filt);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_rawgps(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
if(Serial1.available() > 0) // Ok, let me see, the buffer is empty?
|
||||
{
|
||||
delay(60); // wait for it all
|
||||
while(Serial1.available() > 0){
|
||||
byte incoming = Serial1.read();
|
||||
//Serial.print(incoming,DEC);
|
||||
Serial.print(incoming, BYTE); // will output Hex values
|
||||
//Serial.print(",");
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // HIL_MODE == HIL_MODE_DISABLED
|
|
@ -0,0 +1,5 @@
|
|||
#!/bin/bash
|
||||
echo Updating Parameters ...
|
||||
awk -f paramgen.awk paramgen.in
|
||||
echo Finished.
|
||||
echo Did you increment firmware version?
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,120 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
|
@ -0,0 +1,20 @@
|
|||
|
||||
Microsoft Visual Studio Solution File, Format Version 11.00
|
||||
# Visual C++ Express 2010
|
||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "APMPlannerXplanes", "APMPlannerXplanes\APMPlannerXplanes.vcxproj", "{1600B320-E488-486B-9790-480D4C858B0E}"
|
||||
EndProject
|
||||
Global
|
||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||
Debug|Win32 = Debug|Win32
|
||||
Release|Win32 = Release|Win32
|
||||
EndGlobalSection
|
||||
GlobalSection(ProjectConfigurationPlatforms) = postSolution
|
||||
{1600B320-E488-486B-9790-480D4C858B0E}.Debug|Win32.ActiveCfg = Debug|Win32
|
||||
{1600B320-E488-486B-9790-480D4C858B0E}.Debug|Win32.Build.0 = Debug|Win32
|
||||
{1600B320-E488-486B-9790-480D4C858B0E}.Release|Win32.ActiveCfg = Release|Win32
|
||||
{1600B320-E488-486B-9790-480D4C858B0E}.Release|Win32.Build.0 = Release|Win32
|
||||
EndGlobalSection
|
||||
GlobalSection(SolutionProperties) = preSolution
|
||||
HideSolutionNode = FALSE
|
||||
EndGlobalSection
|
||||
EndGlobal
|
Binary file not shown.
|
@ -0,0 +1,262 @@
|
|||
#include <string.h>
|
||||
#include <math.h>
|
||||
#include "XPLMDisplay.h"
|
||||
#include "XPLMGraphics.h"
|
||||
#include "XPLMCamera.h"
|
||||
#include "XPLMPlanes.h"
|
||||
#include "XPLMUtilities.h"
|
||||
#include "XPLMDataAccess.h"
|
||||
#if LIN
|
||||
#include <GL/gl.h>
|
||||
#else
|
||||
#if __GNUC__
|
||||
#include <OpenGL/gl.h>
|
||||
#else
|
||||
#include <windows.h>
|
||||
#include <..\..\..\..\..\..\..\program files (x86)\microsoft sdks\windows\v7.0a\include\gl\gl.h>
|
||||
#endif
|
||||
#endif
|
||||
#include "AircraftUtils.h"
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
using namespace System;
|
||||
using namespace System::Net;
|
||||
using namespace System::Net::Sockets;
|
||||
|
||||
public ref class Globals abstract sealed {
|
||||
public:
|
||||
static IPEndPoint^ RemoteIpEndPoint = gcnew IPEndPoint( IPAddress::Any, 4900 );
|
||||
static Socket^ XplanesSEND = gcnew Socket(AddressFamily::InterNetwork,
|
||||
SocketType::Dgram, ProtocolType::Udp);
|
||||
};
|
||||
|
||||
XPLMDataRef gPlaneX = NULL;
|
||||
XPLMDataRef gPlaneY = NULL;
|
||||
XPLMDataRef gPlaneZ = NULL;
|
||||
XPLMDataRef gPlaneTheta = NULL;
|
||||
XPLMDataRef gPlanePhi = NULL;
|
||||
XPLMDataRef gPlanePsi = NULL;
|
||||
XPLMDataRef gOverRidePlanePosition = NULL;
|
||||
XPLMDataRef gAGL = NULL;
|
||||
XPLMDataRef gLatRef = NULL;
|
||||
XPLMDataRef gLongRef = NULL;
|
||||
|
||||
float fTextColour[3];
|
||||
char szString[100];
|
||||
|
||||
const double kMaxPlaneDistance = 5280.0 / 3.2 * 10.0;
|
||||
const double kFullPlaneDist = 5280.0 / 3.2 * 3.0;
|
||||
|
||||
static inline float sqr(float a) { return a * a; }
|
||||
|
||||
static inline float CalcDist3D(float x1, float y1, float z1, float x2, float y2, float z2)
|
||||
{
|
||||
return sqrt(sqr(x2-x1) + sqr(y2-y1) + sqr(z2-z1));
|
||||
}
|
||||
|
||||
const double kFtToMeters = 0.3048;
|
||||
|
||||
static XPLMDataRef gFOVDataRef = NULL;
|
||||
|
||||
int AircraftDrawCallback( XPLMDrawingPhase inPhase,
|
||||
int inIsBefore,
|
||||
void * inRefcon);
|
||||
|
||||
PLUGIN_API int XPluginStart( char * outName,
|
||||
char * outSig,
|
||||
char * outDesc)
|
||||
{
|
||||
int planeCount;
|
||||
XPLMCountAircraft(&planeCount, 0, 0);
|
||||
|
||||
fTextColour[0] = 1.0;
|
||||
fTextColour[1] = 1.0;
|
||||
fTextColour[2] = 1.0;
|
||||
|
||||
|
||||
strcpy(outName, "Quad Hil");
|
||||
strcpy(outSig, "based on xplanesdk.examples.drawaircraft");
|
||||
strcpy(outDesc, "A plugin that receives raw data to display");
|
||||
|
||||
/* Prefetch the sim variables we will use. */
|
||||
gPlaneX = XPLMFindDataRef("sim/flightmodel/position/local_x");
|
||||
gPlaneY = XPLMFindDataRef("sim/flightmodel/position/local_y");
|
||||
gPlaneZ = XPLMFindDataRef("sim/flightmodel/position/local_z");
|
||||
gPlaneTheta = XPLMFindDataRef("sim/flightmodel/position/theta");
|
||||
gPlanePhi = XPLMFindDataRef("sim/flightmodel/position/phi");
|
||||
gPlanePsi = XPLMFindDataRef("sim/flightmodel/position/psi");
|
||||
gOverRidePlanePosition = XPLMFindDataRef("sim/operation/override/override_planepath");
|
||||
gAGL = XPLMFindDataRef("sim/flightmodel/position/y_agl");
|
||||
gLatRef = XPLMFindDataRef("sim/flightmodel/position/lat_ref");
|
||||
gLongRef = XPLMFindDataRef("sim/flightmodel/position/lon_ref");
|
||||
|
||||
|
||||
/* Next register the drawing callback. We want to be drawn
|
||||
* after X-Plane draws its 3-d objects. */
|
||||
XPLMRegisterDrawCallback(
|
||||
AircraftDrawCallback,
|
||||
xplm_Phase_Window, /* Draw when sim is doing objects */
|
||||
0, /* After objects */
|
||||
NULL); /* No refcon needed */
|
||||
|
||||
Globals::XplanesSEND->Bind(Globals::RemoteIpEndPoint);
|
||||
/*
|
||||
char FileName[256], AircraftPath[256];
|
||||
|
||||
for (long index = 0; index < planeCount; ++index)
|
||||
{
|
||||
XPLMGetNthAircraftModel(index, FileName, AircraftPath);
|
||||
pAircraft[index] = (char *)AircraftPath;
|
||||
|
||||
if (XPLMAcquirePlanes((char **)&pAircraft, NULL, NULL))
|
||||
XPLMSetAircraftModel(index, AircraftPath);
|
||||
}
|
||||
*/
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
PLUGIN_API void XPluginStop(void)
|
||||
{
|
||||
}
|
||||
|
||||
PLUGIN_API void XPluginDisable(void)
|
||||
{
|
||||
int Enable[10];
|
||||
Enable[0] = 0;
|
||||
|
||||
XPLMSetDatavi(gOverRidePlanePosition,&Enable[0],0,1); // disable physics
|
||||
}
|
||||
|
||||
PLUGIN_API int XPluginEnable(void)
|
||||
{
|
||||
int Enable[10];
|
||||
Enable[0] = 1;
|
||||
|
||||
XPLMSetDatavi(gOverRidePlanePosition,&Enable[0],0,1); // disable physics
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
PLUGIN_API void XPluginReceiveMessage( XPLMPluginID inFromWho,
|
||||
long inMessage,
|
||||
void * inParam)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* AircraftDrawCallback
|
||||
*
|
||||
* This is the actual drawing callback that does the work; for us it will
|
||||
* be called after X-Plane has drawn its 3-d objects. The coordinate system
|
||||
* is 'normal' for 3-d drawing, meaning 0,0,0 is at the earth's surface at the
|
||||
* lat/lon reference point, with +Y = up, +Z = South, +X = East. (Note that
|
||||
* these relationships are only true at 0,0,0 due to the Earth's curvature!!)
|
||||
*
|
||||
* Drawing hooks that draw before X-Plane return 1 to let X-Plane draw or 0
|
||||
* to inhibit drawing. For drawing hooks that run after X-Plane, this return
|
||||
* value is ignored but we will return 1 anyway.
|
||||
*
|
||||
*/
|
||||
|
||||
public struct quad
|
||||
{
|
||||
double t1;
|
||||
double t2;
|
||||
double t3;
|
||||
double t4;
|
||||
|
||||
double lat;
|
||||
double lng;
|
||||
double alt;
|
||||
double altagl;
|
||||
|
||||
double roll;
|
||||
double pitch;
|
||||
double yaw;
|
||||
};
|
||||
|
||||
int AircraftDrawCallback( XPLMDrawingPhase inPhase,
|
||||
int inIsBefore,
|
||||
void * inRefcon)
|
||||
{
|
||||
if (Globals::XplanesSEND->Available > 0) {
|
||||
|
||||
array<Byte>^bytesReceived = gcnew array<Byte>(256);
|
||||
int bytes = 0;
|
||||
bytes = Globals::XplanesSEND->Receive( bytesReceived, bytesReceived->Length, static_cast<SocketFlags>(0) );
|
||||
|
||||
int count = 0;
|
||||
double t1 = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double t2 = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double t3 = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double t4 = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
|
||||
count++;
|
||||
double lat = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double lng = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double alt = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double altagl = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
|
||||
count++;
|
||||
double roll = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double pitch = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
count++;
|
||||
double yaw = BitConverter::ToDouble(bytesReceived, count * 8);
|
||||
|
||||
double X,Y,Z;
|
||||
|
||||
XPLMSetDataf(gLatRef,(float)lat);
|
||||
XPLMSetDataf(gLongRef,(float)lng);
|
||||
|
||||
|
||||
XPLMWorldToLocal(lat,lng,alt * kFtToMeters,&X,&Y,&Z);
|
||||
|
||||
XPLMSetDataf(gPlaneX, X);
|
||||
XPLMSetDataf(gPlaneY, Y);
|
||||
XPLMSetDataf(gPlaneZ, Z);
|
||||
|
||||
|
||||
XPLMSetDataf(gPlaneTheta, pitch);
|
||||
XPLMSetDataf(gPlanePhi, roll);
|
||||
XPLMSetDataf(gPlanePsi, yaw);
|
||||
|
||||
sprintf(szString,"m1: %f, m2: %f, m3: %f, m4: %f\0", t1,t2,t3,t4);
|
||||
XPLMDrawString(fTextColour,700,700,szString,NULL,xplmFont_Basic);
|
||||
|
||||
|
||||
return 1;
|
||||
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
double x,y,z,theta,phi,psi;
|
||||
|
||||
//double Lat = 34.09, Lon = -117.25, Alt = 1170;
|
||||
float Heading = 0, Pitch = 0, Roll = 0, Altitude;
|
||||
|
||||
x = XPLMGetDataf(gPlaneX);
|
||||
y = XPLMGetDataf(gPlaneY);
|
||||
z = XPLMGetDataf(gPlaneZ);
|
||||
theta = XPLMGetDataf(gPlaneTheta);
|
||||
phi = XPLMGetDataf(gPlanePhi);
|
||||
psi = XPLMGetDataf(gPlanePsi);
|
||||
Altitude = XPLMGetDataf(gAGL);
|
||||
|
||||
|
||||
XPLMSetDataf(gPlaneX, x + 1);
|
||||
|
||||
return 1;
|
||||
}
|
|
@ -0,0 +1,13 @@
|
|||
// APMPlannerXplanes.h
|
||||
|
||||
#pragma once
|
||||
|
||||
using namespace System;
|
||||
|
||||
namespace APMPlannerXplanes {
|
||||
|
||||
public ref class Class1
|
||||
{
|
||||
// TODO: Add your methods for this class here.
|
||||
};
|
||||
}
|
|
@ -0,0 +1,94 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project DefaultTargets="Build" ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<ItemGroup Label="ProjectConfigurations">
|
||||
<ProjectConfiguration Include="Debug|Win32">
|
||||
<Configuration>Debug</Configuration>
|
||||
<Platform>Win32</Platform>
|
||||
</ProjectConfiguration>
|
||||
<ProjectConfiguration Include="Release|Win32">
|
||||
<Configuration>Release</Configuration>
|
||||
<Platform>Win32</Platform>
|
||||
</ProjectConfiguration>
|
||||
</ItemGroup>
|
||||
<PropertyGroup Label="Globals">
|
||||
<ProjectGuid>{1600B320-E488-486B-9790-480D4C858B0E}</ProjectGuid>
|
||||
<TargetFrameworkVersion>v3.0</TargetFrameworkVersion>
|
||||
<Keyword>ManagedCProj</Keyword>
|
||||
<RootNamespace>APMPlannerXplanes</RootNamespace>
|
||||
</PropertyGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.Default.props" />
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'" Label="Configuration">
|
||||
<ConfigurationType>DynamicLibrary</ConfigurationType>
|
||||
<UseDebugLibraries>true</UseDebugLibraries>
|
||||
<CLRSupport>true</CLRSupport>
|
||||
<CharacterSet>Unicode</CharacterSet>
|
||||
<PlatformToolset>v100</PlatformToolset>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'" Label="Configuration">
|
||||
<ConfigurationType>DynamicLibrary</ConfigurationType>
|
||||
<UseDebugLibraries>false</UseDebugLibraries>
|
||||
<CLRSupport>true</CLRSupport>
|
||||
<CharacterSet>Unicode</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.props" />
|
||||
<ImportGroup Label="ExtensionSettings">
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<PropertyGroup Label="UserMacros" />
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<LinkIncremental>true</LinkIncremental>
|
||||
<TargetExt>.xpl</TargetExt>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<LinkIncremental>false</LinkIncremental>
|
||||
</PropertyGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<ClCompile>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>Disabled</Optimization>
|
||||
<PreprocessorDefinitions>WIN32;_DEBUG;%(PreprocessorDefinitions);APL</PreprocessorDefinitions>
|
||||
<PrecompiledHeader>NotUsing</PrecompiledHeader>
|
||||
<AdditionalIncludeDirectories>..\..\..\..\..\..\..\program files (x86)\microsoft sdks\windows\v7.0a\include\gl\;C:\Users\hog\Desktop\DIYDrones&avr\X-Plane 9 Demo\SDK\CHeaders\Wrappers;C:\Users\hog\Desktop\DIYDrones&avr\X-Plane 9 Demo\SDK\CHeaders\XPLM;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
|
||||
<DebugInformationFormat>ProgramDatabase</DebugInformationFormat>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<AdditionalDependencies>XPLM.lib;%(AdditionalDependencies)</AdditionalDependencies>
|
||||
<AdditionalLibraryDirectories>C:\Users\hog\Desktop\DIYDrones&avr\X-Plane 9 Demo\SDK\Libraries\Win;%(AdditionalLibraryDirectories)</AdditionalLibraryDirectories>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<ClCompile>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<PreprocessorDefinitions>WIN32;NDEBUG;%(PreprocessorDefinitions)</PreprocessorDefinitions>
|
||||
<PrecompiledHeader>Use</PrecompiledHeader>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<AdditionalDependencies>
|
||||
</AdditionalDependencies>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemGroup>
|
||||
<Reference Include="System" />
|
||||
<Reference Include="System.Data" />
|
||||
<Reference Include="System.Xml" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="AircraftUtils.cpp" />
|
||||
<ClCompile Include="APMPlannerXplanes.cpp" />
|
||||
<ClCompile Include="AssemblyInfo.cpp" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClInclude Include="..\..\..\..\..\..\..\program files (x86)\microsoft sdks\windows\v7.0a\include\gl\gl.h" />
|
||||
<ClInclude Include="AircraftUtils.h" />
|
||||
</ItemGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
|
||||
<ImportGroup Label="ExtensionTargets">
|
||||
</ImportGroup>
|
||||
</Project>
|
|
@ -0,0 +1,36 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<ItemGroup>
|
||||
<Filter Include="Source Files">
|
||||
<UniqueIdentifier>{4FC737F1-C7A5-4376-A066-2A32D752A2FF}</UniqueIdentifier>
|
||||
<Extensions>cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx</Extensions>
|
||||
</Filter>
|
||||
<Filter Include="Header Files">
|
||||
<UniqueIdentifier>{93995380-89BD-4b04-88EB-625FBE52EBFB}</UniqueIdentifier>
|
||||
<Extensions>h;hpp;hxx;hm;inl;inc;xsd</Extensions>
|
||||
</Filter>
|
||||
<Filter Include="Resource Files">
|
||||
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
|
||||
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
|
||||
</Filter>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="APMPlannerXplanes.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="AssemblyInfo.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="AircraftUtils.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClInclude Include="..\..\..\..\..\..\..\program files (x86)\microsoft sdks\windows\v7.0a\include\gl\gl.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="AircraftUtils.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
</ItemGroup>
|
||||
</Project>
|
|
@ -0,0 +1,10 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<LocalDebuggerCommand>C:\Users\hog\Desktop\DIYDrones&avr\X-Plane 9 Demo\X-Plane.exe</LocalDebuggerCommand>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<LocalDebuggerWorkingDirectory>C:\Users\hog\Desktop\DIYDrones&avr\X-Plane 9 Demo</LocalDebuggerWorkingDirectory>
|
||||
<DebuggerFlavor>WindowsLocalDebugger</DebuggerFlavor>
|
||||
</PropertyGroup>
|
||||
</Project>
|
|
@ -0,0 +1,67 @@
|
|||
#include "AircraftUtils.h"
|
||||
#include <string.h>
|
||||
|
||||
Aircraft::Aircraft(int AircraftNo)
|
||||
{
|
||||
char x_str[80];
|
||||
char y_str[80];
|
||||
char z_str[80];
|
||||
char the_str[80];
|
||||
char phi_str[80];
|
||||
char psi_str[80];
|
||||
char gear_deploy_str[80];
|
||||
char throttle_str[80];
|
||||
|
||||
strcpy(x_str, "sim/multiplayer/position/planeX_x");
|
||||
strcpy(y_str, "sim/multiplayer/position/planeX_y");
|
||||
strcpy(z_str, "sim/multiplayer/position/planeX_z");
|
||||
strcpy(the_str, "sim/multiplayer/position/planeX_the");
|
||||
strcpy(phi_str, "sim/multiplayer/position/planeX_phi");
|
||||
strcpy(psi_str, "sim/multiplayer/position/planeX_psi");
|
||||
strcpy(gear_deploy_str, "sim/multiplayer/position/planeX_gear_deploy");
|
||||
strcpy(throttle_str, "sim/multiplayer/position/planeX_throttle");
|
||||
|
||||
char cTemp = (AircraftNo + 0x30);
|
||||
x_str[30] = cTemp;
|
||||
y_str[30] = cTemp;
|
||||
z_str[30] = cTemp;
|
||||
the_str[30] = cTemp;
|
||||
phi_str[30] = cTemp;
|
||||
psi_str[30] = cTemp;
|
||||
gear_deploy_str[30] = cTemp;
|
||||
throttle_str[30] = cTemp;
|
||||
|
||||
dr_plane_x = XPLMFindDataRef(x_str);
|
||||
dr_plane_y = XPLMFindDataRef(y_str);
|
||||
dr_plane_z = XPLMFindDataRef(z_str);
|
||||
dr_plane_the = XPLMFindDataRef(the_str);
|
||||
dr_plane_phi = XPLMFindDataRef(phi_str);
|
||||
dr_plane_psi = XPLMFindDataRef(psi_str);
|
||||
dr_plane_gear_deploy = XPLMFindDataRef(gear_deploy_str);
|
||||
dr_plane_throttle = XPLMFindDataRef(throttle_str);
|
||||
}
|
||||
|
||||
void Aircraft::GetAircraftData(void)
|
||||
{
|
||||
plane_x = XPLMGetDataf(dr_plane_x);
|
||||
plane_y = XPLMGetDataf(dr_plane_y);
|
||||
plane_z = XPLMGetDataf(dr_plane_z);
|
||||
plane_the = XPLMGetDataf(dr_plane_the);
|
||||
plane_phi = XPLMGetDataf(dr_plane_phi);
|
||||
plane_psi = XPLMGetDataf(dr_plane_psi);
|
||||
XPLMGetDatavf(dr_plane_gear_deploy, plane_gear_deploy, 0, 5);
|
||||
XPLMGetDatavf(dr_plane_throttle, plane_throttle, 0, 8);
|
||||
}
|
||||
|
||||
void Aircraft::SetAircraftData(void)
|
||||
{
|
||||
XPLMSetDataf(dr_plane_x, plane_x);
|
||||
XPLMSetDataf(dr_plane_y, plane_y);
|
||||
XPLMSetDataf(dr_plane_z, plane_z);
|
||||
XPLMSetDataf(dr_plane_the, plane_the);
|
||||
XPLMSetDataf(dr_plane_phi, plane_phi);
|
||||
XPLMSetDataf(dr_plane_psi, plane_psi);
|
||||
XPLMSetDatavf(dr_plane_gear_deploy, plane_gear_deploy, 0, 5);
|
||||
XPLMSetDatavf(dr_plane_throttle, plane_throttle, 0, 8);
|
||||
}
|
||||
|
|
@ -0,0 +1,28 @@
|
|||
#include "XPLMPlanes.h"
|
||||
#include "XPLMUtilities.h"
|
||||
#include "XPLMDataAccess.h"
|
||||
|
||||
class Aircraft
|
||||
{
|
||||
private:
|
||||
XPLMDataRef dr_plane_x;
|
||||
XPLMDataRef dr_plane_y;
|
||||
XPLMDataRef dr_plane_z;
|
||||
XPLMDataRef dr_plane_the;
|
||||
XPLMDataRef dr_plane_phi;
|
||||
XPLMDataRef dr_plane_psi;
|
||||
XPLMDataRef dr_plane_gear_deploy;
|
||||
XPLMDataRef dr_plane_throttle;
|
||||
public:
|
||||
float plane_x;
|
||||
float plane_y;
|
||||
float plane_z;
|
||||
float plane_the;
|
||||
float plane_phi;
|
||||
float plane_psi;
|
||||
float plane_gear_deploy[5];
|
||||
float plane_throttle[8];
|
||||
Aircraft(int AircraftNo);
|
||||
void GetAircraftData(void);
|
||||
void SetAircraftData(void);
|
||||
};
|
|
@ -0,0 +1,39 @@
|
|||
|
||||
using namespace System;
|
||||
using namespace System::Reflection;
|
||||
using namespace System::Runtime::CompilerServices;
|
||||
using namespace System::Runtime::InteropServices;
|
||||
using namespace System::Security::Permissions;
|
||||
|
||||
//
|
||||
// General Information about an assembly is controlled through the following
|
||||
// set of attributes. Change these attribute values to modify the information
|
||||
// associated with an assembly.
|
||||
//
|
||||
[assembly:AssemblyTitleAttribute("APMPlannerXplanes")];
|
||||
[assembly:AssemblyDescriptionAttribute("")];
|
||||
[assembly:AssemblyConfigurationAttribute("")];
|
||||
[assembly:AssemblyCompanyAttribute("Microsoft")];
|
||||
[assembly:AssemblyProductAttribute("APMPlannerXplanes")];
|
||||
[assembly:AssemblyCopyrightAttribute("Copyright (c) Microsoft 2011")];
|
||||
[assembly:AssemblyTrademarkAttribute("")];
|
||||
[assembly:AssemblyCultureAttribute("")];
|
||||
|
||||
//
|
||||
// Version information for an assembly consists of the following four values:
|
||||
//
|
||||
// Major Version
|
||||
// Minor Version
|
||||
// Build Number
|
||||
// Revision
|
||||
//
|
||||
// You can specify all the value or you can default the Revision and Build Numbers
|
||||
// by using the '*' as shown below:
|
||||
|
||||
[assembly:AssemblyVersionAttribute("1.0.*")];
|
||||
|
||||
[assembly:ComVisible(false)];
|
||||
|
||||
[assembly:CLSCompliantAttribute(true)];
|
||||
|
||||
[assembly:SecurityPermission(SecurityAction::RequestMinimum, UnmanagedCode = true)];
|
|
@ -0,0 +1,3 @@
|
|||
//{{NO_DEPENDENCIES}}
|
||||
// Microsoft Visual C++ generated include file.
|
||||
// Used by app.rc
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,35 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public delegate void ProgressEventHandler(int progress);
|
||||
|
||||
interface ArduinoComms
|
||||
{
|
||||
bool connectAP();
|
||||
bool keepalive();
|
||||
bool sync();
|
||||
byte[] download(short length);
|
||||
byte[] downloadflash(short length);
|
||||
bool setaddress(int address);
|
||||
bool upload(byte[] data, short startfrom, short length, short startaddress);
|
||||
bool uploadflash(byte[] data, int startfrom, int length, int startaddress);
|
||||
|
||||
event ProgressEventHandler Progress;
|
||||
|
||||
// from serialport class
|
||||
int BaudRate { get; set; }
|
||||
bool DtrEnable { get; set; }
|
||||
string PortName { get; set; }
|
||||
StopBits StopBits { get; set; }
|
||||
Parity Parity { get; set; }
|
||||
bool IsOpen { get; }
|
||||
void Open();
|
||||
void Close();
|
||||
int DataBits { get; set; }
|
||||
}
|
||||
}
|
|
@ -0,0 +1,249 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
class ArduinoDetect
|
||||
{
|
||||
/// <summary>
|
||||
/// detects a 1280 or a 2560 board
|
||||
/// </summary>
|
||||
/// <param name="port">comportname</param>
|
||||
/// <returns>string either (1280/2560) or "" for none</returns>
|
||||
public static string DetectVersion(string port)
|
||||
{
|
||||
SerialPort serialPort = new SerialPort();
|
||||
serialPort.PortName = port;
|
||||
|
||||
if (serialPort.IsOpen)
|
||||
serialPort.Close();
|
||||
|
||||
serialPort.DtrEnable = true;
|
||||
serialPort.BaudRate = 57600;
|
||||
serialPort.Open();
|
||||
|
||||
System.Threading.Thread.Sleep(100);
|
||||
|
||||
int a = 0;
|
||||
while (a < 20) // 20 * 50 = 1 sec
|
||||
{
|
||||
//Console.WriteLine("write " + DateTime.Now.Millisecond);
|
||||
serialPort.DiscardInBuffer();
|
||||
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
|
||||
a++;
|
||||
System.Threading.Thread.Sleep(50);
|
||||
|
||||
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
|
||||
if (serialPort.BytesToRead >= 2)
|
||||
{
|
||||
byte b1 = (byte)serialPort.ReadByte();
|
||||
byte b2 = (byte)serialPort.ReadByte();
|
||||
if (b1 == 0x14 && b2 == 0x10)
|
||||
{
|
||||
serialPort.Close();
|
||||
return "1280";
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
serialPort.Close();
|
||||
|
||||
Console.WriteLine("Not a 1280");
|
||||
|
||||
System.Threading.Thread.Sleep(500);
|
||||
|
||||
serialPort.DtrEnable = true;
|
||||
serialPort.BaudRate = 115200;
|
||||
serialPort.Open();
|
||||
|
||||
System.Threading.Thread.Sleep(100);
|
||||
|
||||
a = 0;
|
||||
while (a < 4)
|
||||
{
|
||||
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
|
||||
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
|
||||
a++;
|
||||
System.Threading.Thread.Sleep(50);
|
||||
|
||||
try
|
||||
{
|
||||
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
|
||||
{
|
||||
serialPort.Close();
|
||||
return "2560";
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
serialPort.Close();
|
||||
Console.WriteLine("Not a 2560");
|
||||
return "";
|
||||
}
|
||||
|
||||
public static int decodeApVar(string comport, string version)
|
||||
{
|
||||
ArduinoComms port = new ArduinoSTK();
|
||||
if (version == "1280")
|
||||
{
|
||||
port = new ArduinoSTK();
|
||||
port.BaudRate = 57600;
|
||||
}
|
||||
else if (version == "2560")
|
||||
{
|
||||
port = new ArduinoSTKv2();
|
||||
port.BaudRate = 115200;
|
||||
}
|
||||
else { return -1; }
|
||||
port.PortName = comport;
|
||||
port.DtrEnable = true;
|
||||
port.Open();
|
||||
port.connectAP();
|
||||
byte[] buffer = port.download(1024 * 4);
|
||||
port.Close();
|
||||
|
||||
if (buffer[0] != 'A' || buffer[1] != 'P') // this is the apvar header
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (buffer[0] == 'A' && buffer[1] == 'P' && buffer[2] == 2)
|
||||
{ // apvar header and version
|
||||
int pos = 4;
|
||||
byte key = 0;
|
||||
while (pos < (1024 * 4))
|
||||
{
|
||||
int size = buffer[pos] & 63;
|
||||
pos++;
|
||||
key = buffer[pos];
|
||||
pos++;
|
||||
|
||||
Console.Write("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
|
||||
|
||||
if (key == 0xff)
|
||||
{
|
||||
Console.WriteLine("end sentinal at {0}", pos - 2);
|
||||
break;
|
||||
}
|
||||
|
||||
if (key == 0)
|
||||
{
|
||||
//Array.Reverse(buffer, pos, 2);
|
||||
return BitConverter.ToUInt16(buffer,pos);
|
||||
}
|
||||
|
||||
|
||||
for (int i = 0; i <= size; i++)
|
||||
{
|
||||
Console.Write(" {0:X2}", buffer[pos]);
|
||||
pos++;
|
||||
}
|
||||
Console.WriteLine();
|
||||
}
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
static byte[] genstkv2packet(SerialPort serialPort, byte[] message)
|
||||
{
|
||||
byte[] data = new byte[300];
|
||||
byte ck = 0;
|
||||
|
||||
data[0] = 0x1b;
|
||||
ck ^= data[0];
|
||||
data[1] = 0x1;
|
||||
ck ^= data[1];
|
||||
data[2] = (byte)((message.Length >> 8) & 0xff);
|
||||
ck ^= data[2];
|
||||
data[3] = (byte)(message.Length & 0xff);
|
||||
ck ^= data[3];
|
||||
data[4] = 0xe;
|
||||
ck ^= data[4];
|
||||
|
||||
int a = 5;
|
||||
foreach (byte let in message)
|
||||
{
|
||||
data[a] = let;
|
||||
ck ^= let;
|
||||
a++;
|
||||
}
|
||||
data[a] = ck;
|
||||
a++;
|
||||
|
||||
serialPort.Write(data, 0, a);
|
||||
//Console.WriteLine("about to read packet");
|
||||
|
||||
byte[] ret = ArduinoDetect.readpacket(serialPort);
|
||||
|
||||
//if (ret[1] == 0x0)
|
||||
{
|
||||
//Console.WriteLine("received OK");
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static byte[] readpacket(SerialPort serialPort)
|
||||
{
|
||||
byte[] temp = new byte[4000];
|
||||
byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
|
||||
int a = 7;
|
||||
int count = 0;
|
||||
|
||||
serialPort.ReadTimeout = 1000;
|
||||
|
||||
while (count < a)
|
||||
{
|
||||
//Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
|
||||
try
|
||||
{
|
||||
temp[count] = (byte)serialPort.ReadByte();
|
||||
}
|
||||
catch { break; }
|
||||
|
||||
|
||||
//Console.Write("{1}", temp[0], (char)temp[0]);
|
||||
|
||||
if (temp[0] != 0x1b)
|
||||
{
|
||||
count = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
if (count == 3)
|
||||
{
|
||||
a = (temp[2] << 8) + temp[3];
|
||||
mes = new byte[a];
|
||||
a += 5;
|
||||
}
|
||||
|
||||
if (count >= 5)
|
||||
{
|
||||
mes[count - 5] = temp[count];
|
||||
}
|
||||
|
||||
count++;
|
||||
}
|
||||
|
||||
//Console.WriteLine("read ck");
|
||||
try
|
||||
{
|
||||
temp[count] = (byte)serialPort.ReadByte();
|
||||
}
|
||||
catch { }
|
||||
|
||||
count++;
|
||||
|
||||
Array.Resize<byte>(ref temp, count);
|
||||
|
||||
//Console.WriteLine(this.BytesToRead);
|
||||
|
||||
return mes;
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,311 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
|
||||
// Written by Michael Oborne
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
class ArduinoSTK : SerialPort, ArduinoComms
|
||||
{
|
||||
public event ProgressEventHandler Progress;
|
||||
|
||||
/// <summary>
|
||||
/// Used to start initial connecting after serialport.open
|
||||
/// </summary>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool connectAP()
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
int a = 0;
|
||||
while (a < 50)
|
||||
{
|
||||
this.DiscardInBuffer();
|
||||
this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
|
||||
a++;
|
||||
Thread.Sleep(50);
|
||||
|
||||
Console.WriteLine("btr {0}", this.BytesToRead);
|
||||
if (this.BytesToRead >= 2)
|
||||
{
|
||||
byte b1 = (byte)this.ReadByte();
|
||||
byte b2 = (byte)this.ReadByte();
|
||||
if (b1 == 0x14 && b2 == 0x10)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Used to keep alive the connection
|
||||
/// </summary>
|
||||
/// <returns>true = passed, false = lost connection</returns>
|
||||
public bool keepalive()
|
||||
{
|
||||
return connectAP();
|
||||
}
|
||||
/// <summary>
|
||||
/// Syncs after a private command has been sent
|
||||
/// </summary>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool sync()
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
this.ReadTimeout = 1000;
|
||||
int f = 0;
|
||||
while (this.BytesToRead < 1)
|
||||
{
|
||||
f++;
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (f > 1000)
|
||||
return false;
|
||||
}
|
||||
int a = 0;
|
||||
while (a < 10)
|
||||
{
|
||||
if (this.BytesToRead >= 2)
|
||||
{
|
||||
byte b1 = (byte)this.ReadByte();
|
||||
byte b2 = (byte)this.ReadByte();
|
||||
Console.WriteLine("bytes {0:X} {1:X}", b1, b2);
|
||||
|
||||
if (b1 == 0x14 && b2 == 0x10)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
Console.WriteLine("btr {0}", this.BytesToRead);
|
||||
Thread.Sleep(10);
|
||||
a++;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
/// <summary>
|
||||
/// Downloads the eeprom with the given length - set Address first
|
||||
/// </summary>
|
||||
/// <param name="length">eeprom length</param>
|
||||
/// <returns>downloaded data</returns>
|
||||
public byte[] download(short length)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
throw new Exception();
|
||||
}
|
||||
byte[] data = new byte[length];
|
||||
|
||||
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
|
||||
if (this.ReadByte() == 0x14)
|
||||
{ // 0x14
|
||||
|
||||
int step = 0;
|
||||
while (step < length)
|
||||
{
|
||||
byte chr = (byte)this.ReadByte();
|
||||
data[step] = chr;
|
||||
step++;
|
||||
}
|
||||
|
||||
if (this.ReadByte() != 0x10) // 0x10
|
||||
throw new Exception();
|
||||
}
|
||||
else
|
||||
{
|
||||
throw new Exception();
|
||||
}
|
||||
return data;
|
||||
}
|
||||
|
||||
public byte[] downloadflash(short length)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
throw new Exception("Port Not Open");
|
||||
}
|
||||
byte[] data = new byte[length];
|
||||
|
||||
this.ReadTimeout = 1000;
|
||||
|
||||
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
|
||||
if (this.ReadByte() == 0x14)
|
||||
{ // 0x14
|
||||
|
||||
int read = length;
|
||||
while (read > 0)
|
||||
{
|
||||
//Console.WriteLine("offset {0} read {1}", length - read, read);
|
||||
read -= this.Read(data, length - read, read);
|
||||
//System.Threading.Thread.Sleep(1);
|
||||
}
|
||||
|
||||
if (this.ReadByte() != 0x10) // 0x10
|
||||
throw new Exception("Lost Sync 0x10");
|
||||
}
|
||||
else
|
||||
{
|
||||
throw new Exception("Lost Sync 0x14");
|
||||
}
|
||||
return data;
|
||||
}
|
||||
|
||||
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
int loops = (length / 0x100);
|
||||
int totalleft = length;
|
||||
int sending = 0;
|
||||
|
||||
for (int a = 0; a <= loops; a++)
|
||||
{
|
||||
if (totalleft > 0x100)
|
||||
{
|
||||
sending = 0x100;
|
||||
}
|
||||
else
|
||||
{
|
||||
sending = totalleft;
|
||||
}
|
||||
|
||||
//startaddress = 256;
|
||||
if (sending == 0)
|
||||
return true;
|
||||
|
||||
setaddress(startaddress);
|
||||
startaddress += sending;
|
||||
|
||||
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
|
||||
this.Write(command, 0, command.Length);
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
this.Write(data, startfrom + (length - totalleft), sending);
|
||||
command = new byte[] { (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
|
||||
totalleft -= sending;
|
||||
|
||||
|
||||
if (Progress != null)
|
||||
Progress((int)(((float)startaddress / (float)length) * 100));
|
||||
|
||||
if (!sync())
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Sets the eeprom start read or write address
|
||||
/// </summary>
|
||||
/// <param name="address">address, must be eaven number</param>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool setaddress(int address)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
if (address % 2 == 1)
|
||||
{
|
||||
throw new Exception("Address must be an even number");
|
||||
}
|
||||
|
||||
Console.WriteLine("Sending address " + ((ushort)(address / 2)));
|
||||
|
||||
address /= 2;
|
||||
address = (ushort)address;
|
||||
|
||||
byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
|
||||
return sync();
|
||||
}
|
||||
/// <summary>
|
||||
/// Upload data at preset address
|
||||
/// </summary>
|
||||
/// <param name="data">array to read from</param>
|
||||
/// <param name="startfrom">start array index</param>
|
||||
/// <param name="length">length to send</param>
|
||||
/// <param name="startaddress">sets eeprom start programing address</param>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool upload(byte[] data, short startfrom, short length, short startaddress)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
int loops = (length / 0x100);
|
||||
int totalleft = length;
|
||||
int sending = 0;
|
||||
|
||||
for (int a = 0; a <= loops; a++)
|
||||
{
|
||||
if (totalleft > 0x100)
|
||||
{
|
||||
sending = 0x100;
|
||||
}
|
||||
else
|
||||
{
|
||||
sending = totalleft;
|
||||
}
|
||||
|
||||
if (sending == 0)
|
||||
return true;
|
||||
|
||||
setaddress(startaddress);
|
||||
startaddress += (short)sending;
|
||||
|
||||
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
|
||||
this.Write(command, 0, command.Length);
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
this.Write(data, startfrom + (length - totalleft), sending);
|
||||
command = new byte[] { (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
|
||||
totalleft -= sending;
|
||||
|
||||
if (!sync())
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
public new bool Close()
|
||||
{
|
||||
try
|
||||
{
|
||||
|
||||
byte[] command = new byte[] { (byte)'Q', (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (base.IsOpen)
|
||||
base.Close();
|
||||
this.DtrEnable = false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,365 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
|
||||
// Written by Michael Oborne
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
class ArduinoSTKv2 : SerialPort,ArduinoComms
|
||||
{
|
||||
public event ProgressEventHandler Progress;
|
||||
|
||||
public byte[] genstkv2packet(byte[] message)
|
||||
{
|
||||
byte[] data = new byte[300];
|
||||
byte ck = 0;
|
||||
|
||||
data[0] = 0x1b;
|
||||
ck ^= data[0];
|
||||
data[1] = 0x1;
|
||||
ck ^= data[1];
|
||||
data[2] = (byte)((message.Length >> 8) & 0xff);
|
||||
ck ^= data[2];
|
||||
data[3] = (byte)(message.Length & 0xff);
|
||||
ck ^= data[3];
|
||||
data[4] = 0xe;
|
||||
ck ^= data[4];
|
||||
|
||||
int a = 5;
|
||||
foreach (byte let in message)
|
||||
{
|
||||
data[a] = let;
|
||||
ck ^= let;
|
||||
a++;
|
||||
}
|
||||
data[a] = ck;
|
||||
a++;
|
||||
|
||||
this.Write(data,0,a);
|
||||
//Console.WriteLine("about to read packet");
|
||||
|
||||
byte[] ret = readpacket();
|
||||
|
||||
//if (ret[1] == 0x0)
|
||||
{
|
||||
//Console.WriteLine("received OK");
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
byte[] readpacket()
|
||||
{
|
||||
byte[] temp = new byte[4000];
|
||||
byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
|
||||
int a = 7;
|
||||
int count = 0;
|
||||
|
||||
this.ReadTimeout = 1000;
|
||||
|
||||
while (count < a)
|
||||
{
|
||||
//Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
|
||||
try
|
||||
{
|
||||
temp[count] = (byte)this.ReadByte();
|
||||
}
|
||||
catch { break; }
|
||||
|
||||
|
||||
//Console.Write("{1}", temp[0], (char)temp[0]);
|
||||
|
||||
if (temp[0] != 0x1b)
|
||||
{
|
||||
count = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
if (count == 3)
|
||||
{
|
||||
a = (temp[2] << 8) + temp[3];
|
||||
mes = new byte[a];
|
||||
a += 5;
|
||||
}
|
||||
|
||||
if (count >= 5)
|
||||
{
|
||||
mes[count - 5] = temp[count];
|
||||
}
|
||||
|
||||
count++;
|
||||
}
|
||||
|
||||
//Console.WriteLine("read ck");
|
||||
try
|
||||
{
|
||||
temp[count] = (byte)this.ReadByte();
|
||||
}
|
||||
catch { }
|
||||
|
||||
count++;
|
||||
|
||||
Array.Resize<byte>(ref temp, count);
|
||||
|
||||
//Console.WriteLine(this.BytesToRead);
|
||||
|
||||
return mes;
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Used to start initial connecting after serialport.open
|
||||
/// </summary>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool connectAP()
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
Thread.Sleep(100);
|
||||
|
||||
int a = 0;
|
||||
while (a < 5)
|
||||
{
|
||||
byte[] temp = new byte[] { 0x6, 0,0,0,0};
|
||||
temp = this.genstkv2packet(temp);
|
||||
a++;
|
||||
Thread.Sleep(50);
|
||||
|
||||
try
|
||||
{
|
||||
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Used to keep alive the connection
|
||||
/// </summary>
|
||||
/// <returns>true = passed, false = lost connection</returns>
|
||||
public bool keepalive()
|
||||
{
|
||||
return connectAP();
|
||||
}
|
||||
/// <summary>
|
||||
/// Syncs after a private command has been sent
|
||||
/// </summary>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool sync()
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
/// <summary>
|
||||
/// Downloads the eeprom with the given length - set Address first
|
||||
/// </summary>
|
||||
/// <param name="length">eeprom length</param>
|
||||
/// <returns>downloaded data</returns>
|
||||
public byte[] download(short length)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
throw new Exception();
|
||||
}
|
||||
byte[] data = new byte[length];
|
||||
|
||||
byte[] temp = new byte[] { 0x16, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
|
||||
temp = this.genstkv2packet(temp);
|
||||
|
||||
Array.Copy(temp, 2, data, 0, length);
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
public byte[] downloadflash(short length)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
throw new Exception("Port Closed");
|
||||
}
|
||||
byte[] data = new byte[length];
|
||||
|
||||
byte[] temp = new byte[] { 0x14, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
|
||||
temp = this.genstkv2packet(temp);
|
||||
|
||||
Array.Copy(temp, 2, data, 0, length);
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
int loops = (length / 0x100);
|
||||
int totalleft = length;
|
||||
int sending = 0;
|
||||
|
||||
for (int a = 0; a <= loops; a++)
|
||||
{
|
||||
if (totalleft > 0x100)
|
||||
{
|
||||
sending = 0x100;
|
||||
}
|
||||
else
|
||||
{
|
||||
sending = totalleft;
|
||||
}
|
||||
|
||||
//startaddress = 256;
|
||||
if (sending == 0)
|
||||
return true;
|
||||
|
||||
setaddress(startaddress);
|
||||
startaddress += sending;
|
||||
|
||||
// 0x13
|
||||
|
||||
byte[] command = new byte[] { (byte)0x13, (byte)(sending >> 8), (byte)(sending & 0xff) };
|
||||
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
|
||||
Array.Resize<byte>(ref command, sending + 10); // sending + head
|
||||
|
||||
Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
|
||||
|
||||
command = this.genstkv2packet(command);
|
||||
|
||||
totalleft -= sending;
|
||||
|
||||
|
||||
if (Progress != null)
|
||||
Progress((int)(((float)startaddress / (float)length) * 100));
|
||||
|
||||
if (command[1] != 0)
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Sets the eeprom start read or write address
|
||||
/// </summary>
|
||||
/// <param name="address">address, must be eaven number</param>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool setaddress(int address)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
if (address % 2 == 1)
|
||||
{
|
||||
throw new Exception("Address must be an even number");
|
||||
}
|
||||
|
||||
Console.WriteLine("Sending address " + ((address / 2)));
|
||||
|
||||
int tempstart = address / 2; // words
|
||||
byte[] temp = new byte[] { 0x6, (byte)((tempstart >> 24) & 0xff), (byte)((tempstart >> 16) & 0xff), (byte)((tempstart >> 8) & 0xff), (byte)((tempstart >> 0) & 0xff) };
|
||||
temp = this.genstkv2packet(temp);
|
||||
|
||||
if (temp[1] == 0)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
/// <summary>
|
||||
/// Upload data at preset address
|
||||
/// </summary>
|
||||
/// <param name="data">array to read from</param>
|
||||
/// <param name="startfrom">start array index</param>
|
||||
/// <param name="length">length to send</param>
|
||||
/// <param name="startaddress">sets eeprom start programing address</param>
|
||||
/// <returns>true = passed, false = failed</returns>
|
||||
public bool upload(byte[] data,short startfrom,short length, short startaddress)
|
||||
{
|
||||
if (!this.IsOpen)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
int loops = (length / 0x100);
|
||||
int totalleft = length;
|
||||
int sending = 0;
|
||||
|
||||
for (int a = 0; a <= loops; a++)
|
||||
{
|
||||
if (totalleft > 0x100)
|
||||
{
|
||||
sending = 0x100;
|
||||
}
|
||||
else
|
||||
{
|
||||
sending = totalleft;
|
||||
}
|
||||
|
||||
//startaddress = 256;
|
||||
if (sending == 0)
|
||||
return true;
|
||||
|
||||
setaddress(startaddress);
|
||||
startaddress += (short)sending;
|
||||
|
||||
// 0x13
|
||||
|
||||
byte[] command = new byte[] { (byte)0x15, (byte)(sending >> 8), (byte)(sending & 0xff) };
|
||||
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
|
||||
Array.Resize<byte>(ref command, sending + 10); // sending + head
|
||||
|
||||
Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
|
||||
|
||||
command = this.genstkv2packet(command);
|
||||
|
||||
totalleft -= sending;
|
||||
|
||||
|
||||
if (Progress != null)
|
||||
Progress((int)(((float)startaddress / (float)length) * 100));
|
||||
|
||||
if (command[1] != 0)
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
public new bool Close() {
|
||||
|
||||
try
|
||||
{
|
||||
byte[] command = new byte[] { (byte)0x11 };
|
||||
genstkv2packet(command);
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (base.IsOpen)
|
||||
base.Close();
|
||||
this.DtrEnable = false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,585 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="4.0" DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<PropertyGroup>
|
||||
<Configuration Condition=" '$(Configuration)' == '' ">Debug</Configuration>
|
||||
<Platform Condition=" '$(Platform)' == '' ">x86</Platform>
|
||||
<ProductVersion>8.0.30703</ProductVersion>
|
||||
<SchemaVersion>2.0</SchemaVersion>
|
||||
<ProjectGuid>{A2E22272-95FE-47B6-B050-9AE7E2055BF5}</ProjectGuid>
|
||||
<OutputType>Exe</OutputType>
|
||||
<AppDesignerFolder>Properties</AppDesignerFolder>
|
||||
<RootNamespace>ArdupilotMega</RootNamespace>
|
||||
<AssemblyName>ArdupilotMegaPlanner</AssemblyName>
|
||||
<TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
|
||||
<TargetFrameworkProfile>
|
||||
</TargetFrameworkProfile>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
<IsWebBootstrapper>false</IsWebBootstrapper>
|
||||
<PublishUrl>publish/</PublishUrl>
|
||||
<Install>true</Install>
|
||||
<InstallFrom>Disk</InstallFrom>
|
||||
<UpdateEnabled>false</UpdateEnabled>
|
||||
<UpdateMode>Background</UpdateMode>
|
||||
<UpdateInterval>7</UpdateInterval>
|
||||
<UpdateIntervalUnits>Days</UpdateIntervalUnits>
|
||||
<UpdatePeriodically>false</UpdatePeriodically>
|
||||
<UpdateRequired>false</UpdateRequired>
|
||||
<MapFileExtensions>false</MapFileExtensions>
|
||||
<TargetCulture>en-US</TargetCulture>
|
||||
<ProductName>ArdupilotMegaPlanner</ProductName>
|
||||
<PublisherName>Michael Oborne</PublisherName>
|
||||
<CreateWebPageOnPublish>true</CreateWebPageOnPublish>
|
||||
<WebPage>index.htm</WebPage>
|
||||
<ApplicationRevision>1</ApplicationRevision>
|
||||
<ApplicationVersion>0.0.0.%2a</ApplicationVersion>
|
||||
<UseApplicationTrust>false</UseApplicationTrust>
|
||||
<PublishWizardCompleted>true</PublishWizardCompleted>
|
||||
<BootstrapperEnabled>true</BootstrapperEnabled>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Debug|x86' ">
|
||||
<PlatformTarget>x86</PlatformTarget>
|
||||
<DebugSymbols>true</DebugSymbols>
|
||||
<DebugType>full</DebugType>
|
||||
<Optimize>false</Optimize>
|
||||
<OutputPath>bin\Debug\</OutputPath>
|
||||
<DefineConstants>TRACE;DEBUG</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
<AllowUnsafeBlocks>false</AllowUnsafeBlocks>
|
||||
<DocumentationFile>
|
||||
</DocumentationFile>
|
||||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||
<NoStdLib>false</NoStdLib>
|
||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
|
||||
<PlatformTarget>x86</PlatformTarget>
|
||||
<DebugType>full</DebugType>
|
||||
<Optimize>true</Optimize>
|
||||
<OutputPath>bin\Release\</OutputPath>
|
||||
<DefineConstants>DEBUG;TRACE</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
<AllowUnsafeBlocks>false</AllowUnsafeBlocks>
|
||||
<DocumentationFile>
|
||||
</DocumentationFile>
|
||||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||
<DebugSymbols>true</DebugSymbols>
|
||||
<NoStdLib>false</NoStdLib>
|
||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<StartupObject>ArdupilotMega.Program</StartupObject>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<ManifestCertificateThumbprint>92959F7BF337E6755031B3721140373D9674958B</ManifestCertificateThumbprint>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<ManifestKeyFile>ArdupilotMega_TemporaryKey.pfx</ManifestKeyFile>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<GenerateManifests>true</GenerateManifests>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<SignManifests>false</SignManifests>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<SignAssembly>true</SignAssembly>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup />
|
||||
<PropertyGroup>
|
||||
<TargetZone>Custom</TargetZone>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup />
|
||||
<PropertyGroup>
|
||||
<AssemblyOriginatorKeyFile>mykey.pfx</AssemblyOriginatorKeyFile>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup>
|
||||
<RunPostBuildEvent>Always</RunPostBuildEvent>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<ApplicationIcon>apm2.ico</ApplicationIcon>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup />
|
||||
<PropertyGroup>
|
||||
<ApplicationManifest>Properties\app.manifest</ApplicationManifest>
|
||||
</PropertyGroup>
|
||||
<ItemGroup>
|
||||
<Reference Include="BSE.Windows.Forms">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\BSE.Windows.Forms.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="Core">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\kml-library\KmlTestbed\bin\Release\Core.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="DirectShowLib-2005">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\myquad\DirectShowLib-2005.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="GMap.NET.Core">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\myquad\greatmaps_e1bb830a18a3\GMap.NET.WindowsForms\bin\Debug\GMap.NET.Core.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="GMap.NET.WindowsForms">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\myquad\greatmaps_e1bb830a18a3\GMap.NET.WindowsForms\bin\Debug\GMap.NET.WindowsForms.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="ICSharpCode.SharpZipLib">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\SrcSamples\bin\ICSharpCode.SharpZipLib.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="KMLib">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\kml-library\KmlTestbed\bin\Release\KMLib.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.dll</HintPath>
|
||||
<Private>False</Private>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.DirectInput.dll</HintPath>
|
||||
<Private>False</Private>
|
||||
</Reference>
|
||||
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\opentk\trunk\Binaries\OpenTK\Release\OpenTK.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\opentk\trunk\Binaries\OpenTK\Release\OpenTK.GLControl.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="SharpKml, Version=1.1.0.0, Culture=neutral, PublicKeyToken=e608cd7d975805ad, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\myquad\sharpkml\SharpKml\bin\Release\SharpKml.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="System" />
|
||||
<Reference Include="System.Data" />
|
||||
<Reference Include="System.Data.SQLite">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones&avr\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\x86\System.Data.SQLite.DLL</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="System.Drawing" />
|
||||
<Reference Include="System.Speech">
|
||||
<Private>True</Private>
|
||||
</Reference>
|
||||
<Reference Include="System.Web" />
|
||||
<Reference Include="System.Windows.Forms" />
|
||||
<Reference Include="System.Xml" />
|
||||
<Reference Include="ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\ArdupilotSim\ArdupilotSim\bin\Release\ZedGraph.dll</HintPath>
|
||||
</Reference>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Compile Include="AGauge.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="ArduinoDetect.cs" />
|
||||
<Compile Include="AviWriter.cs" />
|
||||
<Compile Include="Capture.cs" />
|
||||
<Compile Include="CommsSerialInterface.cs" />
|
||||
<Compile Include="CommsSerialPort.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="CommsUdpSerial.cs" />
|
||||
<Compile Include="HIL\Aircraft.cs" />
|
||||
<Compile Include="HIL\Point3d.cs" />
|
||||
<Compile Include="HIL\QuadCopter.cs" />
|
||||
<Compile Include="HIL\Quaternion.cs" />
|
||||
<Compile Include="HIL\Vector3d.cs" />
|
||||
<Compile Include="MavlinkLog.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="MavlinkLog.Designer.cs">
|
||||
<DependentUpon>MavlinkLog.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\FlightData.Designer.cs">
|
||||
<DependentUpon>FlightData.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\FlightPlanner.Designer.cs">
|
||||
<DependentUpon>FlightPlanner.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\test.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\test.Designer.cs">
|
||||
<DependentUpon>test.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Joystick.cs" />
|
||||
<Compile Include="JoystickSetup.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="JoystickSetup.Designer.cs">
|
||||
<DependentUpon>JoystickSetup.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="MAVLinkTypesenum.cs" />
|
||||
<Compile Include="MyButton.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Common.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="ArduinoComms.cs" />
|
||||
<Compile Include="MyLabel.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="MyUserControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="NetSerialServer.cs" />
|
||||
<Compile Include="ArduinoSTKv2.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="paramcompare.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="paramcompare.Designer.cs">
|
||||
<DependentUpon>paramcompare.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="RAW_Sensor.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="RAW_Sensor.Designer.cs">
|
||||
<DependentUpon>RAW_Sensor.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Help.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Help.Designer.cs">
|
||||
<DependentUpon>Help.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Terminal.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Terminal.Designer.cs">
|
||||
<DependentUpon>Terminal.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="HUD.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="MainV2.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="MainV2.Designer.cs">
|
||||
<DependentUpon>MainV2.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Configuration.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Configuration.Designer.cs">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Firmware.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\FlightData.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\FlightPlanner.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Simulation.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\Simulation.Designer.cs">
|
||||
<DependentUpon>Simulation.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="MyTrackBar.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="CurrentState.cs" />
|
||||
<Compile Include="MAVLinkTypes.cs" />
|
||||
<Compile Include="ElevationProfile.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="ElevationProfile.Designer.cs">
|
||||
<DependentUpon>ElevationProfile.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="MAVLink.cs" />
|
||||
<Compile Include="NetSerial.cs" />
|
||||
<Compile Include="ArduinoSTK.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Log.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Log.Designer.cs">
|
||||
<DependentUpon>Log.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="LogBrowse.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="LogBrowse.designer.cs">
|
||||
<DependentUpon>LogBrowse.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Program.cs" />
|
||||
<Compile Include="Properties\AssemblyInfo.cs" />
|
||||
<Compile Include="SerialOutput.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="SerialOutput.Designer.cs">
|
||||
<DependentUpon>SerialOutput.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Setup\Setup.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Setup\Setup.Designer.cs">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Splash.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Splash.Designer.cs">
|
||||
<DependentUpon>Splash.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="temp.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="temp.Designer.cs">
|
||||
<DependentUpon>temp.cs</DependentUpon>
|
||||
</Compile>
|
||||
<EmbeddedResource Include="AGauge.resx">
|
||||
<DependentUpon>AGauge.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Log.zh-Hans.resx">
|
||||
<DependentUpon>Log.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="LogBrowse.zh-Hans.resx">
|
||||
<DependentUpon>LogBrowse.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="paramcompare.resx">
|
||||
<DependentUpon>paramcompare.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="RAW_Sensor.resx">
|
||||
<DependentUpon>RAW_Sensor.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="MavlinkLog.resx">
|
||||
<DependentUpon>MavlinkLog.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Configuration.resx">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Configuration.zh-Hans.resx">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Firmware.zh-Hans.resx">
|
||||
<DependentUpon>Firmware.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightData.zh-Hans.resx">
|
||||
<DependentUpon>FlightData.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightPlanner.zh-Hans.resx">
|
||||
<DependentUpon>FlightPlanner.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Help.resx">
|
||||
<DependentUpon>Help.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Help.zh-Hans.resx">
|
||||
<DependentUpon>Help.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Simulation.resx">
|
||||
<DependentUpon>Simulation.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Simulation.zh-Hans.resx">
|
||||
<DependentUpon>Simulation.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Terminal.resx">
|
||||
<DependentUpon>Terminal.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Terminal.zh-Hans.resx">
|
||||
<DependentUpon>Terminal.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\test.resx">
|
||||
<DependentUpon>test.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="HUD.resx">
|
||||
<DependentUpon>HUD.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="JoystickSetup.resx">
|
||||
<DependentUpon>JoystickSetup.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="JoystickSetup.zh-Hans.resx">
|
||||
<DependentUpon>JoystickSetup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="MainV2.resx">
|
||||
<DependentUpon>MainV2.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Firmware.resx">
|
||||
<DependentUpon>Firmware.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightData.resx">
|
||||
<DependentUpon>FlightData.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightPlanner.resx">
|
||||
<DependentUpon>FlightPlanner.cs</DependentUpon>
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="ElevationProfile.resx">
|
||||
<DependentUpon>ElevationProfile.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Log.resx">
|
||||
<DependentUpon>Log.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="LogBrowse.resx">
|
||||
<DependentUpon>LogBrowse.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Properties\Resources.resx">
|
||||
<Generator>PublicResXFileCodeGenerator</Generator>
|
||||
<LastGenOutput>Resources.Designer.cs</LastGenOutput>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<Compile Include="Properties\Resources.Designer.cs">
|
||||
<AutoGen>True</AutoGen>
|
||||
<DependentUpon>Resources.resx</DependentUpon>
|
||||
<DesignTime>True</DesignTime>
|
||||
</Compile>
|
||||
<EmbeddedResource Include="SerialOutput.resx">
|
||||
<DependentUpon>SerialOutput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.zh-Hans.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Splash.resx">
|
||||
<DependentUpon>Splash.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="temp.resx">
|
||||
<DependentUpon>temp.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<None Include="app.config" />
|
||||
<None Include="arducopter-fgmodel.zip">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</None>
|
||||
<None Include="arducopter-xplane.zip">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</None>
|
||||
<None Include="defines.h">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</None>
|
||||
<None Include="MAC\Info.plist" />
|
||||
<None Include="MAC\run.sh" />
|
||||
<None Include="mykey.pfx" />
|
||||
<None Include="Properties\app.manifest" />
|
||||
<None Include="Properties\DataSources\CurrentState.datasource" />
|
||||
<None Include="block_plane_0.dae">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</None>
|
||||
<None Include="Resources\Welcome_CN.rtf" />
|
||||
<None Include="Resources\Welcome_to_Michael_Oborne.rtf" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Content Include="apm2.ico" />
|
||||
<Content Include="Resources\MAVCmd.zh-Hans.txt" />
|
||||
<Content Include="Resources\MAVParam.zh-Hans.txt" />
|
||||
<None Include="Resources\MAVCmd.txt" />
|
||||
<None Include="Resources\MAVParam.txt" />
|
||||
<None Include="Resources\new frames-09.png" />
|
||||
<Content Include="dataflashlog.xml">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<None Include="Resources\plane2.png" />
|
||||
<None Include="Resources\quad2.png" />
|
||||
<None Include="Resources\quad.png" />
|
||||
<None Include="Resources\planetracker.png" />
|
||||
<None Include="Resources\terminal.png" />
|
||||
<None Include="Resources\simulation.png" />
|
||||
<None Include="Resources\planner.png" />
|
||||
<None Include="Resources\configuration.png" />
|
||||
<None Include="Resources\data.png" />
|
||||
<None Include="Resources\firmware.png" />
|
||||
<None Include="Resources\bg.jpg" />
|
||||
<None Include="Resources\connect.png" />
|
||||
<None Include="Resources\disconnect.png" />
|
||||
<None Include="Resources\help.png" />
|
||||
<None Include="Resources\APM_airframes_001.png" />
|
||||
<None Include="Resources\APM_airframes_002.png" />
|
||||
<Content Include="m3u\both.m3u">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<Content Include="m3u\hud.m3u">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<Content Include="m3u\map.m3u">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<None Include="Resources\09028-01.jpg" />
|
||||
<None Include="Resources\AC-0004-11-2.jpg" />
|
||||
<Content Include="MAVLink.xml">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<Content Include="quadhil.xml">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<None Include="Resources\APM_airframes-07.png" />
|
||||
<None Include="Resources\APM_airframes-08.png" />
|
||||
<None Include="Resources\frames-01.png" />
|
||||
<None Include="Resources\frames-02.png" />
|
||||
<None Include="Resources\frames-03.png" />
|
||||
<None Include="Resources\frames-04.png" />
|
||||
<None Include="Resources\frames-05.png" />
|
||||
<None Include="Resources\frames-06.png" />
|
||||
<None Include="Resources\frames-07.png" />
|
||||
<None Include="Resources\frames-08.png" />
|
||||
<None Include="Resources\BR-0004-03-2.jpg" />
|
||||
<None Include="Resources\BR-HMC5883-01-2.jpg" />
|
||||
<EmbeddedResource Include="Resources\down.png" />
|
||||
<EmbeddedResource Include="Resources\up.png" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Client.3.5">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework 3.5 SP1 Client Profile</ProductName>
|
||||
<Install>false</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Framework.3.5.SP1">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework 3.5 SP1</ProductName>
|
||||
<Install>true</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Windows.Installer.3.1">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>Windows Installer 3.1</ProductName>
|
||||
<Install>true</Install>
|
||||
</BootstrapperPackage>
|
||||
</ItemGroup>
|
||||
<ItemGroup />
|
||||
<ItemGroup />
|
||||
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
|
||||
<PropertyGroup>
|
||||
<PostBuildEvent>
|
||||
</PostBuildEvent>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<PreBuildEvent>
|
||||
</PreBuildEvent>
|
||||
</PropertyGroup>
|
||||
<!-- To modify your build process, add your task inside one of the targets below and uncomment it.
|
||||
Other similar extension points exist, see Microsoft.Common.targets.
|
||||
<Target Name="BeforeBuild">
|
||||
</Target>
|
||||
<Target Name="AfterBuild">
|
||||
</Target>
|
||||
-->
|
||||
</Project>
|
|
@ -0,0 +1,13 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<PropertyGroup>
|
||||
<PublishUrlHistory>publish/|ftp://vps.oborne.me/ardupilotmegaplanner/|ftp://vps.oborne.me/|ftp://www.vps.oborne.me/ardupilotmegaplanner/|http://www.vps.oborne.me/dav/ardupilotmegaplanner/</PublishUrlHistory>
|
||||
<InstallUrlHistory>http://www.vps.oborne.me/ardupilotmegaplanner/|http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/publish/</InstallUrlHistory>
|
||||
<SupportUrlHistory>http://www.diydrones.com/</SupportUrlHistory>
|
||||
<UpdateUrlHistory>http://www.vps.oborne.me/ardupilotmegaplanner/|http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/publish/|http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Publish/</UpdateUrlHistory>
|
||||
<BootstrapperUrlHistory />
|
||||
<ErrorReportUrlHistory />
|
||||
<FallbackCulture>en-US</FallbackCulture>
|
||||
<VerifyUploadedFiles>false</VerifyUploadedFiles>
|
||||
</PropertyGroup>
|
||||
</Project>
|
|
@ -0,0 +1,65 @@
|
|||
|
||||
Microsoft Visual Studio Solution File, Format Version 11.00
|
||||
# Visual C# Express 2010
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArdupilotMega", "ArdupilotMega.csproj", "{A2E22272-95FE-47B6-B050-9AE7E2055BF5}"
|
||||
ProjectSection(ProjectDependencies) = postProject
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA} = {E64A1A41-A5B0-458E-8284-BB63705354DA}
|
||||
EndProjectSection
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "Updater", "Updater\Updater.csproj", "{E64A1A41-A5B0-458E-8284-BB63705354DA}"
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "resedit", "resedit\resedit.csproj", "{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}"
|
||||
EndProject
|
||||
Global
|
||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||
Debug|Any CPU = Debug|Any CPU
|
||||
Debug|Mixed Platforms = Debug|Mixed Platforms
|
||||
Debug|Win32 = Debug|Win32
|
||||
Debug|x86 = Debug|x86
|
||||
Release|Any CPU = Release|Any CPU
|
||||
Release|Mixed Platforms = Release|Mixed Platforms
|
||||
Release|Win32 = Release|Win32
|
||||
Release|x86 = Release|x86
|
||||
EndGlobalSection
|
||||
GlobalSection(ProjectConfigurationPlatforms) = postSolution
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|Any CPU.ActiveCfg = Debug|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|Mixed Platforms.Build.0 = Debug|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|Win32.ActiveCfg = Debug|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|x86.ActiveCfg = Debug|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|x86.Build.0 = Debug|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|Any CPU.ActiveCfg = Release|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|Mixed Platforms.ActiveCfg = Release|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|Mixed Platforms.Build.0 = Release|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|Win32.ActiveCfg = Release|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|x86.ActiveCfg = Release|x86
|
||||
{A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|x86.Build.0 = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|Any CPU.ActiveCfg = Debug|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|Mixed Platforms.Build.0 = Debug|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|Win32.ActiveCfg = Debug|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|x86.ActiveCfg = Debug|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|x86.Build.0 = Debug|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Any CPU.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Mixed Platforms.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Mixed Platforms.Build.0 = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Win32.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.Build.0 = Release|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Any CPU.ActiveCfg = Debug|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Mixed Platforms.Build.0 = Debug|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Win32.ActiveCfg = Debug|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|x86.ActiveCfg = Debug|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|x86.Build.0 = Debug|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Any CPU.ActiveCfg = Release|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Mixed Platforms.ActiveCfg = Release|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Mixed Platforms.Build.0 = Release|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Win32.ActiveCfg = Release|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|x86.ActiveCfg = Release|x86
|
||||
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|x86.Build.0 = Release|x86
|
||||
EndGlobalSection
|
||||
GlobalSection(SolutionProperties) = preSolution
|
||||
HideSolutionNode = FALSE
|
||||
EndGlobalSection
|
||||
EndGlobal
|
|
@ -0,0 +1,291 @@
|
|||
using System;
|
||||
using System.Runtime.InteropServices;
|
||||
using System.Drawing;
|
||||
using System.Drawing.Imaging;
|
||||
using System.IO;
|
||||
using u32 = System.UInt32;
|
||||
using u16 = System.UInt16;
|
||||
using u8 = System.Byte;
|
||||
|
||||
/// <summary>
|
||||
/// based off ftp://pserver.samba.org/pub/unpacked/picturebook/avi.c
|
||||
/// </summary>
|
||||
|
||||
public class AviWriter
|
||||
{
|
||||
/*
|
||||
avi debug: * LIST-root size:1233440040 pos:0
|
||||
avi debug: + RIFF-AVI size:1233440032 pos:0
|
||||
avi debug: | + LIST-hdrl size:310 pos:12
|
||||
avi debug: | | + avih size:56 pos:24
|
||||
avi debug: | | + LIST-strl size:124 pos:88
|
||||
avi debug: | | | + strh size:64 pos:100
|
||||
avi debug: | | | + strf size:40 pos:172
|
||||
avi debug: | | + LIST-strl size:102 pos:220
|
||||
avi debug: | | | + strh size:64 pos:232
|
||||
avi debug: | | | + strf size:18 pos:304
|
||||
avi debug: | + JUNK size:1698 pos:330
|
||||
avi debug: | + LIST-movi size:1232936964 pos:2036
|
||||
avi debug: | + idx1 size:501024 pos:1232939008
|
||||
avi debug: AVIH: 2 stream, flags HAS_INDEX
|
||||
avi debug: stream[0] rate:1000000 scale:33333 samplesize:0
|
||||
avi debug: stream[0] video(MJPG) 1280x720 24bpp 30.000300fps
|
||||
*/
|
||||
|
||||
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct riff_head
|
||||
{
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] riff; /* "RIFF" */
|
||||
public u32 size;
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] avistr; /* "AVI " */
|
||||
};
|
||||
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct stream_head
|
||||
{ /* 56 bytes */
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] strh; /* "strh" */
|
||||
public u32 size;
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] vids; /* "vids" */
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] codec; /* codec name */
|
||||
public u32 flags;
|
||||
public u32 reserved1;
|
||||
public u32 initialframes;
|
||||
public u32 scale; /* 1 */
|
||||
public u32 rate; /* in frames per second */
|
||||
public u32 start;
|
||||
public u32 length; /* what units?? fps*nframes ?? */
|
||||
public u32 suggested_bufsize;
|
||||
public u32 quality; /* -1 */
|
||||
public u32 samplesize;
|
||||
public short l;
|
||||
public short t;
|
||||
public short r;
|
||||
public short b;
|
||||
};
|
||||
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct avi_head
|
||||
{ /* 64 bytes */
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] avih; /* "avih" */
|
||||
public u32 size;
|
||||
public u32 time; /* microsec per frame? 1e6 / fps ?? */
|
||||
public u32 maxbytespersec;
|
||||
public u32 reserved1;
|
||||
public u32 flags;
|
||||
public u32 nframes;
|
||||
public u32 initialframes;
|
||||
public u32 numstreams; /* 1 */
|
||||
public u32 suggested_bufsize;
|
||||
public u32 width;
|
||||
public u32 height;
|
||||
public u32 scale; /* 1 */
|
||||
public u32 rate; /* fps */
|
||||
public u32 start;
|
||||
public u32 length; /* what units?? fps*nframes ?? */
|
||||
};
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct list_head
|
||||
{ /* 12 bytes */
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] list; /* "LIST" */
|
||||
public u32 size;
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] type;
|
||||
};
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct db_head
|
||||
{
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] db; /* "00db" */
|
||||
public u32 size;
|
||||
};
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct frame_head
|
||||
{ /* 48 bytes */
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] strf; /* "strf" */
|
||||
public u32 size;
|
||||
public UInt32 size2; /* repeat of previous field? */
|
||||
public Int32 width;
|
||||
public Int32 height;
|
||||
public Int16 planes; /* 1 */
|
||||
public Int16 bitcount; /* 24 */
|
||||
[MarshalAs(
|
||||
UnmanagedType.ByValArray,
|
||||
SizeConst = 4)]
|
||||
public char[] codec; /* MJPG */
|
||||
public UInt32 unpackedsize; /* 3 * w * h */
|
||||
public Int32 r1;
|
||||
public Int32 r2;
|
||||
public UInt32 clr_used;
|
||||
public UInt32 clr_important;
|
||||
};
|
||||
|
||||
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||
public struct BITMAPINFOHEADER
|
||||
{
|
||||
public UInt32 biSize;
|
||||
public Int32 biWidth;
|
||||
public Int32 biHeight;
|
||||
public Int16 biPlanes;
|
||||
public Int16 biBitCount;
|
||||
public UInt32 biCompression;
|
||||
public UInt32 biSizeImage;
|
||||
public Int32 biXPelsPerMeter;
|
||||
public Int32 biYPelsPerMeter;
|
||||
public UInt32 biClrUsed;
|
||||
public UInt32 biClrImportant;
|
||||
}
|
||||
|
||||
|
||||
|
||||
static int nframes;
|
||||
static uint totalsize;
|
||||
System.IO.BufferedStream fd;
|
||||
|
||||
public void avi_close()
|
||||
{
|
||||
if (fd != null)
|
||||
fd.Close();
|
||||
}
|
||||
|
||||
/* start writing an AVI file */
|
||||
public void avi_start(string filename)
|
||||
{
|
||||
avi_close();
|
||||
|
||||
fd = new BufferedStream(File.Open(filename, FileMode.Create));
|
||||
|
||||
fd.Seek(2048,SeekOrigin.Begin);
|
||||
|
||||
nframes = 0;
|
||||
totalsize = 0;
|
||||
}
|
||||
|
||||
|
||||
/* add a jpeg frame to an AVI file */
|
||||
public void avi_add(u8[] buf, uint size)
|
||||
{
|
||||
Console.WriteLine(DateTime.Now.Millisecond + "avi frame");
|
||||
db_head db = new db_head { db = "00dc".ToCharArray(), size = size };
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(db), 0, Marshal.SizeOf(db));
|
||||
fd.Write(buf, 0, (int)size);
|
||||
if (size % 2 == 1)
|
||||
{
|
||||
size++;
|
||||
fd.Seek(1, SeekOrigin.Current);
|
||||
}
|
||||
nframes++;
|
||||
totalsize += size;
|
||||
}
|
||||
|
||||
void strcpy(ref char[] to,string orig)
|
||||
{
|
||||
to = orig.ToCharArray();
|
||||
}
|
||||
|
||||
/* finish writing the AVI file - filling in the header */
|
||||
public void avi_end(int width, int height, int fps)
|
||||
{
|
||||
riff_head rh = new riff_head { riff = "RIFF".ToCharArray(), size = 0, avistr = "AVI ".ToCharArray() };
|
||||
list_head lh1 = new list_head { list = "LIST".ToCharArray(), size = 0, type = "hdrl".ToCharArray() };
|
||||
avi_head ah = new avi_head();
|
||||
list_head lh2 = new list_head { list = "LIST".ToCharArray(), size = 0, type = "strl".ToCharArray() };
|
||||
stream_head sh = new stream_head();
|
||||
frame_head fh = new frame_head();
|
||||
list_head junk = new list_head() { list = "JUNK".ToCharArray(), size = 0 };
|
||||
list_head lh3 = new list_head { list = "LIST".ToCharArray(), size = 0, type = "movi".ToCharArray() };
|
||||
|
||||
//bzero(&ah, sizeof(ah));
|
||||
strcpy(ref ah.avih, "avih");
|
||||
ah.time = (u32)(1e6 / fps);
|
||||
ah.numstreams = 1;
|
||||
//ah.scale = (u32)(1e6 / fps);
|
||||
//ah.rate = (u32)fps;
|
||||
//ah.length = (u32)(nframes);
|
||||
ah.nframes = (u32)(nframes);
|
||||
ah.width = (u32)width;
|
||||
ah.height = (u32)height;
|
||||
ah.flags = 0;
|
||||
ah.suggested_bufsize = (u32)(3 * width * height * fps);
|
||||
ah.maxbytespersec = (u32)(3 * width * height * fps);
|
||||
|
||||
//bzero(&sh, sizeof(sh));
|
||||
strcpy(ref sh.strh, "strh");
|
||||
strcpy(ref sh.vids, "vids");
|
||||
strcpy(ref sh.codec, "MJPG");
|
||||
sh.scale = (u32)(1e6 / fps);
|
||||
sh.rate = (u32)1000000;
|
||||
sh.length = (u32)(nframes);
|
||||
sh.suggested_bufsize = (u32)(3 * width * height * fps);
|
||||
unchecked
|
||||
{
|
||||
sh.quality = (uint)-1;
|
||||
}
|
||||
|
||||
//bzero(&fh, sizeof(fh));
|
||||
strcpy(ref fh.strf, "strf");
|
||||
fh.width = width;
|
||||
fh.height = height;
|
||||
fh.planes = 1;
|
||||
fh.bitcount = 24;
|
||||
strcpy(ref fh.codec, "MJPG");
|
||||
fh.unpackedsize = (u32)(3 * width * height);
|
||||
|
||||
rh.size = (u32)(Marshal.SizeOf(lh1) + Marshal.SizeOf(ah) + Marshal.SizeOf(lh2) + Marshal.SizeOf(sh) +
|
||||
Marshal.SizeOf(fh) + Marshal.SizeOf(lh3) +
|
||||
nframes * Marshal.SizeOf((new db_head())) +
|
||||
totalsize);
|
||||
lh1.size = (u32)(4 + Marshal.SizeOf(ah) + Marshal.SizeOf(lh2) + Marshal.SizeOf(sh) + Marshal.SizeOf(fh));
|
||||
ah.size = (u32)(Marshal.SizeOf(ah) - 8);
|
||||
lh2.size = (u32)(4 + Marshal.SizeOf(sh) + Marshal.SizeOf(fh));
|
||||
sh.size = (u32)(Marshal.SizeOf(sh) - 8);
|
||||
fh.size = (u32)(Marshal.SizeOf(fh) - 8);
|
||||
fh.size2 = fh.size;
|
||||
lh3.size = (u32)(4 +
|
||||
nframes * Marshal.SizeOf((new db_head())) +
|
||||
totalsize);
|
||||
junk.size = 2048 - lh1.size - 12 - 12 - 12 - 4; // junk head, list head, rif head , 4
|
||||
long pos = fd.Position;
|
||||
fd.Seek(0, SeekOrigin.Begin);
|
||||
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(rh),0, Marshal.SizeOf(rh));
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(lh1), 0, Marshal.SizeOf(lh1));
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(ah), 0, Marshal.SizeOf(ah));
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(lh2), 0, Marshal.SizeOf(lh2));
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(sh), 0, Marshal.SizeOf(sh));
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(fh), 0, Marshal.SizeOf(fh));
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(junk), 0, Marshal.SizeOf(junk));
|
||||
fd.Seek(2036, SeekOrigin.Begin);
|
||||
fd.Write(ArdupilotMega.MAVLink.StructureToByteArray(lh3), 0, Marshal.SizeOf(lh3));
|
||||
|
||||
fd.Seek(pos, SeekOrigin.Begin);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,549 @@
|
|||
/****************************************************************************
|
||||
While the underlying libraries are covered by LGPL, this sample is released
|
||||
as public domain. It is distributed in the hope that it will be useful, but
|
||||
WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*****************************************************************************/
|
||||
|
||||
using System;
|
||||
using System.Drawing;
|
||||
using System.Drawing.Imaging;
|
||||
using System.Collections;
|
||||
using System.Runtime.InteropServices;
|
||||
using System.Threading;
|
||||
using System.Diagnostics;
|
||||
using System.Collections.Generic;
|
||||
|
||||
using DirectShowLib;
|
||||
|
||||
|
||||
namespace WebCamService
|
||||
{
|
||||
public delegate void CamImage(Image camimage);
|
||||
|
||||
/// <summary> Summary description for MainForm. </summary>
|
||||
public class Capture : ISampleGrabberCB, IDisposable
|
||||
{
|
||||
#region Member variables
|
||||
|
||||
/// <summary> graph builder interface. </summary>
|
||||
private IFilterGraph2 m_FilterGraph = null;
|
||||
private IMediaControl m_mediaCtrl = null;
|
||||
|
||||
/// <summary> so we can wait for the async job to finish </summary>
|
||||
private ManualResetEvent m_PictureReady = null;
|
||||
|
||||
/// <summary> Set by async routine when it captures an image </summary>
|
||||
private volatile bool m_bGotOne = false;
|
||||
|
||||
/// <summary> Indicates the status of the graph </summary>
|
||||
private bool m_bRunning = false;
|
||||
|
||||
/// <summary> Dimensions of the image, calculated once in constructor. </summary>
|
||||
private IntPtr m_handle = IntPtr.Zero;
|
||||
private int m_videoWidth;
|
||||
private int m_videoHeight;
|
||||
private int m_stride;
|
||||
public int m_Dropped = 0;
|
||||
|
||||
public Image image = null;
|
||||
IntPtr ip = IntPtr.Zero;
|
||||
|
||||
public event CamImage camimage;
|
||||
System.Windows.Forms.Timer timer1 = new System.Windows.Forms.Timer();
|
||||
|
||||
#endregion
|
||||
|
||||
#region API
|
||||
|
||||
[DllImport("Kernel32.dll", EntryPoint="RtlMoveMemory")]
|
||||
private static extern void CopyMemory(IntPtr Destination, IntPtr Source, int Length);
|
||||
|
||||
#endregion
|
||||
|
||||
/// <summary> Use capture device zero, default frame rate and size</summary>
|
||||
public Capture()
|
||||
{
|
||||
//_Capture(0, 0, 0, 0);
|
||||
}
|
||||
/// <summary> Use specified capture device, default frame rate and size</summary>
|
||||
public Capture(int iDeviceNum)
|
||||
{
|
||||
_Capture(iDeviceNum, 0, 0, 0);
|
||||
}
|
||||
/// <summary> Use specified capture device, specified frame rate and default size</summary>
|
||||
public Capture(int iDeviceNum, int iFrameRate)
|
||||
{
|
||||
_Capture(iDeviceNum, iFrameRate, 0, 0);
|
||||
}
|
||||
/// <summary> Use specified capture device, specified frame rate and size</summary>
|
||||
public Capture(int iDeviceNum, int iFrameRate, int iWidth, int iHeight)
|
||||
{
|
||||
_Capture(iDeviceNum, iFrameRate, iWidth, iHeight);
|
||||
}
|
||||
/// <summary> release everything. </summary>
|
||||
public void Dispose()
|
||||
{
|
||||
timer1.Stop();
|
||||
if (camimage != null)
|
||||
{
|
||||
camimage(null); // clear last pic
|
||||
}
|
||||
CloseInterfaces();
|
||||
if (m_PictureReady != null)
|
||||
{
|
||||
m_PictureReady.Close();
|
||||
m_PictureReady = null;
|
||||
}
|
||||
}
|
||||
// Destructor
|
||||
~Capture()
|
||||
{
|
||||
Dispose();
|
||||
}
|
||||
|
||||
public int Width
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_videoWidth;
|
||||
}
|
||||
}
|
||||
public int Height
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_videoHeight;
|
||||
}
|
||||
}
|
||||
public int Stride
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_stride;
|
||||
}
|
||||
}
|
||||
/// <summary> capture the next image </summary>
|
||||
public IntPtr GetBitMap()
|
||||
{
|
||||
if (m_handle == IntPtr.Zero)
|
||||
m_handle = Marshal.AllocCoTaskMem(m_stride * m_videoHeight);
|
||||
|
||||
try
|
||||
{
|
||||
// get ready to wait for new image
|
||||
m_PictureReady.Reset();
|
||||
m_bGotOne = false;
|
||||
|
||||
// If the graph hasn't been started, start it.
|
||||
Start();
|
||||
|
||||
// Start waiting
|
||||
if ( ! m_PictureReady.WaitOne(5000, false) )
|
||||
{
|
||||
throw new Exception("Timeout waiting to get picture");
|
||||
}
|
||||
//Pause(); //- we are effectivly pulling at 15 fps, so no need to pause
|
||||
}
|
||||
catch
|
||||
{
|
||||
Marshal.FreeCoTaskMem(m_handle);
|
||||
throw;
|
||||
}
|
||||
|
||||
// Got one
|
||||
return m_handle;
|
||||
}
|
||||
// Start the capture graph
|
||||
public void Start()
|
||||
{
|
||||
if (!m_bRunning)
|
||||
{
|
||||
int hr = m_mediaCtrl.Run();
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
m_bRunning = true;
|
||||
}
|
||||
}
|
||||
// Pause the capture graph.
|
||||
// Running the graph takes up a lot of resources. Pause it when it
|
||||
// isn't needed.
|
||||
public void Pause()
|
||||
{
|
||||
if (m_bRunning)
|
||||
{
|
||||
int hr = m_mediaCtrl.Pause();
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
m_bRunning = false;
|
||||
}
|
||||
}
|
||||
|
||||
public static List<string> getDevices()
|
||||
{
|
||||
List<string> list = new List<string>();
|
||||
DsDevice[] capDevices;
|
||||
|
||||
// Get the collection of video devices
|
||||
capDevices = DsDevice.GetDevicesOfCat(FilterCategory.VideoInputDevice);
|
||||
|
||||
foreach (DsDevice dev in capDevices)
|
||||
{
|
||||
list.Add(dev.Name);
|
||||
}
|
||||
|
||||
return list;
|
||||
}
|
||||
|
||||
// Internal capture
|
||||
private void _Capture(int iDeviceNum, int iFrameRate, int iWidth, int iHeight)
|
||||
{
|
||||
DsDevice[] capDevices;
|
||||
|
||||
// Get the collection of video devices
|
||||
capDevices = DsDevice.GetDevicesOfCat( FilterCategory.VideoInputDevice );
|
||||
|
||||
if (iDeviceNum + 1 > capDevices.Length)
|
||||
{
|
||||
throw new Exception("No video capture devices found at that index!");
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
// Set up the capture graph
|
||||
SetupGraph( capDevices[iDeviceNum], iFrameRate, iWidth, iHeight);
|
||||
|
||||
// tell the callback to ignore new images
|
||||
m_PictureReady = new ManualResetEvent(false);
|
||||
m_bGotOne = true;
|
||||
m_bRunning = false;
|
||||
|
||||
timer1.Interval = 1000 / 15; // 15 fps
|
||||
timer1.Tick += new EventHandler(timer1_Tick);
|
||||
timer1.Start();
|
||||
|
||||
}
|
||||
catch
|
||||
{
|
||||
Dispose();
|
||||
throw;
|
||||
}
|
||||
}
|
||||
|
||||
public bool showhud = true;
|
||||
|
||||
void timer1_Tick(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
ip = this.GetBitMap();
|
||||
image = new Bitmap(this.Width, this.Height, this.Stride, PixelFormat.Format24bppRgb, ip);
|
||||
image.RotateFlip(RotateFlipType.RotateNoneFlipY);
|
||||
if (camimage != null)
|
||||
{
|
||||
camimage(image);
|
||||
}
|
||||
}
|
||||
catch { Console.WriteLine("Grab bmp failed"); timer1.Enabled = false; this.CloseInterfaces(); System.Windows.Forms.MessageBox.Show("Problem with capture device, grabbing frame took longer than 5 sec"); }
|
||||
}
|
||||
|
||||
/// <summary> build the capture graph for grabber. </summary>
|
||||
private void SetupGraph(DsDevice dev, int iFrameRate, int iWidth, int iHeight)
|
||||
{
|
||||
int hr;
|
||||
|
||||
ISampleGrabber sampGrabber = null;
|
||||
IBaseFilter capFilter = null;
|
||||
ICaptureGraphBuilder2 capGraph = null;
|
||||
|
||||
// Get the graphbuilder object
|
||||
m_FilterGraph = (IFilterGraph2) new FilterGraph();
|
||||
m_mediaCtrl = m_FilterGraph as IMediaControl;
|
||||
try
|
||||
{
|
||||
// Get the ICaptureGraphBuilder2
|
||||
capGraph = (ICaptureGraphBuilder2) new CaptureGraphBuilder2();
|
||||
|
||||
// Get the SampleGrabber interface
|
||||
sampGrabber = (ISampleGrabber) new SampleGrabber();
|
||||
|
||||
// Start building the graph
|
||||
hr = capGraph.SetFiltergraph( m_FilterGraph );
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
// Add the video device
|
||||
hr = m_FilterGraph.AddSourceFilterForMoniker(dev.Mon, null, "Video input", out capFilter);
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
// add video crossbar
|
||||
// thanks to Andrew Fernie - this is to get tv tuner cards working
|
||||
IAMCrossbar crossbar = null;
|
||||
object o;
|
||||
|
||||
hr = capGraph.FindInterface(PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMCrossbar).GUID, out o);
|
||||
if (hr >= 0)
|
||||
{
|
||||
crossbar = (IAMCrossbar)o;
|
||||
int oPin, iPin;
|
||||
int ovLink, ivLink;
|
||||
ovLink = ivLink = 0;
|
||||
|
||||
crossbar.get_PinCounts(out oPin, out iPin);
|
||||
int pIdxRel;
|
||||
PhysicalConnectorType tp;
|
||||
for (int i = 0; i < iPin; i++)
|
||||
{
|
||||
crossbar.get_CrossbarPinInfo(true, i, out pIdxRel, out tp);
|
||||
if (tp == PhysicalConnectorType.Video_Composite) ivLink = i;
|
||||
}
|
||||
|
||||
for (int i = 0; i < oPin; i++)
|
||||
{
|
||||
crossbar.get_CrossbarPinInfo(false, i, out pIdxRel, out tp);
|
||||
if (tp == PhysicalConnectorType.Video_VideoDecoder) ovLink = i;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
crossbar.Route(ovLink, ivLink);
|
||||
o = null;
|
||||
}
|
||||
|
||||
catch
|
||||
{
|
||||
throw new Exception("Failed to get IAMCrossbar");
|
||||
}
|
||||
}
|
||||
|
||||
//add AVI Decompressor
|
||||
IBaseFilter pAVIDecompressor = (IBaseFilter)new AVIDec();
|
||||
hr = m_FilterGraph.AddFilter(pAVIDecompressor, "AVI Decompressor");
|
||||
DsError.ThrowExceptionForHR(hr);
|
||||
|
||||
//
|
||||
IBaseFilter baseGrabFlt = (IBaseFilter) sampGrabber;
|
||||
ConfigureSampleGrabber(sampGrabber);
|
||||
|
||||
// Add the frame grabber to the graph
|
||||
hr = m_FilterGraph.AddFilter( baseGrabFlt, "Ds.NET Grabber" );
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
// If any of the default config items are set
|
||||
if (iFrameRate + iHeight + iWidth > 0)
|
||||
{
|
||||
SetConfigParms(capGraph, capFilter, iFrameRate, iWidth, iHeight);
|
||||
}
|
||||
|
||||
hr = capGraph.RenderStream(PinCategory.Capture, MediaType.Video, capFilter, pAVIDecompressor, baseGrabFlt);
|
||||
if (hr < 0)
|
||||
{
|
||||
hr = capGraph.RenderStream(PinCategory.Capture, MediaType.Video, capFilter, null, baseGrabFlt);
|
||||
}
|
||||
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
SaveSizeInfo(sampGrabber);
|
||||
}
|
||||
finally
|
||||
{
|
||||
if (capFilter != null)
|
||||
{
|
||||
Marshal.ReleaseComObject(capFilter);
|
||||
capFilter = null;
|
||||
}
|
||||
if (sampGrabber != null)
|
||||
{
|
||||
Marshal.ReleaseComObject(sampGrabber);
|
||||
sampGrabber = null;
|
||||
}
|
||||
if (capGraph != null)
|
||||
{
|
||||
Marshal.ReleaseComObject(capGraph);
|
||||
capGraph = null;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void SaveSizeInfo(ISampleGrabber sampGrabber)
|
||||
{
|
||||
int hr;
|
||||
|
||||
// Get the media type from the SampleGrabber
|
||||
AMMediaType media = new AMMediaType();
|
||||
hr = sampGrabber.GetConnectedMediaType( media );
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
if( (media.formatType != FormatType.VideoInfo) || (media.formatPtr == IntPtr.Zero) )
|
||||
{
|
||||
throw new NotSupportedException( "Unknown Grabber Media Format" );
|
||||
}
|
||||
|
||||
// Grab the size info
|
||||
VideoInfoHeader videoInfoHeader = (VideoInfoHeader) Marshal.PtrToStructure( media.formatPtr, typeof(VideoInfoHeader) );
|
||||
m_videoWidth = videoInfoHeader.BmiHeader.Width;
|
||||
m_videoHeight = videoInfoHeader.BmiHeader.Height;
|
||||
m_stride = m_videoWidth * (videoInfoHeader.BmiHeader.BitCount / 8);
|
||||
|
||||
DsUtils.FreeAMMediaType(media);
|
||||
media = null;
|
||||
}
|
||||
private void ConfigureSampleGrabber(ISampleGrabber sampGrabber)
|
||||
{
|
||||
AMMediaType media;
|
||||
int hr;
|
||||
|
||||
// Set the media type to Video/RBG24
|
||||
media = new AMMediaType();
|
||||
media.majorType = MediaType.Video;
|
||||
media.subType = MediaSubType.RGB24;
|
||||
media.formatType = FormatType.VideoInfo;
|
||||
hr = sampGrabber.SetMediaType( media );
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
DsUtils.FreeAMMediaType(media);
|
||||
media = null;
|
||||
|
||||
// Configure the samplegrabber
|
||||
hr = sampGrabber.SetCallback( this, 1 );
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
}
|
||||
|
||||
// Set the Framerate, and video size
|
||||
private void SetConfigParms(ICaptureGraphBuilder2 capGraph, IBaseFilter capFilter, int iFrameRate, int iWidth, int iHeight)
|
||||
{
|
||||
int hr;
|
||||
object o;
|
||||
AMMediaType media;
|
||||
|
||||
// Find the stream config interface
|
||||
hr = capGraph.FindInterface(
|
||||
PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMStreamConfig).GUID, out o );
|
||||
|
||||
IAMStreamConfig videoStreamConfig = o as IAMStreamConfig;
|
||||
if (videoStreamConfig == null)
|
||||
{
|
||||
throw new Exception("Failed to get IAMStreamConfig");
|
||||
}
|
||||
|
||||
// Get the existing format block
|
||||
hr = videoStreamConfig.GetFormat( out media);
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
// copy out the videoinfoheader
|
||||
VideoInfoHeader v = new VideoInfoHeader();
|
||||
Marshal.PtrToStructure( media.formatPtr, v );
|
||||
|
||||
// if overriding the framerate, set the frame rate
|
||||
if (iFrameRate > 0)
|
||||
{
|
||||
v.AvgTimePerFrame = 10000000 / iFrameRate;
|
||||
}
|
||||
|
||||
// if overriding the width, set the width
|
||||
if (iWidth > 0)
|
||||
{
|
||||
v.BmiHeader.Width = iWidth;
|
||||
}
|
||||
|
||||
// if overriding the Height, set the Height
|
||||
if (iHeight > 0)
|
||||
{
|
||||
v.BmiHeader.Height = iHeight;
|
||||
}
|
||||
|
||||
// Copy the media structure back
|
||||
Marshal.StructureToPtr( v, media.formatPtr, false );
|
||||
|
||||
// Set the new format
|
||||
hr = videoStreamConfig.SetFormat( media );
|
||||
DsError.ThrowExceptionForHR( hr );
|
||||
|
||||
DsUtils.FreeAMMediaType(media);
|
||||
media = null;
|
||||
}
|
||||
|
||||
/// <summary> Shut down capture </summary>
|
||||
private void CloseInterfaces()
|
||||
{
|
||||
int hr;
|
||||
|
||||
try
|
||||
{
|
||||
if( m_mediaCtrl != null )
|
||||
{
|
||||
// Stop the graph
|
||||
hr = m_mediaCtrl.Stop();
|
||||
m_bRunning = false;
|
||||
}
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
Debug.WriteLine(ex);
|
||||
}
|
||||
|
||||
if (m_FilterGraph != null)
|
||||
{
|
||||
Marshal.ReleaseComObject(m_FilterGraph);
|
||||
m_FilterGraph = null;
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary> sample callback, NOT USED. </summary>
|
||||
int ISampleGrabberCB.SampleCB( double SampleTime, IMediaSample pSample )
|
||||
{
|
||||
if (!m_bGotOne)
|
||||
{
|
||||
// Set bGotOne to prevent further calls until we
|
||||
// request a new bitmap.
|
||||
m_bGotOne = true;
|
||||
IntPtr pBuffer;
|
||||
|
||||
pSample.GetPointer(out pBuffer);
|
||||
int iBufferLen = pSample.GetSize();
|
||||
|
||||
if (pSample.GetSize() > m_stride * m_videoHeight)
|
||||
{
|
||||
throw new Exception("Buffer is wrong size");
|
||||
}
|
||||
|
||||
CopyMemory(m_handle, pBuffer, m_stride * m_videoHeight);
|
||||
|
||||
// Picture is ready.
|
||||
m_PictureReady.Set();
|
||||
}
|
||||
|
||||
Marshal.ReleaseComObject(pSample);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/// <summary> buffer callback, COULD BE FROM FOREIGN THREAD. </summary>
|
||||
int ISampleGrabberCB.BufferCB( double SampleTime, IntPtr pBuffer, int BufferLen )
|
||||
{
|
||||
if (!m_bGotOne)
|
||||
{
|
||||
// The buffer should be long enought
|
||||
if(BufferLen <= m_stride * m_videoHeight)
|
||||
{
|
||||
// Copy the frame to the buffer
|
||||
CopyMemory(m_handle, pBuffer, m_stride * m_videoHeight);
|
||||
}
|
||||
else
|
||||
{
|
||||
throw new Exception("Buffer is wrong size");
|
||||
}
|
||||
|
||||
// Set bGotOne to prevent further calls until we
|
||||
// request a new bitmap.
|
||||
m_bGotOne = true;
|
||||
|
||||
// Picture is ready.
|
||||
m_PictureReady.Set();
|
||||
}
|
||||
else
|
||||
{
|
||||
m_Dropped++;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,844 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using AGaugeApp;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
using GMap.NET;
|
||||
using GMap.NET.WindowsForms;
|
||||
using GMap.NET.WindowsForms.Markers;
|
||||
|
||||
using System.Net;
|
||||
using System.Net.Sockets;
|
||||
using System.Xml; // config file
|
||||
using System.Runtime.InteropServices; // dll imports
|
||||
using ZedGraph; // Graphs
|
||||
using ArdupilotMega;
|
||||
using System.Reflection;
|
||||
|
||||
using System.IO;
|
||||
|
||||
using System.Drawing.Drawing2D;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
/// <summary>
|
||||
/// Struct as used in Ardupilot
|
||||
/// </summary>
|
||||
public struct Locationwp
|
||||
{
|
||||
public byte id; // command id
|
||||
public byte options; ///< options bitmask (1<<0 = relative altitude)
|
||||
public byte p1; // param 1
|
||||
public int lat; // Lattitude * 10**7
|
||||
public int lng; // Longitude * 10**7
|
||||
public int alt; // Altitude in centimeters (meters * 100)
|
||||
};
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// used to override the drawing of the waypoint box bounding
|
||||
/// </summary>
|
||||
public class GMapMarkerRect : GMapMarker
|
||||
{
|
||||
public Pen Pen;
|
||||
|
||||
public GMapMarker InnerMarker;
|
||||
|
||||
public int wprad = 0;
|
||||
public GMapControl MainMap;
|
||||
PointLatLng wpradposition;
|
||||
|
||||
public GMapMarkerRect(PointLatLng p)
|
||||
: base(p)
|
||||
{
|
||||
Pen = new Pen(Brushes.White, 2);
|
||||
|
||||
Pen.DashStyle = DashStyle.Dash;
|
||||
|
||||
// do not forget set Size of the marker
|
||||
// if so, you shall have no event on it ;}
|
||||
Size = new System.Drawing.Size(50, 50);
|
||||
Offset = new System.Drawing.Point(-Size.Width / 2, -Size.Height / 2 - 20);
|
||||
}
|
||||
|
||||
public override void OnRender(Graphics g)
|
||||
{
|
||||
base.OnRender(g);
|
||||
|
||||
if (wprad == 0 || MainMap == null)
|
||||
return;
|
||||
|
||||
if (Pen.Color == Color.Blue)
|
||||
Pen.Color = Color.White;
|
||||
|
||||
{
|
||||
double width = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Width, 0)) * 1000.0);
|
||||
double height = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Height, 0)) * 1000.0);
|
||||
double m2pixelwidth = MainMap.Width / width;
|
||||
double m2pixelheight = MainMap.Height / height;
|
||||
|
||||
wpradposition = MainMap.FromLocalToLatLng((int)(LocalPosition.X - (m2pixelwidth * wprad * 2)), LocalPosition.Y);
|
||||
}
|
||||
|
||||
Matrix temp = g.Transform;
|
||||
|
||||
GPoint loc = MainMap.FromLatLngToLocal(wpradposition);
|
||||
|
||||
g.DrawArc(Pen, new System.Drawing.Rectangle(LocalPosition.X - Offset.X - (Math.Abs(loc.X - LocalPosition.X) / 2), LocalPosition.Y - Offset.Y - Math.Abs(loc.X - LocalPosition.X) / 2, Math.Abs(loc.X - LocalPosition.X), Math.Abs(loc.X - LocalPosition.X)), 0, 360);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
public class GMapMarkerPlane : GMapMarker
|
||||
{
|
||||
const float rad2deg = (float)(180 / Math.PI);
|
||||
const float deg2rad = (float)(1.0 / rad2deg);
|
||||
|
||||
static readonly System.Drawing.Size SizeSt = new System.Drawing.Size(global::ArdupilotMega.Properties.Resources.planetracker.Width, global::ArdupilotMega.Properties.Resources.planetracker.Height);
|
||||
float heading = 0;
|
||||
float cog = -1;
|
||||
float target = -1;
|
||||
float nav_bearing = -1;
|
||||
|
||||
public GMapMarkerPlane(PointLatLng p, float heading, float cog, float nav_bearing,float target)
|
||||
: base(p)
|
||||
{
|
||||
this.heading = heading;
|
||||
this.cog = cog;
|
||||
this.target = target;
|
||||
this.nav_bearing = nav_bearing;
|
||||
Size = SizeSt;
|
||||
}
|
||||
|
||||
public override void OnRender(Graphics g)
|
||||
{
|
||||
Matrix temp = g.Transform;
|
||||
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
|
||||
|
||||
int length = 500;
|
||||
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length);
|
||||
|
||||
g.RotateTransform(heading);
|
||||
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.planetracker, global::ArdupilotMega.Properties.Resources.planetracker.Width / -2, global::ArdupilotMega.Properties.Resources.planetracker.Height / -2);
|
||||
|
||||
g.Transform = temp;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public class GMapMarkerQuad : GMapMarker
|
||||
{
|
||||
static readonly System.Drawing.Size SizeSt = new System.Drawing.Size(global::ArdupilotMega.Properties.Resources.quad2.Width, global::ArdupilotMega.Properties.Resources.quad2.Height);
|
||||
float heading = 0;
|
||||
float cog = -1;
|
||||
float target = -1;
|
||||
|
||||
public GMapMarkerQuad(PointLatLng p, float heading, float cog, float target)
|
||||
: base(p)
|
||||
{
|
||||
this.heading = heading;
|
||||
this.cog = cog;
|
||||
this.target = target;
|
||||
Size = SizeSt;
|
||||
}
|
||||
|
||||
public override void OnRender(Graphics g)
|
||||
{
|
||||
Matrix temp = g.Transform;
|
||||
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
|
||||
g.RotateTransform(heading);
|
||||
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quad2, global::ArdupilotMega.Properties.Resources.quad2.Width / -2, global::ArdupilotMega.Properties.Resources.quad2.Height / -2);
|
||||
|
||||
g.Transform = temp;
|
||||
}
|
||||
}
|
||||
|
||||
public class PointLatLngAlt
|
||||
{
|
||||
public double Lat = 0;
|
||||
public double Lng = 0;
|
||||
public double Alt = 0;
|
||||
public string Tag = "";
|
||||
|
||||
public PointLatLngAlt(double lat, double lng, double alt, string tag)
|
||||
{
|
||||
this.Lat = lat;
|
||||
this.Lng = lng;
|
||||
this.Alt = alt;
|
||||
this.Tag = tag;
|
||||
}
|
||||
|
||||
public PointLatLngAlt()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public PointLatLng Point()
|
||||
{
|
||||
return new PointLatLng(Lat, Lng);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Calc Distance in M
|
||||
/// </summary>
|
||||
/// <param name="p2"></param>
|
||||
/// <returns>Distance in M</returns>
|
||||
public double GetDistance(PointLatLngAlt p2)
|
||||
{
|
||||
double d = Lat * 0.017453292519943295;
|
||||
double num2 = Lng * 0.017453292519943295;
|
||||
double num3 = p2.Lat * 0.017453292519943295;
|
||||
double num4 = p2.Lng * 0.017453292519943295;
|
||||
double num5 = num4 - num2;
|
||||
double num6 = num3 - d;
|
||||
double num7 = Math.Pow(Math.Sin(num6 / 2.0), 2.0) + ((Math.Cos(d) * Math.Cos(num3)) * Math.Pow(Math.Sin(num5 / 2.0), 2.0));
|
||||
double num8 = 2.0 * Math.Atan2(Math.Sqrt(num7), Math.Sqrt(1.0 - num7));
|
||||
return (6378.137 * num8) * 1000; // M
|
||||
}
|
||||
}
|
||||
|
||||
public class Common
|
||||
{
|
||||
public enum distances
|
||||
{
|
||||
Meters,
|
||||
Feet
|
||||
}
|
||||
|
||||
public enum speeds
|
||||
{
|
||||
ms,
|
||||
fps,
|
||||
kph,
|
||||
mph,
|
||||
knots
|
||||
}
|
||||
|
||||
public enum apmmodes
|
||||
{
|
||||
MANUAL = 0,
|
||||
CIRCLE = 1,
|
||||
STABILIZE = 2,
|
||||
FLY_BY_WIRE_A = 5,
|
||||
FLY_BY_WIRE_B = 6,
|
||||
AUTO = 10,
|
||||
RTL = 11,
|
||||
LOITER = 12,
|
||||
GUIDED = 15
|
||||
}
|
||||
|
||||
public enum ac2modes
|
||||
{
|
||||
STABILIZE = 0, // hold level position
|
||||
ACRO = 1, // rate control
|
||||
SIMPLE = 2, //
|
||||
ALT_HOLD = 3, // AUTO control
|
||||
AUTO = 4, // AUTO control
|
||||
GUIDED = 5, // AUTO control
|
||||
LOITER = 6, // Hold a single location
|
||||
RTL = 7, // AUTO control
|
||||
CIRCLE = 8
|
||||
}
|
||||
|
||||
public static bool translateMode(string modein, ref MAVLink.__mavlink_set_nav_mode_t navmode, ref MAVLink.__mavlink_set_mode_t mode)
|
||||
{
|
||||
|
||||
//MAVLink.__mavlink_set_nav_mode_t navmode = new MAVLink.__mavlink_set_nav_mode_t();
|
||||
navmode.target = MainV2.comPort.sysid;
|
||||
navmode.nav_mode = 255;
|
||||
|
||||
//MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
|
||||
mode.target = MainV2.comPort.sysid;
|
||||
|
||||
try
|
||||
{
|
||||
if (Common.getModes() == typeof(Common.apmmodes))
|
||||
{
|
||||
switch ((int)Enum.Parse(Common.getModes(), modein))
|
||||
{
|
||||
case (int)Common.apmmodes.MANUAL:
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_MANUAL;
|
||||
break;
|
||||
case (int)Common.apmmodes.GUIDED:
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_GUIDED;
|
||||
break;
|
||||
case (int)Common.apmmodes.STABILIZE:
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST1;
|
||||
break;
|
||||
// AUTO MODES
|
||||
case (int)Common.apmmodes.AUTO:
|
||||
navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_WAYPOINT;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||
break;
|
||||
case (int)Common.apmmodes.RTL:
|
||||
navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_RETURNING;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||
break;
|
||||
case (int)Common.apmmodes.LOITER:
|
||||
navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_LOITER;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||
break;
|
||||
// FBW
|
||||
case (int)Common.apmmodes.FLY_BY_WIRE_A:
|
||||
navmode.nav_mode = (byte)1;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2;
|
||||
break;
|
||||
case (int)Common.apmmodes.FLY_BY_WIRE_B:
|
||||
navmode.nav_mode = (byte)2;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2;
|
||||
break;
|
||||
default:
|
||||
MessageBox.Show("No Mode Changed " + (int)Enum.Parse(Common.getModes(), modein));
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else if (Common.getModes() == typeof(Common.ac2modes))
|
||||
{
|
||||
switch ((int)Enum.Parse(Common.getModes(), modein))
|
||||
{
|
||||
case (int)Common.ac2modes.GUIDED:
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_GUIDED;
|
||||
break;
|
||||
case (int)Common.ac2modes.STABILIZE:
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_MANUAL;
|
||||
break;
|
||||
// AUTO MODES
|
||||
case (int)Common.ac2modes.AUTO:
|
||||
navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_WAYPOINT;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||
break;
|
||||
case (int)Common.ac2modes.RTL:
|
||||
navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_RETURNING;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||
break;
|
||||
case (int)Common.ac2modes.LOITER:
|
||||
navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_LOITER;
|
||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||
break;
|
||||
default:
|
||||
MessageBox.Show("No Mode Changed " + (int)Enum.Parse(Common.getModes(), modein));
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
catch { System.Windows.Forms.MessageBox.Show("Failed to find Mode"); return false; }
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
public static bool getFilefromNet(string url,string saveto) {
|
||||
try
|
||||
{
|
||||
// Create a request using a URL that can receive a post.
|
||||
WebRequest request = WebRequest.Create(url);
|
||||
request.Timeout = 5000;
|
||||
// Set the Method property of the request to POST.
|
||||
request.Method = "GET";
|
||||
// Get the response.
|
||||
WebResponse response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
if (((HttpWebResponse)response).StatusDescription != "200")
|
||||
return false;
|
||||
// Get the stream containing content returned by the server.
|
||||
Stream dataStream = response.GetResponseStream();
|
||||
|
||||
long bytes = response.ContentLength;
|
||||
long contlen = bytes;
|
||||
|
||||
byte[] buf1 = new byte[1024];
|
||||
|
||||
FileStream fs = new FileStream(saveto+".new", FileMode.Create);
|
||||
|
||||
DateTime dt = DateTime.Now;
|
||||
|
||||
while (dataStream.CanRead && bytes > 0)
|
||||
{
|
||||
Application.DoEvents();
|
||||
Console.WriteLine(saveto + " " + bytes);
|
||||
int len = dataStream.Read(buf1, 0, buf1.Length);
|
||||
bytes -= len;
|
||||
fs.Write(buf1, 0, len);
|
||||
}
|
||||
|
||||
fs.Close();
|
||||
dataStream.Close();
|
||||
response.Close();
|
||||
|
||||
File.Delete(saveto);
|
||||
File.Move(saveto + ".new", saveto);
|
||||
|
||||
return true;
|
||||
}
|
||||
catch { return false; }
|
||||
}
|
||||
|
||||
public static Type getModes()
|
||||
{
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega)
|
||||
{
|
||||
return typeof(apmmodes);
|
||||
}
|
||||
else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
|
||||
{
|
||||
return typeof(ac2modes);
|
||||
}
|
||||
|
||||
return null;
|
||||
}
|
||||
|
||||
public static Form LoadingBox(string title, string promptText)
|
||||
{
|
||||
Form form = new Form();
|
||||
System.Windows.Forms.Label label = new System.Windows.Forms.Label();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
|
||||
form.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
|
||||
form.Text = title;
|
||||
label.Text = promptText;
|
||||
|
||||
label.SetBounds(9, 50, 372, 13);
|
||||
|
||||
label.AutoSize = true;
|
||||
|
||||
form.ClientSize = new Size(396, 107);
|
||||
form.Controls.AddRange(new Control[] { label });
|
||||
form.ClientSize = new Size(Math.Max(300, label.Right + 10), form.ClientSize.Height);
|
||||
form.FormBorderStyle = FormBorderStyle.FixedDialog;
|
||||
form.StartPosition = FormStartPosition.CenterScreen;
|
||||
form.MinimizeBox = false;
|
||||
form.MaximizeBox = false;
|
||||
|
||||
MainV2.fixtheme(form);
|
||||
|
||||
form.Show();
|
||||
form.Refresh();
|
||||
label.Refresh();
|
||||
Application.DoEvents();
|
||||
return form;
|
||||
}
|
||||
|
||||
public static DialogResult MessageShowAgain(string title, string promptText)
|
||||
{
|
||||
Form form = new Form();
|
||||
System.Windows.Forms.Label label = new System.Windows.Forms.Label();
|
||||
CheckBox chk = new CheckBox();
|
||||
MyButton buttonOk = new MyButton();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
|
||||
form.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
|
||||
form.Text = title;
|
||||
label.Text = promptText;
|
||||
|
||||
chk.Tag = ("SHOWAGAIN_" + title.Replace(" ","_"));
|
||||
chk.AutoSize = true;
|
||||
chk.Text = "Show me again?";
|
||||
chk.Checked = true;
|
||||
chk.Location = new Point(9,80);
|
||||
|
||||
if (MainV2.config[(string)chk.Tag] != null && (string)MainV2.config[(string)chk.Tag] == "False") // skip it
|
||||
{
|
||||
form.Dispose();
|
||||
chk.Dispose();
|
||||
buttonOk.Dispose();
|
||||
label.Dispose();
|
||||
return DialogResult.OK;
|
||||
}
|
||||
|
||||
chk.CheckStateChanged += new EventHandler(chk_CheckStateChanged);
|
||||
|
||||
buttonOk.Text = "OK";
|
||||
buttonOk.DialogResult = DialogResult.OK;
|
||||
buttonOk.Location = new Point(form.Right - 100 ,80);
|
||||
|
||||
label.SetBounds(9, 40, 372, 13);
|
||||
|
||||
label.AutoSize = true;
|
||||
|
||||
form.ClientSize = new Size(396, 107);
|
||||
form.Controls.AddRange(new Control[] { label, chk, buttonOk });
|
||||
form.ClientSize = new Size(Math.Max(300, label.Right + 10), form.ClientSize.Height);
|
||||
form.FormBorderStyle = FormBorderStyle.FixedDialog;
|
||||
form.StartPosition = FormStartPosition.CenterScreen;
|
||||
form.MinimizeBox = false;
|
||||
form.MaximizeBox = false;
|
||||
|
||||
MainV2.fixtheme(form);
|
||||
|
||||
return form.ShowDialog();
|
||||
}
|
||||
|
||||
static void chk_CheckStateChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[(string)((CheckBox)(sender)).Tag] = ((CheckBox)(sender)).Checked.ToString();
|
||||
}
|
||||
|
||||
//from http://www.csharp-examples.net/inputbox/
|
||||
public static DialogResult InputBox(string title, string promptText, ref string value)
|
||||
{
|
||||
Form form = new Form();
|
||||
System.Windows.Forms.Label label = new System.Windows.Forms.Label();
|
||||
TextBox textBox = new TextBox();
|
||||
MyButton buttonOk = new MyButton();
|
||||
MyButton buttonCancel = new MyButton();
|
||||
|
||||
form.TopMost = true;
|
||||
|
||||
form.Text = title;
|
||||
label.Text = promptText;
|
||||
textBox.Text = value;
|
||||
|
||||
buttonOk.Text = "OK";
|
||||
buttonCancel.Text = "Cancel";
|
||||
buttonOk.DialogResult = DialogResult.OK;
|
||||
buttonCancel.DialogResult = DialogResult.Cancel;
|
||||
|
||||
label.SetBounds(9, 20, 372, 13);
|
||||
textBox.SetBounds(12, 36, 372, 20);
|
||||
buttonOk.SetBounds(228, 72, 75, 23);
|
||||
buttonCancel.SetBounds(309, 72, 75, 23);
|
||||
|
||||
label.AutoSize = true;
|
||||
textBox.Anchor = textBox.Anchor | AnchorStyles.Right;
|
||||
buttonOk.Anchor = AnchorStyles.Bottom | AnchorStyles.Right;
|
||||
buttonCancel.Anchor = AnchorStyles.Bottom | AnchorStyles.Right;
|
||||
|
||||
form.ClientSize = new Size(396, 107);
|
||||
form.Controls.AddRange(new Control[] { label, textBox, buttonOk, buttonCancel });
|
||||
form.ClientSize = new Size(Math.Max(300, label.Right + 10), form.ClientSize.Height);
|
||||
form.FormBorderStyle = FormBorderStyle.FixedDialog;
|
||||
form.StartPosition = FormStartPosition.CenterScreen;
|
||||
form.MinimizeBox = false;
|
||||
form.MaximizeBox = false;
|
||||
form.AcceptButton = buttonOk;
|
||||
form.CancelButton = buttonCancel;
|
||||
|
||||
MainV2.fixtheme(form);
|
||||
|
||||
DialogResult dialogResult = form.ShowDialog();
|
||||
if (dialogResult == DialogResult.OK)
|
||||
{
|
||||
value = textBox.Text;
|
||||
}
|
||||
return dialogResult;
|
||||
}
|
||||
|
||||
public static string speechConversion(string input)
|
||||
{
|
||||
if (MainV2.cs.wpno == 0)
|
||||
{
|
||||
input = input.Replace("{wpn}", "Home");
|
||||
}
|
||||
else
|
||||
{
|
||||
input = input.Replace("{wpn}", MainV2.cs.wpno.ToString());
|
||||
}
|
||||
|
||||
input = input.Replace("{asp}", MainV2.cs.airspeed.ToString("0"));
|
||||
|
||||
input = input.Replace("{alt}", MainV2.cs.alt.ToString("0"));
|
||||
|
||||
input = input.Replace("{wpa}", MainV2.cs.targetalt.ToString("0"));
|
||||
|
||||
input = input.Replace("{gsp}", MainV2.cs.groundspeed.ToString("0"));
|
||||
|
||||
input = input.Replace("{mode}", MainV2.cs.mode.ToString());
|
||||
|
||||
input = input.Replace("{batv}", MainV2.cs.battery_voltage.ToString("0.00"));
|
||||
|
||||
return input;
|
||||
}
|
||||
}
|
||||
|
||||
public class VerticalProgressBar : HorizontalProgressBar
|
||||
{
|
||||
protected override CreateParams CreateParams
|
||||
{
|
||||
get
|
||||
{
|
||||
CreateParams cp = base.CreateParams;
|
||||
cp.Style |= 0x04;
|
||||
return cp;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public class VerticalProgressBar2 : HorizontalProgressBar2
|
||||
{
|
||||
protected override void OnPaint(PaintEventArgs e)
|
||||
{
|
||||
e.Graphics.TranslateTransform(0, e.Graphics.ClipBounds.Height);
|
||||
e.Graphics.RotateTransform(270);
|
||||
e.Graphics.ScaleTransform((float)this.Height / (float)this.Width, (float)this.Width / (float)this.Height);
|
||||
base.OnPaint(e);
|
||||
}
|
||||
}
|
||||
|
||||
public class HorizontalProgressBar2 : BSE.Windows.Forms.ProgressBar
|
||||
{
|
||||
private string m_Text;
|
||||
int offset = 0;
|
||||
int _min = 0;
|
||||
int _max = 0;
|
||||
int _value = 0;
|
||||
System.Windows.Forms.Label lbl1 = new System.Windows.Forms.Label();
|
||||
System.Windows.Forms.Label lbl = new System.Windows.Forms.Label();
|
||||
|
||||
public HorizontalProgressBar2()
|
||||
: base()
|
||||
{
|
||||
}
|
||||
|
||||
public new int Value
|
||||
{
|
||||
get { return _value; }
|
||||
set
|
||||
{
|
||||
if (_value == value)
|
||||
return;
|
||||
_value = value;
|
||||
int ans = value + offset;
|
||||
if (ans <= base.Minimum)
|
||||
{
|
||||
ans = base.Minimum + 1; // prevent an exception for the -1 hack
|
||||
}
|
||||
else if (ans >= base.Maximum)
|
||||
{
|
||||
ans = base.Maximum;
|
||||
}
|
||||
|
||||
base.Value = ans;
|
||||
|
||||
if (this.DesignMode) return;
|
||||
|
||||
if (this.Parent != null)
|
||||
{
|
||||
this.Parent.Controls.Add(lbl);
|
||||
this.Parent.Controls.Add(lbl1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public new int Minimum
|
||||
{
|
||||
get { return _min; }
|
||||
set
|
||||
{
|
||||
_min = value;
|
||||
if (_min < 0)
|
||||
{
|
||||
base.Minimum = 0; offset = (_max - value) / 2; base.Maximum = _max - value;
|
||||
}
|
||||
else
|
||||
{
|
||||
base.Minimum = value;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public new int Maximum { get { return _max; } set { _max = value; base.Maximum = value; } }
|
||||
|
||||
[System.ComponentModel.Browsable(true),
|
||||
System.ComponentModel.Category("Mine"),
|
||||
System.ComponentModel.Description("Text under Bar")]
|
||||
public string Label
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_Text;
|
||||
}
|
||||
set
|
||||
{
|
||||
if (m_Text != value)
|
||||
{
|
||||
m_Text = value;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void drawlbl(Graphics e)
|
||||
{
|
||||
lbl.Location = new Point(this.Location.X, this.Location.Y + this.Height + 2);
|
||||
lbl.ClientSize = new Size(this.Width, 13);
|
||||
lbl.TextAlign = ContentAlignment.MiddleCenter;
|
||||
lbl.Text = m_Text;
|
||||
|
||||
lbl1.Location = new Point(this.Location.X, this.Location.Y + this.Height + 15);
|
||||
lbl1.ClientSize = new Size(this.Width, 13);
|
||||
lbl1.TextAlign = ContentAlignment.MiddleCenter;
|
||||
lbl1.Text = Value.ToString();
|
||||
|
||||
if (minline != 0 && maxline != 0)
|
||||
{
|
||||
float range = this.Maximum - this.Minimum;
|
||||
float range2 = this.Width;
|
||||
Pen redPen = new Pen(Color.Red, 2);
|
||||
|
||||
SolidBrush mybrush = new SolidBrush(Color.FromArgb(0x40, 0x57, 0x04));
|
||||
|
||||
if ((Type)this.GetType() == typeof(VerticalProgressBar2)) {
|
||||
e.ResetTransform();
|
||||
range2 = this.Height;
|
||||
e.DrawLine(redPen, 0, (this.Maximum - minline) / range * range2 + 0, this.Width, (this.Maximum - minline) / range * range2 + 0);
|
||||
e.DrawLine(redPen, 0, (this.Maximum - maxline) / range * range2 + 6, this.Width, (this.Maximum - maxline) / range * range2 + 6);
|
||||
e.DrawString(minline.ToString(), SystemFonts.DefaultFont, mybrush, 5, (this.Maximum - minline) / range * range2 + 2);
|
||||
e.DrawString(maxline.ToString(), SystemFonts.DefaultFont, Brushes.White, 5, (this.Maximum - maxline) / range * range2 - 10);
|
||||
} else {
|
||||
e.DrawLine(redPen, (minline - this.Minimum) / range * range2 - 0, 0, (minline - this.Minimum) / range * range2 - 0, this.Height);
|
||||
e.DrawLine(redPen, (maxline - this.Minimum) / range * range2 - 0, 0, (maxline - this.Minimum) / range * range2 - 0, this.Height);
|
||||
e.DrawString(minline.ToString(), SystemFonts.DefaultFont, mybrush, (minline - this.Minimum) / range * range2 - 30, 5);
|
||||
e.DrawString(maxline.ToString(), SystemFonts.DefaultFont, Brushes.White, (maxline - this.Minimum) / range * range2 - 0, 5);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public int minline { get; set; }
|
||||
public int maxline { get; set; }
|
||||
|
||||
protected override void OnPaint(PaintEventArgs e)
|
||||
{
|
||||
base.OnPaint(e);
|
||||
drawlbl(e.Graphics);
|
||||
}
|
||||
}
|
||||
|
||||
public class HorizontalProgressBar : ProgressBar
|
||||
{
|
||||
private string m_Text;
|
||||
int offset = 0;
|
||||
int _min = 0;
|
||||
int _max = 0;
|
||||
int _value = 0;
|
||||
System.Windows.Forms.Label lbl1 = new System.Windows.Forms.Label();
|
||||
System.Windows.Forms.Label lbl = new System.Windows.Forms.Label();
|
||||
|
||||
|
||||
public HorizontalProgressBar()
|
||||
: base()
|
||||
{
|
||||
drawlbl();
|
||||
//this.Parent.Controls.AddRange(new Control[] { lbl, lbl1 });
|
||||
}
|
||||
|
||||
public new int Value
|
||||
{
|
||||
get { return _value; }
|
||||
set
|
||||
{
|
||||
_value = value;
|
||||
int ans = value + offset;
|
||||
if (ans <= base.Minimum)
|
||||
{
|
||||
ans = base.Minimum + 1; // prevent an exception for the -1 hack
|
||||
}
|
||||
else if (ans >= base.Maximum)
|
||||
{
|
||||
ans = base.Maximum;
|
||||
}
|
||||
base.Value = ans;
|
||||
drawlbl();
|
||||
base.Value = ans - 1;
|
||||
drawlbl();
|
||||
base.Value = ans;
|
||||
drawlbl();
|
||||
}
|
||||
}
|
||||
|
||||
public new int Minimum
|
||||
{
|
||||
get { return _min; }
|
||||
set
|
||||
{
|
||||
_min = value;
|
||||
if (_min < 0)
|
||||
{
|
||||
base.Minimum = 0; offset = (_max - value) / 2; base.Maximum = _max - value;
|
||||
}
|
||||
else
|
||||
{
|
||||
base.Minimum = value;
|
||||
}
|
||||
|
||||
if (this.DesignMode) return;
|
||||
|
||||
if (this.Parent != null)
|
||||
{
|
||||
this.Parent.Controls.Add(lbl);
|
||||
this.Parent.Controls.Add(lbl1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public new int Maximum { get { return _max; } set { _max = value; base.Maximum = value; } }
|
||||
|
||||
[System.ComponentModel.Browsable(true),
|
||||
System.ComponentModel.Category("Mine"),
|
||||
System.ComponentModel.Description("Text under Bar")]
|
||||
public string Label
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_Text;
|
||||
}
|
||||
set
|
||||
{
|
||||
if (m_Text != value)
|
||||
{
|
||||
m_Text = value;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void drawlbl()
|
||||
{
|
||||
lbl.Location = new Point(this.Location.X, this.Location.Y + this.Height + 2);
|
||||
lbl.ClientSize = new Size(this.Width, 13);
|
||||
lbl.TextAlign = ContentAlignment.MiddleCenter;
|
||||
lbl.Text = m_Text;
|
||||
|
||||
lbl1.Location = new Point(this.Location.X, this.Location.Y + this.Height + 15);
|
||||
lbl1.ClientSize = new Size(this.Width, 13);
|
||||
lbl1.TextAlign = ContentAlignment.MiddleCenter;
|
||||
lbl1.Text = Value.ToString();
|
||||
|
||||
if (minline != 0 && maxline != 0)
|
||||
{
|
||||
float range = this.Maximum - this.Minimum;
|
||||
float range2 = this.Width;
|
||||
Graphics e = this.CreateGraphics();
|
||||
Pen redPen = new Pen(Color.Red, 2);
|
||||
|
||||
if ((Type)this.GetType() == typeof(VerticalProgressBar)) {
|
||||
range2 = this.Height;
|
||||
e.DrawLine(redPen, 0, (this.Maximum - minline) / range * range2 + 0, this.Width, (this.Maximum - minline) / range * range2 + 0);
|
||||
e.DrawLine(redPen, 0, (this.Maximum - maxline) / range * range2 + 0, this.Width, (this.Maximum - maxline) / range * range2 + 0);
|
||||
e.DrawString(minline.ToString(), SystemFonts.DefaultFont, Brushes.Black, 5, (this.Maximum - minline) / range * range2 + 2);
|
||||
e.DrawString(maxline.ToString(), SystemFonts.DefaultFont, Brushes.Black, 5, (this.Maximum - maxline) / range * range2 - 15);
|
||||
} else {
|
||||
e.DrawLine(redPen, (minline - this.Minimum) / range * range2 - 3, 0, (minline - this.Minimum) / range * range2 - 3, this.Height);
|
||||
e.DrawLine(redPen, (maxline - this.Minimum) / range * range2 - 3, 0, (maxline - this.Minimum) / range * range2 - 3, this.Height);
|
||||
e.DrawString(minline.ToString(), SystemFonts.DefaultFont, Brushes.Black, (minline - this.Minimum) / range * range2 - 35, 5);
|
||||
e.DrawString(maxline.ToString(), SystemFonts.DefaultFont, Brushes.Black, (maxline - this.Minimum) / range * range2 - 3, 5);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public int minline { get; set; }
|
||||
public int maxline { get; set; }
|
||||
|
||||
protected override void OnPaint(PaintEventArgs e)
|
||||
{
|
||||
base.OnPaint(e);
|
||||
drawlbl();
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,23 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public interface ICommsSerial
|
||||
{
|
||||
// from serialport class
|
||||
int BaudRate { get; set; }
|
||||
bool DtrEnable { get; set; }
|
||||
string PortName { get; set; }
|
||||
StopBits StopBits { get; set; }
|
||||
Parity Parity { get; set; }
|
||||
bool IsOpen { get; }
|
||||
void Open();
|
||||
void Open(bool getparams);
|
||||
void Close();
|
||||
int DataBits { get; set; }
|
||||
}
|
||||
}
|
|
@ -0,0 +1,57 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.IO;
|
||||
using System.Reflection;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public interface ICommsSerial
|
||||
{
|
||||
// from serialport class
|
||||
// Methods
|
||||
void Close();
|
||||
void DiscardInBuffer();
|
||||
//void DiscardOutBuffer();
|
||||
void Open();
|
||||
int Read(byte[] buffer, int offset, int count);
|
||||
//int Read(char[] buffer, int offset, int count);
|
||||
int ReadByte();
|
||||
int ReadChar();
|
||||
string ReadExisting();
|
||||
string ReadLine();
|
||||
//string ReadTo(string value);
|
||||
void Write(string text);
|
||||
void Write(byte[] buffer, int offset, int count);
|
||||
//void Write(char[] buffer, int offset, int count);
|
||||
void WriteLine(string text);
|
||||
|
||||
// Properties
|
||||
//Stream BaseStream { get; }
|
||||
int BaudRate { get; set; }
|
||||
//bool BreakState { get; set; }
|
||||
int BytesToRead { get; }
|
||||
//int BytesToWrite { get; }
|
||||
//bool CDHolding { get; }
|
||||
//bool CtsHolding { get; }
|
||||
int DataBits { get; set; }
|
||||
//bool DiscardNull { get; set; }
|
||||
//bool DsrHolding { get; }
|
||||
bool DtrEnable { get; set; }
|
||||
//Encoding Encoding { get; set; }
|
||||
//Handshake Handshake { get; set; }
|
||||
bool IsOpen { get; }
|
||||
//string NewLine { get; set; }
|
||||
Parity Parity { get; set; }
|
||||
//byte ParityReplace { get; set; }
|
||||
string PortName { get; set; }
|
||||
int ReadBufferSize { get; set; }
|
||||
int ReadTimeout { get; set; }
|
||||
int ReceivedBytesThreshold { get; set; }
|
||||
bool RtsEnable { get; set; }
|
||||
StopBits StopBits { get; set; }
|
||||
int WriteBufferSize { get; set; }
|
||||
int WriteTimeout { get; set; }
|
||||
}
|
||||
}
|
|
@ -0,0 +1,13 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
|
||||
{
|
||||
|
||||
}
|
||||
}
|
|
@ -0,0 +1,241 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
using System.Net; // dns, ip address
|
||||
using System.Net.Sockets; // tcplistner
|
||||
using SerialProxy;
|
||||
|
||||
namespace System.IO.Ports
|
||||
{
|
||||
public class UdpSerial : ArdupilotMega.ICommsSerial
|
||||
{
|
||||
UdpClient client = new UdpClient();
|
||||
IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
|
||||
byte[] rbuffer = new byte[0];
|
||||
int rbufferread = 0;
|
||||
|
||||
public int WriteBufferSize { get; set; }
|
||||
public int WriteTimeout { get; set; }
|
||||
public int ReceivedBytesThreshold { get; set; }
|
||||
public bool RtsEnable { get; set; }
|
||||
|
||||
~UdpSerial()
|
||||
{
|
||||
this.Close();
|
||||
client = null;
|
||||
}
|
||||
|
||||
public UdpSerial()
|
||||
{
|
||||
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
|
||||
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
|
||||
|
||||
Port = "14550";
|
||||
}
|
||||
|
||||
public string Port { get; set; }
|
||||
|
||||
public int ReadTimeout
|
||||
{
|
||||
get;// { return client.ReceiveTimeout; }
|
||||
set;// { client.ReceiveTimeout = value; }
|
||||
}
|
||||
|
||||
public int ReadBufferSize {get;set;}
|
||||
|
||||
public int BaudRate { get; set; }
|
||||
public StopBits StopBits { get; set; }
|
||||
public Parity Parity { get; set; }
|
||||
public int DataBits { get; set; }
|
||||
|
||||
public string PortName { get; set; }
|
||||
|
||||
public int BytesToRead
|
||||
{
|
||||
get { return client.Available + rbuffer.Length - rbufferread; }
|
||||
}
|
||||
|
||||
public bool IsOpen { get { return client.Client.Connected; } }
|
||||
|
||||
public bool DtrEnable
|
||||
{
|
||||
get;
|
||||
set;
|
||||
}
|
||||
|
||||
public void Open()
|
||||
{
|
||||
if (client.Client.Connected)
|
||||
{
|
||||
Console.WriteLine("udpserial socket already open");
|
||||
return;
|
||||
}
|
||||
|
||||
string dest = Port;
|
||||
ArdupilotMega.Common.InputBox("Listern Port", "Enter Local port (ensure remote end is already sending)", ref dest);
|
||||
Port = dest;
|
||||
|
||||
client = new UdpClient(int.Parse(Port));
|
||||
|
||||
try
|
||||
{
|
||||
client.Receive(ref RemoteIpEndPoint);
|
||||
Console.WriteLine("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
|
||||
client.Connect(RemoteIpEndPoint);
|
||||
}
|
||||
catch (Exception e) {
|
||||
if (client != null && client.Client.Connected) { client.Close(); }
|
||||
Console.WriteLine(e.ToString());
|
||||
System.Windows.Forms.MessageBox.Show("Please check your Firewall settings\nPlease try running this command\n1. Run the following command in an elevated command prompt to disable Windows Firewall temporarily:\n \nNetsh advfirewall set allprofiles state off\n \nNote: This is just for test; please turn it back on with the command 'Netsh advfirewall set allprofiles state on'.\n");
|
||||
throw new Exception("The socket/serialproxy is closed " + e);
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
void VerifyConnected()
|
||||
{
|
||||
if (client == null || !IsOpen)
|
||||
{
|
||||
throw new Exception("The socket/serialproxy is closed");
|
||||
}
|
||||
}
|
||||
|
||||
public int Read(byte[] readto,int offset,int length)
|
||||
{
|
||||
VerifyConnected();
|
||||
try
|
||||
{
|
||||
if (length < 1) { return 0; }
|
||||
|
||||
if (rbufferread == rbuffer.Length)
|
||||
{
|
||||
rbuffer = client.Receive(ref RemoteIpEndPoint);
|
||||
rbufferread = 0;
|
||||
}
|
||||
|
||||
Array.Copy(rbuffer, rbufferread, readto, offset, length);
|
||||
|
||||
rbufferread += length;
|
||||
|
||||
return length;
|
||||
}
|
||||
catch { throw new Exception("Socket Closed"); }
|
||||
}
|
||||
|
||||
public int ReadByte()
|
||||
{
|
||||
VerifyConnected();
|
||||
int count = 0;
|
||||
while (this.BytesToRead == 0)
|
||||
{
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (count > ReadTimeout)
|
||||
throw new Exception("NetSerial Timeout on read");
|
||||
count++;
|
||||
}
|
||||
byte[] buffer = new byte[1];
|
||||
Read(buffer, 0, 1);
|
||||
return buffer[0];
|
||||
}
|
||||
|
||||
public int ReadChar()
|
||||
{
|
||||
return ReadByte();
|
||||
}
|
||||
|
||||
public string ReadExisting()
|
||||
{
|
||||
VerifyConnected();
|
||||
byte[] data = new byte[client.Available];
|
||||
if (data.Length > 0)
|
||||
Read(data, 0, data.Length);
|
||||
|
||||
string line = Encoding.ASCII.GetString(data, 0, data.Length);
|
||||
|
||||
return line;
|
||||
}
|
||||
|
||||
public void WriteLine(string line)
|
||||
{
|
||||
VerifyConnected();
|
||||
line = line + "\n";
|
||||
Write(line);
|
||||
}
|
||||
|
||||
public void Write(string line)
|
||||
{
|
||||
VerifyConnected();
|
||||
byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
|
||||
Write(data, 0, data.Length);
|
||||
}
|
||||
|
||||
public void Write(byte[] write, int offset, int length)
|
||||
{
|
||||
VerifyConnected();
|
||||
try
|
||||
{
|
||||
client.Send(write, length);
|
||||
}
|
||||
catch { }//throw new Exception("Comport / Socket Closed"); }
|
||||
}
|
||||
|
||||
public void DiscardInBuffer()
|
||||
{
|
||||
VerifyConnected();
|
||||
int size = client.Available;
|
||||
byte[] crap = new byte[size];
|
||||
Console.WriteLine("UdpSerial DiscardInBuffer {0}",size);
|
||||
Read(crap, 0, size);
|
||||
}
|
||||
|
||||
public string ReadLine() {
|
||||
byte[] temp = new byte[4000];
|
||||
int count = 0;
|
||||
int timeout = 0;
|
||||
|
||||
while (timeout <= 100)
|
||||
{
|
||||
if (!this.IsOpen) { break; }
|
||||
if (this.BytesToRead > 0)
|
||||
{
|
||||
byte letter = (byte)this.ReadByte();
|
||||
|
||||
temp[count] = letter;
|
||||
|
||||
if (letter == '\n') // normal line
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
count++;
|
||||
if (count == temp.Length)
|
||||
break;
|
||||
timeout = 0;
|
||||
} else {
|
||||
timeout++;
|
||||
System.Threading.Thread.Sleep(5);
|
||||
}
|
||||
}
|
||||
|
||||
Array.Resize<byte>(ref temp, count + 1);
|
||||
|
||||
return Encoding.ASCII.GetString(temp, 0, temp.Length);
|
||||
}
|
||||
|
||||
public void Close()
|
||||
{
|
||||
if (client.Client.Connected)
|
||||
{
|
||||
client.Client.Close();
|
||||
client.Close();
|
||||
}
|
||||
|
||||
client = new UdpClient();
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,647 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.ComponentModel;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public class CurrentState: ICloneable
|
||||
{
|
||||
// multipliers
|
||||
public float multiplierdist = 1;
|
||||
public float multiplierspeed = 1;
|
||||
|
||||
// orientation - rads
|
||||
public float roll { get; set; }
|
||||
public float pitch { get; set; }
|
||||
public float yaw { get { return _yaw; } set { if (value < 0) { _yaw = value + 360; } else { _yaw = value; } } }
|
||||
private float _yaw = 0;
|
||||
|
||||
public float groundcourse { get { return _groundcourse; } set { if (value < 0) { _groundcourse = value + 360; } else { _groundcourse = value; } } }
|
||||
private float _groundcourse = 0;
|
||||
|
||||
// speeds
|
||||
public float airspeed { get { return _airspeed * multiplierspeed; } set { _airspeed = value; } }
|
||||
public float groundspeed { get { return _groundspeed * multiplierspeed; } set { _groundspeed = value; } }
|
||||
float _airspeed;
|
||||
float _groundspeed;
|
||||
float _verticalspeed;
|
||||
public float verticalspeed { get { return _verticalspeed; } set { _verticalspeed = _verticalspeed * 0.8f + value * 0.2f; } }
|
||||
public float wind_dir { get; set; }
|
||||
public float wind_vel { get; set; }
|
||||
/// <summary>
|
||||
/// used in wind calc
|
||||
/// </summary>
|
||||
double Wn_fgo;
|
||||
/// <summary>
|
||||
/// used for wind calc
|
||||
/// </summary>
|
||||
double We_fgo;
|
||||
|
||||
//(alt_now - alt_then)/(time_now-time_then)
|
||||
|
||||
// position
|
||||
public float lat { get; set; }
|
||||
public float lng { get; set; }
|
||||
public float alt { get { return (_alt - altoffsethome) * multiplierdist; } set { _alt = value; } }
|
||||
DateTime lastalt = DateTime.Now;
|
||||
float oldalt = 0;
|
||||
public float altoffsethome { get; set; }
|
||||
private float _alt = 0;
|
||||
public float gpsstatus { get; set; }
|
||||
public float gpshdop { get; set; }
|
||||
public float satcount { get; set; }
|
||||
|
||||
public float altd1000 { get { return (alt / 1000) % 10; } }
|
||||
public float altd100 { get { return (alt / 100) % 10; } }
|
||||
|
||||
// accel
|
||||
public float ax { get; set; }
|
||||
public float ay { get; set; }
|
||||
public float az { get; set; }
|
||||
// gyro
|
||||
public float gx { get; set; }
|
||||
public float gy { get; set; }
|
||||
public float gz { get; set; }
|
||||
|
||||
// calced turn rate
|
||||
public float turnrate { get { if (groundspeed == 0) return 0; return (roll * 9.8f) / groundspeed; } }
|
||||
|
||||
//radio
|
||||
public float ch1in { get; set; }
|
||||
public float ch2in { get; set; }
|
||||
public float ch3in { get; set; }
|
||||
public float ch4in { get; set; }
|
||||
public float ch5in { get; set; }
|
||||
public float ch6in { get; set; }
|
||||
public float ch7in { get; set; }
|
||||
public float ch8in { get; set; }
|
||||
|
||||
// motors
|
||||
public float ch1out { get; set; }
|
||||
public float ch2out { get; set; }
|
||||
public float ch3out { get; set; }
|
||||
public float ch4out { get; set; }
|
||||
public float ch5out { get; set; }
|
||||
public float ch6out { get; set; }
|
||||
public float ch7out { get; set; }
|
||||
public float ch8out { get; set; }
|
||||
public float ch3percent {
|
||||
get {
|
||||
try
|
||||
{
|
||||
return (int)((ch3out - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) / (float.Parse(MainV2.comPort.param["RC3_MAX"].ToString()) - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) * 100);
|
||||
}
|
||||
catch {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//nav state
|
||||
public float nav_roll { get; set; }
|
||||
public float nav_pitch { get; set; }
|
||||
public short nav_bearing { get; set; }
|
||||
public short target_bearing { get; set; }
|
||||
public ushort wp_dist { get { return (ushort)(_wpdist * multiplierdist); } set { _wpdist = value; } }
|
||||
public float alt_error { get { return _alt_error * multiplierdist; } set { _alt_error = value; } }
|
||||
public float ber_error { get { return (target_bearing - yaw); } set { } }
|
||||
public float aspd_error { get { return _aspd_error * multiplierspeed; } set { _aspd_error = value; } }
|
||||
public float xtrack_error { get; set; }
|
||||
public int wpno { get; set; }
|
||||
public string mode { get; set; }
|
||||
public float climbrate { get; set; }
|
||||
ushort _wpdist;
|
||||
float _aspd_error;
|
||||
float _alt_error;
|
||||
|
||||
public float targetaltd100 { get { return ((alt + alt_error) / 100) % 10; } }
|
||||
public float targetalt { get { return (float)Math.Round(alt + alt_error,0); } }
|
||||
|
||||
//airspeed_error = (airspeed_error - airspeed);
|
||||
public float targetairspeed { get { return (float)Math.Round(airspeed + aspd_error / 100,0); } }
|
||||
|
||||
|
||||
//message
|
||||
public List<string> messages { get; set; }
|
||||
public string message { get { return messages[messages.Count - 1]; } set { } }
|
||||
|
||||
//battery
|
||||
public float battery_voltage { get { return _battery_voltage; } set { _battery_voltage = value / 1000; } }
|
||||
private float _battery_voltage;
|
||||
public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; } }
|
||||
private float _battery_remaining;
|
||||
|
||||
// HIL
|
||||
public int hilch1 { get; set; }
|
||||
public int hilch2 { get; set; }
|
||||
public int hilch3 { get; set; }
|
||||
public int hilch4 { get; set; }
|
||||
|
||||
// rc override
|
||||
public ushort rcoverridech1 { get; set; }
|
||||
public ushort rcoverridech2 { get; set; }
|
||||
public ushort rcoverridech3 { get; set; }
|
||||
public ushort rcoverridech4 { get; set; }
|
||||
|
||||
// current firmware
|
||||
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPilotMega;
|
||||
public float freemem { get; set; }
|
||||
public float brklevel { get; set; }
|
||||
|
||||
// stats
|
||||
public ushort packetdrop { get; set; }
|
||||
|
||||
// requested stream rates
|
||||
public byte rateattitude { get; set; }
|
||||
public byte rateposition { get; set; }
|
||||
public byte ratestatus { get; set; }
|
||||
public byte ratesensors { get; set; }
|
||||
public byte raterc { get; set; }
|
||||
|
||||
// reference
|
||||
public DateTime datetime { get; set; }
|
||||
|
||||
public CurrentState()
|
||||
{
|
||||
mode = "";
|
||||
messages = new List<string>();
|
||||
rateattitude = 10;
|
||||
rateposition = 3;
|
||||
ratestatus = 1;
|
||||
ratesensors = 3;
|
||||
raterc = 3;
|
||||
}
|
||||
|
||||
const float rad2deg = (float)(180 / Math.PI);
|
||||
const float deg2rad = (float)(1.0 / rad2deg);
|
||||
|
||||
private DateTime lastupdate = DateTime.Now;
|
||||
|
||||
private DateTime lastwindcalc = DateTime.Now;
|
||||
|
||||
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs)
|
||||
{
|
||||
UpdateCurrentSettings(bs, false);
|
||||
}
|
||||
|
||||
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow)
|
||||
{
|
||||
if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz
|
||||
{
|
||||
lastupdate = DateTime.Now;
|
||||
|
||||
if (DateTime.Now.Second != lastwindcalc.Second)
|
||||
{
|
||||
lastwindcalc = DateTime.Now;
|
||||
dowindcalc();
|
||||
}
|
||||
|
||||
// Console.WriteLine("Updating CurrentState " + DateTime.Now.Millisecond);
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
|
||||
{
|
||||
|
||||
string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
|
||||
|
||||
int ind = logdata.IndexOf('\0');
|
||||
if (ind != -1)
|
||||
logdata = logdata.Substring(0, ind);
|
||||
if (messages.Count > 5)
|
||||
{
|
||||
messages.RemoveAt(0);
|
||||
}
|
||||
messages.Add(logdata + "\n");
|
||||
|
||||
MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] != null) // hil
|
||||
{
|
||||
var hil = new ArdupilotMega.MAVLink.__mavlink_rc_channels_scaled_t();
|
||||
|
||||
object temp = hil;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED], ref temp, 6);
|
||||
|
||||
hil = (MAVLink.__mavlink_rc_channels_scaled_t)(temp);
|
||||
|
||||
hilch1 = hil.chan1_scaled;
|
||||
hilch2 = hil.chan2_scaled;
|
||||
hilch3 = hil.chan3_scaled;
|
||||
hilch4 = hil.chan4_scaled;
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] != null)
|
||||
{
|
||||
MAVLink.__mavlink_nav_controller_output_t nav = new MAVLink.__mavlink_nav_controller_output_t();
|
||||
|
||||
object temp = nav;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT], ref temp, 6);
|
||||
|
||||
nav = (MAVLink.__mavlink_nav_controller_output_t)(temp);
|
||||
|
||||
nav_roll = nav.nav_roll;
|
||||
nav_pitch = nav.nav_pitch;
|
||||
nav_bearing = nav.nav_bearing;
|
||||
target_bearing = nav.target_bearing;
|
||||
wp_dist = nav.wp_dist;
|
||||
alt_error = nav.alt_error;
|
||||
aspd_error = nav.aspd_error;
|
||||
xtrack_error = nav.xtrack_error;
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] != null)
|
||||
{
|
||||
ArdupilotMega.MAVLink.__mavlink_sys_status_t sysstatus = new ArdupilotMega.MAVLink.__mavlink_sys_status_t();
|
||||
|
||||
object temp = sysstatus;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS], ref temp, 6);
|
||||
|
||||
sysstatus = (ArdupilotMega.MAVLink.__mavlink_sys_status_t)(temp);
|
||||
|
||||
string oldmode = mode;
|
||||
|
||||
switch (sysstatus.mode)
|
||||
{
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_UNINIT:
|
||||
switch (sysstatus.nav_mode)
|
||||
{
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_GROUNDED:
|
||||
mode = "Initialising";
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case (byte)100:
|
||||
mode = "Stabilize";
|
||||
break;
|
||||
case (byte)101:
|
||||
mode = "Acro";
|
||||
break;
|
||||
case (byte)102:
|
||||
mode = "Simple";
|
||||
break;
|
||||
case (byte)103:
|
||||
mode = "Alt Hold";
|
||||
break;
|
||||
case (byte)104:
|
||||
mode = "Auto";
|
||||
break;
|
||||
case (byte)105:
|
||||
mode = "Guided";
|
||||
break;
|
||||
case (byte)106:
|
||||
mode = "Loiter";
|
||||
break;
|
||||
case (byte)107:
|
||||
mode = "RTL";
|
||||
break;
|
||||
case (byte)108:
|
||||
mode = "Circle";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_MANUAL:
|
||||
mode = "Manual";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_GUIDED:
|
||||
mode = "Guided";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_TEST1:
|
||||
mode = "Stabilize";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_TEST2:
|
||||
mode = "FBW A"; // fall though old
|
||||
switch (sysstatus.nav_mode)
|
||||
{
|
||||
case (byte)1:
|
||||
mode = "FBW A";
|
||||
break;
|
||||
case (byte)2:
|
||||
mode = "FBW B";
|
||||
break;
|
||||
case (byte)3:
|
||||
mode = "FBW C";
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_TEST3:
|
||||
mode = "FBW B";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_AUTO:
|
||||
switch (sysstatus.nav_mode)
|
||||
{
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_WAYPOINT:
|
||||
mode = "Auto";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_RETURNING:
|
||||
mode = "RTL";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_HOLD:
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_LOITER:
|
||||
mode = "Loiter";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_LIFTOFF:
|
||||
mode = "Takeoff";
|
||||
break;
|
||||
case (byte)ArdupilotMega.MAVLink.MAV_NAV.MAV_NAV_LANDING:
|
||||
mode = "Land";
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
default:
|
||||
mode = "Unknown";
|
||||
break;
|
||||
}
|
||||
|
||||
battery_voltage = sysstatus.vbat;
|
||||
battery_remaining = sysstatus.battery_remaining;
|
||||
|
||||
packetdrop = sysstatus.packet_drop;
|
||||
|
||||
if (oldmode != mode && MainV2.speechenable && MainV2.getConfig("speechmodeenabled") == "True")
|
||||
{
|
||||
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
|
||||
}
|
||||
|
||||
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null)
|
||||
{
|
||||
var att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
|
||||
|
||||
object temp = att;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE], ref temp, 6);
|
||||
|
||||
att = (MAVLink.__mavlink_attitude_t)(temp);
|
||||
|
||||
roll = att.roll * rad2deg;
|
||||
pitch = att.pitch * rad2deg;
|
||||
yaw = att.yaw * rad2deg;
|
||||
|
||||
// Console.WriteLine(roll + " " + pitch + " " + yaw);
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] != null)
|
||||
{
|
||||
var gps = new MAVLink.__mavlink_gps_raw_t();
|
||||
|
||||
object temp = gps;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW], ref temp, 6);
|
||||
|
||||
gps = (MAVLink.__mavlink_gps_raw_t)(temp);
|
||||
|
||||
lat = gps.lat;
|
||||
lng = gps.lon;
|
||||
// alt = gps.alt; // using vfr as includes baro calc
|
||||
|
||||
gpsstatus = gps.fix_type;
|
||||
// Console.WriteLine("gpsfix {0}",gpsstatus);
|
||||
|
||||
gpshdop = gps.eph;
|
||||
|
||||
groundspeed = gps.v;
|
||||
groundcourse = gps.hdg;
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS] != null)
|
||||
{
|
||||
var gps = new MAVLink.__mavlink_gps_status_t();
|
||||
|
||||
object temp = gps;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS], ref temp, 6);
|
||||
|
||||
gps = (MAVLink.__mavlink_gps_status_t)(temp);
|
||||
|
||||
satcount = gps.satellites_visible;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT] != null)
|
||||
{
|
||||
var loc = new MAVLink.__mavlink_global_position_int_t();
|
||||
|
||||
object temp = loc;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT], ref temp, 6);
|
||||
|
||||
loc = (MAVLink.__mavlink_global_position_int_t)(temp);
|
||||
|
||||
alt = loc.alt / 1000.0f;
|
||||
lat = loc.lat / 10000000.0f;
|
||||
lng = loc.lon / 10000000.0f;
|
||||
|
||||
}
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION] != null)
|
||||
{
|
||||
var loc = new MAVLink.__mavlink_global_position_t();
|
||||
|
||||
object temp = loc;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION], ref temp, 6);
|
||||
|
||||
loc = (MAVLink.__mavlink_global_position_t)(temp);
|
||||
|
||||
alt = loc.alt;
|
||||
lat = loc.lat;
|
||||
lng = loc.lon;
|
||||
|
||||
}
|
||||
if (MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] != null)
|
||||
{
|
||||
ArdupilotMega.MAVLink.__mavlink_waypoint_current_t wpcur = new ArdupilotMega.MAVLink.__mavlink_waypoint_current_t();
|
||||
|
||||
object temp = wpcur;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT], ref temp, 6);
|
||||
|
||||
wpcur = (ArdupilotMega.MAVLink.__mavlink_waypoint_current_t)(temp);
|
||||
|
||||
int oldwp = wpno;
|
||||
|
||||
wpno = wpcur.seq;
|
||||
|
||||
if (oldwp != wpno && MainV2.speechenable && MainV2.getConfig("speechwaypointenabled") == "True")
|
||||
{
|
||||
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
|
||||
}
|
||||
|
||||
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] != null)
|
||||
{
|
||||
var rcin = new MAVLink.__mavlink_rc_channels_raw_t();
|
||||
|
||||
object temp = rcin;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW], ref temp, 6);
|
||||
|
||||
rcin = (MAVLink.__mavlink_rc_channels_raw_t)(temp);
|
||||
|
||||
ch1in = rcin.chan1_raw;
|
||||
ch2in = rcin.chan2_raw;
|
||||
ch3in = rcin.chan3_raw;
|
||||
ch4in = rcin.chan4_raw;
|
||||
ch5in = rcin.chan5_raw;
|
||||
ch6in = rcin.chan6_raw;
|
||||
ch7in = rcin.chan7_raw;
|
||||
ch8in = rcin.chan8_raw;
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] != null)
|
||||
{
|
||||
var servoout = new MAVLink.__mavlink_servo_output_raw_t();
|
||||
|
||||
object temp = servoout;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW], ref temp, 6);
|
||||
|
||||
servoout = (MAVLink.__mavlink_servo_output_raw_t)(temp);
|
||||
|
||||
ch1out = servoout.servo1_raw;
|
||||
ch2out = servoout.servo2_raw;
|
||||
ch3out = servoout.servo3_raw;
|
||||
ch4out = servoout.servo4_raw;
|
||||
ch5out = servoout.servo5_raw;
|
||||
ch6out = servoout.servo6_raw;
|
||||
ch7out = servoout.servo7_raw;
|
||||
ch8out = servoout.servo8_raw;
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] != null)
|
||||
{
|
||||
var imu = new MAVLink.__mavlink_raw_imu_t();
|
||||
|
||||
object temp = imu;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU], ref temp, 6);
|
||||
|
||||
imu = (MAVLink.__mavlink_raw_imu_t)(temp);
|
||||
|
||||
gx = imu.xgyro;
|
||||
gy = imu.ygyro;
|
||||
gz = imu.zgyro;
|
||||
|
||||
ax = imu.xacc;
|
||||
ay = imu.yacc;
|
||||
az = imu.zacc;
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null)
|
||||
{
|
||||
MAVLink.__mavlink_vfr_hud_t vfr = new MAVLink.__mavlink_vfr_hud_t();
|
||||
|
||||
object temp = vfr;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD], ref temp, 6);
|
||||
|
||||
vfr = (MAVLink.__mavlink_vfr_hud_t)(temp);
|
||||
|
||||
groundspeed = vfr.groundspeed;
|
||||
airspeed = vfr.airspeed;
|
||||
|
||||
alt = vfr.alt; // this might include baro
|
||||
|
||||
//climbrate = vfr.climb;
|
||||
|
||||
if ((DateTime.Now - lastalt).TotalSeconds >= 0.1 && oldalt != alt)
|
||||
{
|
||||
climbrate = (alt - oldalt) / (float)(DateTime.Now - lastalt).TotalSeconds;
|
||||
verticalspeed = (alt - oldalt) / (float)(DateTime.Now - lastalt).TotalSeconds;
|
||||
if (float.IsInfinity(_verticalspeed))
|
||||
_verticalspeed = 0;
|
||||
lastalt = DateTime.Now;
|
||||
oldalt = alt;
|
||||
}
|
||||
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] = null;
|
||||
}
|
||||
|
||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO] != null) // hil
|
||||
{
|
||||
var mem = new ArdupilotMega.MAVLink.__mavlink_meminfo_t();
|
||||
|
||||
object temp = mem;
|
||||
|
||||
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO], ref temp, 6);
|
||||
|
||||
mem = (MAVLink.__mavlink_meminfo_t)(temp);
|
||||
|
||||
freemem = mem.freemem;
|
||||
brklevel = mem.brkval;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
//Console.WriteLine(DateTime.Now.Millisecond + " start ");
|
||||
// update form
|
||||
try
|
||||
{
|
||||
if (bs != null)
|
||||
{
|
||||
//Console.WriteLine(DateTime.Now.Millisecond);
|
||||
bs.DataSource = this;
|
||||
//Console.WriteLine(DateTime.Now.Millisecond + " 1 " + updatenow);
|
||||
bs.ResetBindings(false);
|
||||
//Console.WriteLine(DateTime.Now.Millisecond + " done ");
|
||||
}
|
||||
}
|
||||
catch { Console.WriteLine("CurrentState Binding error"); }
|
||||
}
|
||||
|
||||
public object Clone()
|
||||
{
|
||||
return this.MemberwiseClone();
|
||||
}
|
||||
|
||||
public void dowindcalc()
|
||||
{
|
||||
//Wind Fixed gain Observer
|
||||
//Ryan Beall
|
||||
//8FEB10
|
||||
|
||||
double Kw = 0.010; // 0.01 // 0.10
|
||||
|
||||
if (airspeed < 1 || groundspeed < 1)
|
||||
return;
|
||||
|
||||
double Wn_error = airspeed * Math.Cos((yaw) * deg2rad) * Math.Cos(pitch * deg2rad) - groundspeed * Math.Cos((groundcourse) * deg2rad) - Wn_fgo;
|
||||
double We_error = airspeed * Math.Sin((yaw) * deg2rad) * Math.Cos(pitch * deg2rad) - groundspeed * Math.Sin((groundcourse) * deg2rad) - We_fgo;
|
||||
|
||||
Wn_fgo = Wn_fgo + Kw * Wn_error;
|
||||
We_fgo = We_fgo + Kw * We_error;
|
||||
|
||||
double wind_dir = (Math.Atan2(We_fgo, Wn_fgo) * (180 / Math.PI));
|
||||
double wind_vel = (Math.Sqrt(Math.Pow(We_fgo,2) + Math.Pow(Wn_fgo,2)));
|
||||
|
||||
wind_dir = (wind_dir + 360) % 360;
|
||||
|
||||
this.wind_dir = (float)wind_dir;// (float)(wind_dir * 0.5 + this.wind_dir * 0.5);
|
||||
this.wind_vel = (float)wind_vel;// (float)(wind_vel * 0.5 + this.wind_vel * 0.5);
|
||||
|
||||
//Console.WriteLine("Wn_error = {0}\nWe_error = {1}\nWn_fgo = {2}\nWe_fgo = {3}\nWind_dir = {4}\nWind_vel = {5}\n",Wn_error,We_error,Wn_fgo,We_fgo,wind_dir,wind_vel);
|
||||
|
||||
//Console.WriteLine("wind_dir: {0} wind_vel: {1} as {4} yaw {5} pitch {6} gs {7} cog {8}", wind_dir, wind_vel, Wn_fgo, We_fgo , airspeed,yaw,pitch,groundspeed,groundcourse);
|
||||
|
||||
//low pass the outputs for better results!
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,84 @@
|
|||
namespace ArdupilotMega
|
||||
{
|
||||
partial class ElevationProfile
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Windows Form Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.zg1 = new ZedGraph.ZedGraphControl();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// zg1
|
||||
//
|
||||
this.zg1.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
|
||||
| System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.zg1.Location = new System.Drawing.Point(12, 23);
|
||||
this.zg1.Name = "zg1";
|
||||
this.zg1.ScrollGrace = 0D;
|
||||
this.zg1.ScrollMaxX = 0D;
|
||||
this.zg1.ScrollMaxY = 0D;
|
||||
this.zg1.ScrollMaxY2 = 0D;
|
||||
this.zg1.ScrollMinX = 0D;
|
||||
this.zg1.ScrollMinY = 0D;
|
||||
this.zg1.ScrollMinY2 = 0D;
|
||||
this.zg1.Size = new System.Drawing.Size(810, 427);
|
||||
this.zg1.TabIndex = 30;
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(162, 7);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(507, 13);
|
||||
this.label1.TabIndex = 31;
|
||||
this.label1.Text = "NOTE: The ground height data is pulled from Google Earth at 100m intervals. You u" +
|
||||
"se this at your own risk";
|
||||
//
|
||||
// ElevationProfile
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40)))));
|
||||
this.ClientSize = new System.Drawing.Size(834, 462);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.zg1);
|
||||
this.ForeColor = System.Drawing.Color.White;
|
||||
this.Name = "ElevationProfile";
|
||||
this.Text = "ElevationProfile";
|
||||
this.Load += new System.EventHandler(this.ElevationProfile_Load);
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private ZedGraph.ZedGraphControl zg1;
|
||||
private System.Windows.Forms.Label label1;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,217 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ZedGraph;
|
||||
using GMap.NET;
|
||||
using System.Xml; // GE xml alt reader
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class ElevationProfile : Form
|
||||
{
|
||||
List<PointLatLngAlt> gelocs = new List<PointLatLngAlt>();
|
||||
List<PointLatLngAlt> planlocs = new List<PointLatLngAlt>();
|
||||
PointPairList list1 = new PointPairList();
|
||||
PointPairList list2 = new PointPairList();
|
||||
int distance = 0;
|
||||
double homealt = 0;
|
||||
|
||||
public ElevationProfile(List<PointLatLngAlt> locs, double homealt)
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
planlocs = locs;
|
||||
|
||||
if (planlocs.Count <= 1)
|
||||
{
|
||||
MessageBox.Show("Please plan something first");
|
||||
return;
|
||||
}
|
||||
|
||||
// get total distance
|
||||
distance = 0;
|
||||
PointLatLngAlt lastloc = null;
|
||||
foreach (PointLatLngAlt loc in planlocs)
|
||||
{
|
||||
if (lastloc != null) {
|
||||
distance += (int)loc.GetDistance(lastloc);
|
||||
}
|
||||
lastloc = loc;
|
||||
}
|
||||
|
||||
this.homealt = homealt / MainV2.cs.multiplierdist;
|
||||
|
||||
Form frm = Common.LoadingBox("Loading", "Downloading Google Earth Data");
|
||||
|
||||
gelocs = getGEAltPath(planlocs);
|
||||
|
||||
frm.Close();
|
||||
}
|
||||
|
||||
private void ElevationProfile_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (planlocs.Count <= 1)
|
||||
{
|
||||
this.Close();
|
||||
return;
|
||||
}
|
||||
// GE plot
|
||||
double a = 0;
|
||||
double increment = (distance / (gelocs.Count - 1));
|
||||
|
||||
foreach (PointLatLngAlt geloc in gelocs)
|
||||
{
|
||||
list2.Add(a,geloc.Alt);
|
||||
|
||||
Console.WriteLine(geloc.Lng + "," + geloc.Lat + "," + geloc.Alt);
|
||||
|
||||
a+=increment;
|
||||
}
|
||||
// Planner Plot
|
||||
a=0;
|
||||
int count = 0;
|
||||
PointLatLngAlt lastloc = null;
|
||||
foreach (PointLatLngAlt planloc in planlocs)
|
||||
{
|
||||
if (lastloc != null)
|
||||
{
|
||||
a += planloc.GetDistance(lastloc);
|
||||
}
|
||||
|
||||
list1.Add(a, planloc.Alt / MainV2.cs.multiplierdist, 0, planloc.Tag); // homealt
|
||||
|
||||
lastloc = planloc;
|
||||
count++;
|
||||
}
|
||||
// draw graph
|
||||
CreateChart(zg1);
|
||||
}
|
||||
|
||||
List<PointLatLngAlt> getGEAltPath(List<PointLatLngAlt> list)
|
||||
{
|
||||
double alt = 0;
|
||||
double lat = 0;
|
||||
double lng = 0;
|
||||
|
||||
int pos = 0;
|
||||
|
||||
List<PointLatLngAlt> answer = new List<PointLatLngAlt>();
|
||||
|
||||
//http://code.google.com/apis/maps/documentation/elevation/
|
||||
//http://maps.google.com/maps/api/elevation/xml
|
||||
string coords = "";
|
||||
|
||||
foreach (PointLatLngAlt loc in list)
|
||||
{
|
||||
coords = coords + loc.Lat.ToString(new System.Globalization.CultureInfo("en-US")) + "," + loc.Lng.ToString(new System.Globalization.CultureInfo("en-US")) + "|";
|
||||
}
|
||||
coords = coords.Remove(coords.Length - 1);
|
||||
|
||||
if (list.Count <= 2 || coords.Length > (2048 - 256) || distance > 50000)
|
||||
{
|
||||
MessageBox.Show("To many/few WP's or to Big a Distance " + (distance/1000) + "km");
|
||||
return answer;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
using (XmlTextReader xmlreader = new XmlTextReader("http://maps.google.com/maps/api/elevation/xml?path=" + coords + "&samples=" + (distance / 100).ToString(new System.Globalization.CultureInfo("en-US")) + "&sensor=false"))
|
||||
{
|
||||
while (xmlreader.Read())
|
||||
{
|
||||
xmlreader.MoveToElement();
|
||||
switch (xmlreader.Name)
|
||||
{
|
||||
case "elevation":
|
||||
alt = double.Parse(xmlreader.ReadString(), new System.Globalization.CultureInfo("en-US"));
|
||||
Console.WriteLine("DO it " + lat + " " + lng + " " + alt);
|
||||
PointLatLngAlt loc = new PointLatLngAlt(lat,lng,alt,"");
|
||||
answer.Add(loc);
|
||||
pos++;
|
||||
break;
|
||||
case "lat":
|
||||
lat = double.Parse(xmlreader.ReadString(), new System.Globalization.CultureInfo("en-US"));
|
||||
break;
|
||||
case "lng":
|
||||
lng = double.Parse(xmlreader.ReadString(), new System.Globalization.CultureInfo("en-US"));
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
catch { MessageBox.Show("Error getting GE data"); }
|
||||
|
||||
return answer;
|
||||
}
|
||||
|
||||
public void CreateChart(ZedGraphControl zgc)
|
||||
{
|
||||
GraphPane myPane = zgc.GraphPane;
|
||||
|
||||
// Set the titles and axis labels
|
||||
myPane.Title.Text = "Elevation above ground";
|
||||
myPane.XAxis.Title.Text = "Distance (m)";
|
||||
myPane.YAxis.Title.Text = "Elevation (m)";
|
||||
|
||||
LineItem myCurve;
|
||||
|
||||
myCurve = myPane.AddCurve("Planner", list1, Color.Red, SymbolType.None);
|
||||
myCurve = myPane.AddCurve("GE", list2, Color.Green, SymbolType.None);
|
||||
|
||||
foreach (PointPair pp in list1)
|
||||
{
|
||||
// Add a another text item to to point out a graph feature
|
||||
TextObj text = new TextObj((string)pp.Tag, pp.X, pp.Y);
|
||||
// rotate the text 90 degrees
|
||||
text.FontSpec.Angle = 90;
|
||||
text.FontSpec.FontColor = Color.White;
|
||||
// Align the text such that the Right-Center is at (700, 50) in user scale coordinates
|
||||
text.Location.AlignH = AlignH.Right;
|
||||
text.Location.AlignV = AlignV.Center;
|
||||
// Disable the border and background fill options for the text
|
||||
text.FontSpec.Fill.IsVisible = false;
|
||||
text.FontSpec.Border.IsVisible = false;
|
||||
myPane.GraphObjList.Add(text);
|
||||
}
|
||||
|
||||
// Show the x axis grid
|
||||
myPane.XAxis.MajorGrid.IsVisible = true;
|
||||
|
||||
myPane.XAxis.Scale.Min = 0;
|
||||
myPane.XAxis.Scale.Max = distance;
|
||||
|
||||
// Make the Y axis scale red
|
||||
myPane.YAxis.Scale.FontSpec.FontColor = Color.Red;
|
||||
myPane.YAxis.Title.FontSpec.FontColor = Color.Red;
|
||||
// turn off the opposite tics so the Y tics don't show up on the Y2 axis
|
||||
myPane.YAxis.MajorTic.IsOpposite = false;
|
||||
myPane.YAxis.MinorTic.IsOpposite = false;
|
||||
// Don't display the Y zero line
|
||||
myPane.YAxis.MajorGrid.IsZeroLine = true;
|
||||
// Align the Y axis labels so they are flush to the axis
|
||||
myPane.YAxis.Scale.Align = AlignP.Inside;
|
||||
// Manually set the axis range
|
||||
//myPane.YAxis.Scale.Min = -1;
|
||||
//myPane.YAxis.Scale.Max = 1;
|
||||
|
||||
// Fill the axis background with a gradient
|
||||
//myPane.Chart.Fill = new Fill(Color.White, Color.LightGray, 45.0f);
|
||||
|
||||
// Calculate the Axis Scale Ranges
|
||||
try
|
||||
{
|
||||
zg1.AxisChange();
|
||||
}
|
||||
catch { }
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,120 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
|
@ -0,0 +1,400 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:68:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde: In function 'void init_compass()':
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:458: warning: unused variable 'junkbool'
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_roll' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:433: warning: 'temp' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde: At global scope:
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1494: warning: 'void tuning()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1586: warning: 'void point_at_home_yaw()' defined but not used
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:135: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:127: warning: 'void decrement_WP_index()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:148: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:429: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:40: warning: 'void update_servo_switches()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:49: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:232: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:194: warning: 'void calc_altitude_smoothing_error()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:267: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:272: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:293: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:78: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:83: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:282: warning: 'void report_gains()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:420: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1099: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_max' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:280: warning: 'heli_servo_out' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:294: warning: 'rate_yaw_flag' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:296: warning: 'did_clear_yaw_control' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:303: warning: 'timer_light' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:322: warning: 'nav_gain_scaler' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:324: warning: 'last_ground_speed' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:339: warning: 'simple_bearing_is_set' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:356: warning: 'distance_error' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:388: warning: 'baro_alt_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:397: warning: 'landing_distance' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:420: warning: 'set_throttle_cruise_flag' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:437: warning: 'next_wp_index' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:447: warning: 'repeat_forever' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:454: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:473: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:474: warning: 'new_location' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:485: warning: 'imu_health' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:488: warning: 'gcs_messages_sent' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:493: warning: 'GCS_buffer' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:494: warning: 'display_PID' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:517: warning: 'elapsedTime' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:46: warning: 'trim_timer' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()':
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp'
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:46:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
autogenerated: At global scope:
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:334: warning: 'landing_distance' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()':
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp'
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,668 @@
|
|||
00000001 b _ZL10wp_control
|
||||
00000001 b _ZL11GPS_enabled
|
||||
00000001 b _ZL11home_is_set
|
||||
00000001 b _ZL11motor_armed
|
||||
00000001 b _ZL11motor_light
|
||||
00000001 b _ZL12control_mode
|
||||
00000001 b _ZL12flight_timer
|
||||
00000001 d _ZL12yaw_tracking
|
||||
00000001 b _ZL13land_complete
|
||||
00000001 b _ZL14command_may_ID
|
||||
00000001 b _ZL14wp_verify_byte
|
||||
00000001 d _ZL15altitude_sensor
|
||||
00000001 b _ZL15command_must_ID
|
||||
00000001 b _ZL15command_yaw_dir
|
||||
00000001 b _ZL16counter_one_herz
|
||||
00000001 b _ZL16delta_ms_fiftyhz
|
||||
00000001 b _ZL16did_ground_start
|
||||
00000001 b _ZL16invalid_throttle
|
||||
00000001 b _ZL16motor_auto_armed
|
||||
00000001 b _ZL16old_control_mode
|
||||
00000001 b _ZL16slow_loopCounter
|
||||
00000001 b _ZL16takeoff_complete
|
||||
00000001 b _ZL17baro_filter_index
|
||||
00000001 b _ZL17command_may_index
|
||||
00000001 b _ZL17oldSwitchPosition
|
||||
00000001 b _ZL18command_must_index
|
||||
00000001 b _ZL18delta_ms_fast_loop
|
||||
00000001 d _ZL18ground_start_count
|
||||
00000001 b _ZL18medium_loopCounter
|
||||
00000001 b _ZL20command_yaw_relative
|
||||
00000001 b _ZL20delta_ms_medium_loop
|
||||
00000001 b _ZL8event_id
|
||||
00000001 b _ZL8led_mode
|
||||
00000001 b _ZL9GPS_light
|
||||
00000001 b _ZL9loop_step
|
||||
00000001 b _ZL9trim_flag
|
||||
00000001 b _ZL9yaw_debug
|
||||
00000001 b _ZZL13dancing_lightvE4step
|
||||
00000001 b _ZZL17update_motor_ledsvE5blink
|
||||
00000001 b _ZZL18radio_input_switchvE7bouncer
|
||||
00000001 d _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE7mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T _Z19mavlink_acknowledge17mavlink_channel_thhh
|
||||
00000002 b _ZL10climb_rate
|
||||
00000002 b _ZL11event_delay
|
||||
00000002 b _ZL11event_value
|
||||
00000002 b _ZL12event_repeat
|
||||
00000002 b _ZL12nav_throttle
|
||||
00000002 b _ZL13gps_fix_count
|
||||
00000002 b _ZL13velocity_land
|
||||
00000002 b _ZL14mainLoop_count
|
||||
00000002 b _ZL14waypoint_speed
|
||||
00000002 b _ZL16command_yaw_time
|
||||
00000002 b _ZL16event_undo_value
|
||||
00000002 b _ZL16loiter_error_max
|
||||
00000002 b _ZL17command_yaw_speed
|
||||
00000002 b _ZL18auto_level_counter
|
||||
00000002 b _ZL18ground_temperature
|
||||
00000002 b _ZL20heli_manual_override
|
||||
00000002 b _ZL21superslow_loopCounter
|
||||
00000002 r _ZL5comma
|
||||
00000002 b _ZL5g_gps
|
||||
00000002 b _ZL8G_Dt_max
|
||||
00000002 b _ZL8airspeed
|
||||
00000002 b _ZL8baro_alt
|
||||
00000002 b _ZL9sonar_alt
|
||||
00000002 T _ZN11GCS_MAVLINK11acknowledgeEhhh
|
||||
00000002 b _ZZL10arm_motorsvE14arming_counter
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_0
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_1
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_2
|
||||
00000002 r _ZZL7test_wphPKN4Menu3argEE3__c_0
|
||||
00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c
|
||||
00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_0
|
||||
00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_1
|
||||
00000002 B adc
|
||||
00000003 r _ZZL10setup_gyrohPKN4Menu3argEE3__c
|
||||
00000003 r _ZZL11select_logshPKN4Menu3argEE3__c_4
|
||||
00000003 r _ZZL11setup_sonarhPKN4Menu3argEE3__c
|
||||
00000003 r _ZZL13print_enabledhE3__c
|
||||
00000003 r _ZZL13setup_compasshPKN4Menu3argEE3__c
|
||||
00000004 d _ZL10cos_roll_x
|
||||
00000004 b _ZL10land_start
|
||||
00000004 b _ZL10long_error
|
||||
00000004 b _ZL10sin_roll_y
|
||||
00000004 d _ZL11cos_pitch_x
|
||||
00000004 b _ZL11event_timer
|
||||
00000004 b _ZL11loiter_time
|
||||
00000004 b _ZL11nav_bearing
|
||||
00000004 d _ZL11scaleLongUp
|
||||
00000004 b _ZL11sin_pitch_y
|
||||
00000004 b _ZL11wp_distance
|
||||
00000004 b _ZL12abs_pressure
|
||||
00000004 b _ZL12current_amps
|
||||
00000004 b _ZL12original_alt
|
||||
00000004 b _ZL13bearing_error
|
||||
00000004 b _ZL13current_total
|
||||
00000004 b _ZL13nav_loopTimer
|
||||
00000004 d _ZL13scaleLongDown
|
||||
00000004 t _ZL13test_failsafehPKN4Menu3argE
|
||||
00000004 b _ZL14altitude_error
|
||||
00000004 b _ZL14fast_loopTimer
|
||||
00000004 b _ZL14perf_mon_timer
|
||||
00000004 b _ZL14target_bearing
|
||||
00000004 d _ZL15battery_voltage
|
||||
00000004 b _ZL15command_yaw_end
|
||||
00000004 b _ZL15condition_start
|
||||
00000004 b _ZL15condition_value
|
||||
00000004 b _ZL15ground_pressure
|
||||
00000004 b _ZL15loiter_time_max
|
||||
00000004 b _ZL15target_altitude
|
||||
00000004 d _ZL16battery_voltage1
|
||||
00000004 d _ZL16battery_voltage2
|
||||
00000004 d _ZL16battery_voltage3
|
||||
00000004 d _ZL16battery_voltage4
|
||||
00000004 b _ZL16crosstrack_error
|
||||
00000004 b _ZL16medium_loopTimer
|
||||
00000004 b _ZL16wp_totalDistance
|
||||
00000004 b _ZL17command_yaw_delta
|
||||
00000004 b _ZL17command_yaw_start
|
||||
00000004 b _ZL17fiftyhz_loopTimer
|
||||
00000004 b _ZL18crosstrack_bearing
|
||||
00000004 b _ZL18fast_loopTimeStamp
|
||||
00000004 b _ZL19throttle_integrator
|
||||
00000004 b _ZL20saved_target_bearing
|
||||
00000004 r _ZL21__menu_name__log_menu
|
||||
00000004 b _ZL22command_yaw_start_time
|
||||
00000004 b _ZL22initial_simple_bearing
|
||||
00000004 d _ZL4G_Dt
|
||||
00000004 b _ZL4load
|
||||
00000004 b _ZL5dTnav
|
||||
00000004 b _ZL7nav_lat
|
||||
00000004 b _ZL7nav_lon
|
||||
00000004 b _ZL7nav_yaw
|
||||
00000004 b _ZL7old_alt
|
||||
00000004 b _ZL8nav_roll
|
||||
00000004 d _ZL9cos_yaw_x
|
||||
00000004 b _ZL9lat_error
|
||||
00000004 b _ZL9nav_pitch
|
||||
00000004 b _ZL9sin_yaw_y
|
||||
00000004 b _ZL9yaw_error
|
||||
00000004 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_0
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_0
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_10
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_3
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_8
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_9
|
||||
00000004 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_0
|
||||
00000004 b _ZZL13mavlink_delaymE8last_1hz
|
||||
00000004 b _ZZL13mavlink_delaymE8last_3hz
|
||||
00000004 b _ZZL13mavlink_delaymE9last_10hz
|
||||
00000004 b _ZZL13mavlink_delaymE9last_50hz
|
||||
00000004 r _ZZL13print_enabledhE3__c_0
|
||||
00000004 r _ZZL13setup_compasshPKN4Menu3argEE3__c_0
|
||||
00000004 r _ZZL14print_log_menuvE3__c_4
|
||||
00000004 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c
|
||||
00000004 r _ZZL20Log_Read_PerformancevE3__c
|
||||
00000004 r _ZZL8test_adchPKN4Menu3argEE3__c_0
|
||||
00000004 V _ZZN10ParametersC1EvE3__c_32
|
||||
00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c
|
||||
00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_1
|
||||
00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_2
|
||||
00000005 r _ZL22__menu_name__test_menu
|
||||
00000005 r _ZZL10report_imuvE3__c
|
||||
00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_5
|
||||
00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_6
|
||||
00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_7
|
||||
00000005 r _ZZL12Log_Read_RawvE3__c
|
||||
00000005 r _ZZL13Log_Read_ModevE3__c
|
||||
00000005 r _ZZL14print_log_menuvE3__c_0
|
||||
00000005 r _ZZL14print_log_menuvE3__c_3
|
||||
00000005 r _ZZL14print_log_menuvE3__c_7
|
||||
00000005 r _ZZL14print_log_menuvE3__c_8
|
||||
00000005 r _ZZL8test_adchPKN4Menu3argEE3__c
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_35
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_36
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_37
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_38
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_49
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_50
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_51
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_52
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_53
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_54
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_55
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_56
|
||||
00000005 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_0
|
||||
00000005 r _ZZN11GCS_MAVLINKC1EjE3__c
|
||||
00000005 r _ZZN11GCS_MAVLINKC1EjE3__c_0
|
||||
00000005 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_2
|
||||
00000006 T _Z17mavlink_send_text17mavlink_channel_thPKc
|
||||
00000006 r _ZL23__menu_name__setup_menu
|
||||
00000006 r _ZZL10report_gpsvE3__c
|
||||
00000006 r _ZZL11report_helivE3__c
|
||||
00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c
|
||||
00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c_0
|
||||
00000006 r _ZZL11zero_eepromvE3__c_0
|
||||
00000006 r _ZZL13Log_Read_ModevE3__c_0
|
||||
00000006 r _ZZL14print_log_menuvE3__c_5
|
||||
00000006 r _ZZL14print_log_menuvE3__c_6
|
||||
00000006 V _ZZN10ParametersC1EvE3__c_33
|
||||
00000006 t put_float_by_index
|
||||
00000006 T setup
|
||||
00000007 b _ZL10setup_menu
|
||||
00000007 b _ZL12planner_menu
|
||||
00000007 b _ZL8log_menu
|
||||
00000007 b _ZL9main_menu
|
||||
00000007 b _ZL9test_menu
|
||||
00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_11
|
||||
00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_13
|
||||
00000007 r _ZZL12report_framevE3__c
|
||||
00000007 r _ZZL12report_radiovE3__c
|
||||
00000007 r _ZZL12report_sonarvE3__c
|
||||
00000007 r _ZZL13print_enabledhE3__c_1
|
||||
00000007 r _ZZL7test_wphPKN4Menu3argEE3__c_2
|
||||
00000007 V _ZZN10ParametersC1EvE3__c_57
|
||||
00000007 V _ZZN10ParametersC1EvE3__c_58
|
||||
00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_6
|
||||
00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_7
|
||||
00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_8
|
||||
00000008 t _ZL11setup_erasehPKN4Menu3argE
|
||||
00000008 r _ZL25__menu_name__planner_menu
|
||||
00000008 r _ZZL11select_logshPKN4Menu3argEE3__c_12
|
||||
00000008 r _ZZL14print_log_menuvE3__c_10
|
||||
00000008 r _ZZL19report_batt_monitorvE3__c_0
|
||||
00000008 r _ZZL19report_batt_monitorvE3__c_1
|
||||
00000008 r _ZZL7test_wphPKN4Menu3argEE3__c_1
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_10
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_17
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_18
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_67
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_69
|
||||
00000008 r _ZZN11GCS_MAVLINKC1EjE3__c_3
|
||||
00000009 r _ZZL11report_gyrovE3__c_0
|
||||
00000009 r _ZZL12print_switchhhE3__c
|
||||
00000009 r _ZZL14print_log_menuvE3__c_11
|
||||
00000009 r _ZZL14print_log_menuvE3__c_9
|
||||
00000009 r _ZZL14report_compassvE3__c
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_11
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_12
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_23
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_24
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_25
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_26
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_27
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_28
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_34
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_39
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_40
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_41
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_42
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_43
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_44
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_45
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_46
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_62
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_63
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_64
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_65
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_66
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_68
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_1
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_2
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_4
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_5
|
||||
0000000a r _ZZL10test_relayhPKN4Menu3argEE3__c
|
||||
0000000a r _ZZL11test_tuninghPKN4Menu3argEE3__c
|
||||
0000000a r _ZZL13start_new_logvE3__c
|
||||
0000000a r _ZZL14print_log_menuvE3__c_13
|
||||
0000000a r _ZZL16Log_Read_StartupvE3__c
|
||||
0000000a r _ZZL7test_wphPKN4Menu3argEE3__c
|
||||
0000000a r _ZZL8test_maghPKN4Menu3argEE3__c_0
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_14
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_29
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_48
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_59
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_60
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_61
|
||||
0000000b r _ZZL10test_relayhPKN4Menu3argEE3__c_0
|
||||
0000000b r _ZZL19report_batt_monitorvE3__c_2
|
||||
0000000b r _ZZL8set_modehE3__c
|
||||
0000000b V _ZZN10ParametersC1EvE3__c_8
|
||||
0000000c t _ZL12process_logshPKN4Menu3argE
|
||||
0000000c b _ZL15heli_rollFactor
|
||||
0000000c b _ZL16heli_pitchFactor
|
||||
0000000c b _ZL5omega
|
||||
0000000c t _ZL9test_modehPKN4Menu3argE
|
||||
0000000c T _ZN11GCS_MAVLINK9send_textEhPKc
|
||||
0000000c V _ZTV3IMU
|
||||
0000000c r _ZZL12report_framevE3__c_0
|
||||
0000000c r _ZZL9test_barohPKN4Menu3argEE3__c
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_2
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_30
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_47
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_9
|
||||
0000000d r _ZZL10verify_RTLvE3__c
|
||||
0000000d r _ZZL11select_logshPKN4Menu3argEE3__c_2
|
||||
0000000d r _ZZL12test_batteryhPKN4Menu3argEE3__c
|
||||
0000000d r _ZZL14startup_groundvE3__c
|
||||
0000000d r _ZZL7test_wphPKN4Menu3argEE3__c_3
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_16
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_19
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_21
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_3
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_31
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_5
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_6
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t _GLOBAL__D_Serial
|
||||
0000000e t _GLOBAL__I_Serial
|
||||
0000000e V _ZTV10AP_Float16
|
||||
0000000e V _ZTV7AP_VarAIfLh6EE
|
||||
0000000e V _ZTV7AP_VarSI7Matrix3IfEE
|
||||
0000000e V _ZTV7AP_VarSI7Vector3IfEE
|
||||
0000000e V _ZTV7AP_VarTIaE
|
||||
0000000e V _ZTV7AP_VarTIfE
|
||||
0000000e V _ZTV7AP_VarTIiE
|
||||
0000000e r _ZZL10erase_logshPKN4Menu3argEE3__c_0
|
||||
0000000e r _ZZL10setup_helihPKN4Menu3argEE3__c
|
||||
0000000e r _ZZL10setup_modehPKN4Menu3argEE3__c
|
||||
0000000e r _ZZL10test_sonarhPKN4Menu3argEE3__c_0
|
||||
0000000e r _ZZL11select_logshPKN4Menu3argEE3__c_1
|
||||
0000000e r _ZZL14print_log_menuvE3__c_2
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_0
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_1
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_2
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_3
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_4
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_5
|
||||
0000000e r _ZZL19report_batt_monitorvE3__c_3
|
||||
0000000e r _ZZL19report_flight_modesvE3__c
|
||||
0000000e r _ZZL8dump_loghPKN4Menu3argEE3__c
|
||||
0000000e V _ZZN10ParametersC1EvE3__c
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_0
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_1
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_13
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_15
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_20
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_22
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_4
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_7
|
||||
0000000f b _ZL11current_loc
|
||||
0000000f b _ZL12next_command
|
||||
0000000f r _ZL22__menu_name__main_menu
|
||||
0000000f b _ZL4home
|
||||
0000000f b _ZL7next_WP
|
||||
0000000f b _ZL7prev_WP
|
||||
0000000f b _ZL9guided_WP
|
||||
0000000f b _ZL9simple_WP
|
||||
0000000f b _ZL9target_WP
|
||||
0000000f r _ZZL11report_helivE3__c_5
|
||||
0000000f r _ZZL14print_log_menuvE3__c
|
||||
0000000f r _ZZL14print_log_menuvE3__c_1
|
||||
0000000f r _ZZL14report_versionvE3__c
|
||||
0000000f r _ZZL19report_batt_monitorvE3__c
|
||||
0000000f r _ZZL8test_imuhPKN4Menu3argEE3__c
|
||||
0000000f V _ZZN13AP_IMU_OilpanC1EP6AP_ADCjE3__c
|
||||
00000010 r _ZL21planner_menu_commands
|
||||
00000010 b _ZL9motor_out
|
||||
00000010 W _ZNK7AP_VarTIfE13cast_to_floatEv
|
||||
00000010 r _ZZL10test_sonarhPKN4Menu3argEE3__c
|
||||
00000010 r _ZZL11report_gyrovE3__c
|
||||
00000010 r _ZZL11report_helivE3__c_6
|
||||
00000010 r _ZZL14report_compassvE3__c_0
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r _ZZL10erase_logshPKN4Menu3argEE3__c
|
||||
00000011 r _ZZL10setup_helihPKN4Menu3argEE3__c_8
|
||||
00000011 r _ZZL11zero_eepromvE3__c
|
||||
00000011 r _ZZL15update_commandsvE3__c
|
||||
00000011 r _ZZL17Log_Read_AttitudevE3__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r _ZL19flight_mode_strings
|
||||
00000012 W _ZN10AP_Float16D1Ev
|
||||
00000012 W _ZN7AP_VarAIfLh6EED1Ev
|
||||
00000012 W _ZN7AP_VarSI7Matrix3IfEED1Ev
|
||||
00000012 W _ZN7AP_VarSI7Vector3IfEED1Ev
|
||||
00000012 W _ZN7AP_VarTIaED1Ev
|
||||
00000012 W _ZN7AP_VarTIfED1Ev
|
||||
00000012 W _ZN7AP_VarTIiED1Ev
|
||||
00000012 W _ZNK7AP_VarTIaE9serializeEPvj
|
||||
00000012 r _ZZL10print_donevE3__c
|
||||
00000012 r _ZZL10setup_helihPKN4Menu3argEE3__c_12
|
||||
00000012 r _ZZL11select_logshPKN4Menu3argEE3__c
|
||||
00000012 r _ZZL11setup_framehPKN4Menu3argEE3__c_3
|
||||
00000012 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c
|
||||
00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_13
|
||||
00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_6
|
||||
00000013 r _ZZL11report_helivE3__c_1
|
||||
00000013 r _ZZL11report_helivE3__c_2
|
||||
00000013 r _ZZL11report_helivE3__c_3
|
||||
00000013 r _ZZL11report_helivE3__c_4
|
||||
00000013 r _ZZL13setup_compasshPKN4Menu3argEE3__c_1
|
||||
00000013 r _ZZL14change_commandhE3__c
|
||||
00000013 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c_0
|
||||
00000014 W _ZN7AP_VarTIaE11unserializeEPvj
|
||||
00000014 W _ZNK7AP_VarTIaE13cast_to_floatEv
|
||||
00000014 W _ZNK7AP_VarTIiE13cast_to_floatEv
|
||||
00000014 r _ZZL10setup_helihPKN4Menu3argEE3__c_1
|
||||
00000014 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_1
|
||||
00000014 r _ZZL8test_trihPKN4Menu3argEE3__c
|
||||
00000015 r _ZZL12map_baudrateamE3__c
|
||||
00000015 r _ZZL14init_ardupilotvE3__c_0
|
||||
00000015 r _ZZL15Log_Read_MotorsvE3__c
|
||||
00000015 r _ZZL15print_hit_entervE3__c
|
||||
00000015 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c_0
|
||||
00000016 r _ZZL10setup_helihPKN4Menu3argEE3__c_0
|
||||
00000016 r _ZZL14init_ardupilotvE3__c
|
||||
00000016 r _ZZN11GCS_MAVLINK6updateEvE3__c
|
||||
00000016 B sonar
|
||||
00000018 b _ZL11baro_filter
|
||||
00000018 t _ZL11setup_accelhPKN4Menu3argE
|
||||
00000018 T _ZN11GCS_MAVLINK12send_messageEhm
|
||||
00000018 W _ZNK7AP_VarTIiE9serializeEPvj
|
||||
00000019 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_1
|
||||
00000019 r _ZZN11GCS_MAVLINK6updateEvE3__c_0
|
||||
0000001a t _ZL10clear_ledsv
|
||||
0000001a r _ZZL14print_log_menuvE3__c_12
|
||||
0000001b r _ZZL10setup_helihPKN4Menu3argEE3__c_2
|
||||
0000001b r _ZZL11report_helivE3__c_0
|
||||
0000001c W _ZN7AP_VarAIfLh6EE11unserializeEPvj
|
||||
0000001c W _ZN7AP_VarSI7Matrix3IfEE11unserializeEPvj
|
||||
0000001c W _ZN7AP_VarSI7Vector3IfEE11unserializeEPvj
|
||||
0000001c W _ZN7AP_VarTIiE11unserializeEPvj
|
||||
0000001c W _ZNK7AP_VarAIfLh6EE9serializeEPvj
|
||||
0000001c W _ZNK7AP_VarSI7Matrix3IfEE9serializeEPvj
|
||||
0000001c W _ZNK7AP_VarSI7Vector3IfEE9serializeEPvj
|
||||
0000001c b _ZZ26mavlink_get_channel_statusE16m_mavlink_status
|
||||
0000001e r _ZZL11report_helivE3__c_7
|
||||
0000001e r _ZZL16Log_Read_OptflowvE3__c
|
||||
0000001f r _ZZL8test_maghPKN4Menu3argEE3__c
|
||||
00000020 r _ZZL12test_currenthPKN4Menu3argEE3__c
|
||||
00000021 r _ZZL10setup_helihPKN4Menu3argEE3__c_7
|
||||
00000021 r _ZZL14print_log_menuvE3__c_14
|
||||
00000021 r _ZZL14report_compassvE3__c_1
|
||||
00000021 r _ZZL16Log_Read_CurrentvE3__c
|
||||
00000022 t _ZL12print_blanksi
|
||||
00000022 W _ZN10AP_Float16D0Ev
|
||||
00000022 W _ZN7AP_VarAIfLh6EED0Ev
|
||||
00000022 W _ZN7AP_VarSI7Matrix3IfEED0Ev
|
||||
00000022 W _ZN7AP_VarSI7Vector3IfEED0Ev
|
||||
00000022 W _ZN7AP_VarTIaED0Ev
|
||||
00000022 W _ZN7AP_VarTIfED0Ev
|
||||
00000022 W _ZN7AP_VarTIiED0Ev
|
||||
00000023 r _ZZL10setup_helihPKN4Menu3argEE3__c_4
|
||||
00000023 r _ZZL10setup_modehPKN4Menu3argEE3__c_1
|
||||
00000023 r _ZZL18print_gyro_offsetsvE3__c
|
||||
00000024 r _ZZL10setup_helihPKN4Menu3argEE3__c_3
|
||||
00000024 r _ZZL19print_accel_offsetsvE3__c
|
||||
00000025 r _ZZL13setup_factoryhPKN4Menu3argEE3__c_0
|
||||
00000026 t _ZL10print_donev
|
||||
00000026 t _ZL15print_hit_enterv
|
||||
00000026 t _ZL16Log_Read_Startupv
|
||||
00000026 r _ZZL19Log_Read_Nav_TuningvE3__c
|
||||
00000026 B barometer
|
||||
00000027 r _ZZL9test_xbeehPKN4Menu3argEE3__c
|
||||
00000028 t _ZL12test_batteryhPKN4Menu3argE
|
||||
00000028 t _ZL14main_menu_helphPKN4Menu3argE
|
||||
00000028 t _ZL8help_loghPKN4Menu3argE
|
||||
00000028 W _ZN7AP_VarTIfE11unserializeEPvj
|
||||
00000028 W _ZNK7AP_VarTIfE9serializeEPvj
|
||||
00000028 r _ZZL12Log_Read_CmdvE3__c
|
||||
00000029 r _ZZL10setup_helihPKN4Menu3argEE3__c_9
|
||||
00000029 r _ZZL10setup_modehPKN4Menu3argEE3__c_0
|
||||
00000029 r _ZZL8test_gpshPKN4Menu3argEE3__c
|
||||
0000002a t _ZL11reset_nav_Iv
|
||||
0000002a t _ZL17setup_declinationhPKN4Menu3argE
|
||||
0000002b r _ZZL12planner_modehPKN4Menu3argEE3__c
|
||||
0000002c t _ZL7freeRAMv
|
||||
0000002e t _ZL12setup_motorshPKN4Menu3argE
|
||||
0000002e t _ZL13print_dividerv
|
||||
0000002e t _ZL9send_ratejj
|
||||
0000002e W _ZN12AP_Var_groupC1EjPK11prog_char_th
|
||||
0000002f r _ZZL10test_radiohPKN4Menu3argEE3__c
|
||||
00000030 t _ZL12planner_modehPKN4Menu3argE
|
||||
00000030 t put_int32_t_by_index
|
||||
00000032 T _ZN11GCS_MAVLINK4initEP12BetterStream
|
||||
00000032 r _ZZL10setup_helihPKN4Menu3argEE3__c_5
|
||||
00000034 t _ZL14heli_get_servoi
|
||||
00000034 W _ZNK10AP_Float169serializeEPvj
|
||||
00000035 r _ZZL14test_radio_pwmhPKN4Menu3argEE3__c
|
||||
00000036 t _ZL12report_radiov
|
||||
00000036 r _ZZL12Log_Read_GPSvE3__c
|
||||
00000037 r _ZZL8print_wpP8LocationhE3__c
|
||||
00000038 t _ZL20init_throttle_cruisev
|
||||
00000038 r _ZZL11setup_radiohPKN4Menu3argEE3__c
|
||||
00000038 r _ZZL13setup_factoryhPKN4Menu3argEE3__c
|
||||
0000003a t _ZL10report_gpsv
|
||||
0000003a t _ZL10report_imuv
|
||||
0000003a t _ZL12comm_send_ch17mavlink_channel_th
|
||||
0000003a W _ZN3PIDD1Ev
|
||||
0000003c W _ZN10RC_ChannelD1Ev
|
||||
0000003d r _ZZL23Log_Read_Control_TuningvE3__c
|
||||
0000003d B g_gps_driver
|
||||
0000003e t _ZL10verify_RTLv
|
||||
0000003e T _ZN11GCS_MAVLINK9send_textEhPK11prog_char_t
|
||||
0000003e W _ZN7AP_VarTIaEC1EajPK11prog_char_th
|
||||
00000040 W _ZN10AP_Float1611unserializeEPvj
|
||||
00000042 T _Z10output_minv
|
||||
00000042 t _ZL12report_sonarv
|
||||
00000042 r _ZZL10setup_helihPKN4Menu3argEE3__c_10
|
||||
00000044 W _ZN7AP_VarTIiEC1EijPK11prog_char_th
|
||||
0000004a t _ZL19read_control_switchv
|
||||
0000004a W _ZN7AP_VarTIiEC1EP12AP_Var_groupjiPK11prog_char_th
|
||||
0000004a t mavlink_msg_waypoint_current_send
|
||||
0000004a t mavlink_update_checksum
|
||||
0000004c t _ZL10setup_showhPKN4Menu3argE
|
||||
0000004c t _ZL14update_nav_yawv
|
||||
0000004c B imu
|
||||
0000004e t mavlink_msg_waypoint_ack_send
|
||||
00000050 r _ZL17log_menu_commands
|
||||
00000050 r _ZL18main_menu_commands
|
||||
00000050 t _ZL9read_AHRSv
|
||||
00000050 T _ZN11GCS_MAVLINK15_find_parameterEj
|
||||
00000050 t mavlink_msg_waypoint_request_send
|
||||
00000052 t _ZL14change_commandh
|
||||
00000052 t _ZL14report_versionv
|
||||
00000054 t _ZL13print_enabledh
|
||||
00000054 t _ZL17update_motor_ledsv
|
||||
00000054 t _ZL19report_flight_modesv
|
||||
00000055 r _ZZL14main_menu_helphPKN4Menu3argEE3__c
|
||||
00000055 r _ZZL17setup_flightmodeshPKN4Menu3argEE3__c
|
||||
00000056 t _ZL10readSwitchv
|
||||
00000056 t _ZL13dancing_lightv
|
||||
00000057 r _ZZL8help_loghPKN4Menu3argEE3__c
|
||||
00000058 t _ZL11test_tuninghPKN4Menu3argE
|
||||
00000058 t _ZL14startup_groundv
|
||||
00000058 t _ZL18Log_Write_Attitudev
|
||||
0000005a t _ZL12report_framev
|
||||
0000005a t mavlink_msg_statustext_send
|
||||
0000005c t _ZL12get_num_logsv
|
||||
0000005c t _ZL9setup_eschPKN4Menu3argE
|
||||
0000005e t _ZL16update_GPS_lightv
|
||||
0000005e t _ZL18radio_input_switchv
|
||||
0000005e T _ZN11GCS_MAVLINK17_count_parametersEv
|
||||
0000005f r _ZZL10setup_helihPKN4Menu3argEE3__c_11
|
||||
00000060 W _ZN10AP_Float16C1EP12AP_Var_groupjfPK11prog_char_th
|
||||
00000062 t _ZL12print_switchhh
|
||||
00000064 t _ZL9test_xbeehPKN4Menu3argE
|
||||
00000068 t _ZL11zero_eepromv
|
||||
00000068 t _ZL18find_last_log_pagei
|
||||
0000006a t _ZL20read_num_from_serialv
|
||||
0000006a W _ZN11GCS_MAVLINKD1Ev
|
||||
0000006c t _ZL11setup_sonarhPKN4Menu3argE
|
||||
00000074 t _ZL19output_motors_armedv
|
||||
00000078 t _ZL18setup_batt_monitorhPKN4Menu3argE
|
||||
0000007a t _ZL13setup_factoryhPKN4Menu3argE
|
||||
0000007a t _ZL18get_nav_yaw_offsetii
|
||||
0000007c t _ZL9test_barohPKN4Menu3argE
|
||||
0000007e t _ZL11test_rawgpshPKN4Menu3argE
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t _ZL6do_RTLv
|
||||
00000084 t mavlink_send_uart
|
||||
00000086 t _ZL17Log_Read_Attitudev
|
||||
00000088 t _ZL12Log_Read_Rawv
|
||||
0000008c t _ZL11setup_framehPKN4Menu3argE
|
||||
0000008c t _ZL18print_gyro_offsetsv
|
||||
0000008c t _ZL19print_accel_offsetsv
|
||||
00000092 t _ZL11report_gyrov
|
||||
00000095 r _ZZL14init_ardupilotvE3__c_1
|
||||
00000096 t _ZL12map_baudrateam
|
||||
00000096 t _ZL8print_wpP8Locationh
|
||||
0000009a t _ZL12init_compassv
|
||||
0000009a t _ZL14init_barometerv
|
||||
0000009a t _ZL15Log_Read_Motorsv
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t _ZL10setup_modehPKN4Menu3argE
|
||||
0000009e t _ZL13Log_Write_CmdhP8Location
|
||||
000000a0 t _ZL13Log_Read_Modev
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000a6 t mavlink_msg_param_value_send
|
||||
000000aa t _ZL10test_sonarhPKN4Menu3argE
|
||||
000000ac t _ZL20Log_Read_Performancev
|
||||
000000ae t _ZL13auto_throttlev
|
||||
000000b0 t _ZL10read_radiov
|
||||
000000b2 t _ZL10erase_logshPKN4Menu3argE
|
||||
000000b2 t _ZL8dump_loghPKN4Menu3argE
|
||||
000000b4 t _ZL10test_relayhPKN4Menu3argE
|
||||
000000b4 t _ZL11planner_gcshPKN4Menu3argE
|
||||
000000b6 t _ZL18get_log_boundarieshRiS_
|
||||
000000b7 B compass
|
||||
000000c2 t _ZL13setup_compasshPKN4Menu3argE
|
||||
000000c4 t _ZL12get_distanceP8LocationS0_
|
||||
000000c4 t _ZL13update_eventsv
|
||||
000000c4 r _ZZL9setup_eschPKN4Menu3argEE3__c
|
||||
000000c6 t _ZL11test_eedumphPKN4Menu3argE
|
||||
000000c6 t _ZL8Log_Readii
|
||||
000000c6 t _ZL8test_trihPKN4Menu3argE
|
||||
000000c7 B dcm
|
||||
000000c8 t _ZL14read_barometerv
|
||||
000000ca t _ZL12get_throttlei
|
||||
000000ce W _ZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKi
|
||||
000000d0 t _ZL11get_bearingP8LocationS0_
|
||||
000000d8 t _ZL10test_radiohPKN4Menu3argE
|
||||
000000dc t _ZL18read_baro_filteredv
|
||||
000000de t _ZL8test_adchPKN4Menu3argE
|
||||
000000e4 t _ZL14test_radio_pwmhPKN4Menu3argE
|
||||
000000e4 t _ZL16Log_Read_Optflowv
|
||||
000000e6 t _ZL17setup_flightmodeshPKN4Menu3argE
|
||||
000000e6 t _ZL19Log_Read_Nav_Tuningv
|
||||
000000e6 t mavlink_finalize_message_chan
|
||||
000000e8 t _ZL16Log_Read_Currentv
|
||||
000000ec t put_uint64_t_by_index
|
||||
000000ee t _ZL19report_batt_monitorv
|
||||
000000f0 r _ZL19setup_menu_commands
|
||||
000000f2 t _ZL18get_stabilize_rolll
|
||||
000000f2 t _ZL19get_stabilize_pitchl
|
||||
000000f6 t _ZL12Log_Read_Cmdv
|
||||
000000fc T _ZN11GCS_MAVLINK12_queued_sendEv
|
||||
00000106 t _ZL10setup_gyrohPKN4Menu3argE
|
||||
0000010a t _ZL8test_gpshPKN4Menu3argE
|
||||
0000010c W _ZN10RC_ChannelC1EjPK11prog_char_t
|
||||
00000112 t _ZL12test_currenthPKN4Menu3argE
|
||||
00000112 t _ZL15adjust_altitudev
|
||||
00000112 T _ZN11GCS_MAVLINKC1Ej
|
||||
00000112 T _ZN11GCS_MAVLINKC2Ej
|
||||
00000118 t _ZL22set_command_with_index8Locationi
|
||||
00000120 r _ZL18test_menu_commands
|
||||
00000128 t _ZL22get_command_with_indexi
|
||||
0000012c t _ZL23Log_Read_Control_Tuningv
|
||||
00000130 t _ZL14report_compassv
|
||||
00000144 t _ZL15calc_nav_outputv
|
||||
0000014c T _ZN11GCS_MAVLINK6updateEv
|
||||
00000150 t _ZL11update_trigv
|
||||
00000152 t _ZL11set_next_WPP8Location
|
||||
00000156 t _ZL12Log_Read_GPSv
|
||||
0000015c t _ZL10arm_motorsv
|
||||
00000166 t _ZL11select_logshPKN4Menu3argE
|
||||
0000016c t _ZL15update_commandsv
|
||||
00000170 t _ZL8test_maghPKN4Menu3argE
|
||||
0000017e t _ZL17get_stabilize_yawlf
|
||||
0000018e T _ZN11GCS_MAVLINK16data_stream_sendEjj
|
||||
00000196 t _ZL8set_modeh
|
||||
000001a0 t _ZL9init_homev
|
||||
000001a8 t _ZL18print_radio_valuesv
|
||||
000001ae t _ZL13mavlink_delaym
|
||||
000001b8 t _ZL8test_imuhPKN4Menu3argE
|
||||
000001c4 t _ZL17update_crosstrackv
|
||||
000001ce t _ZL13start_new_logv
|
||||
0000020c b _ZZ18mavlink_parse_charE17m_mavlink_message
|
||||
00000220 t _ZL7test_wphPKN4Menu3argE
|
||||
00000228 t _ZL11setup_radiohPKN4Menu3argE
|
||||
00000264 t _ZL13update_nav_wpv
|
||||
00000288 t _ZL13calc_rate_navi
|
||||
000002b8 t _ZL15heli_init_swashv
|
||||
000002d0 t _ZL11report_heliv
|
||||
0000031e t _ZL12read_batteryv
|
||||
00000368 t _ZL15heli_move_swashiiii
|
||||
00000384 t _ZL14print_log_menuv
|
||||
0000055e t mavlink_parse_char
|
||||
00000628 t _ZL14init_ardupilotv
|
||||
0000071a t _ZL10setup_helihPKN4Menu3argE
|
||||
00000800 t _Z41__static_initialization_and_destruction_0ii
|
||||
00000866 T _Z26update_current_flight_modev
|
||||
000008f4 t _ZL20process_next_commandv
|
||||
0000097e W _ZN10ParametersC1Ev
|
||||
00000b3c b _ZL1g
|
||||
00001148 T _ZN11GCS_MAVLINK13handleMessageEP17__mavlink_message
|
||||
000015be T _Z20mavlink_send_message17mavlink_channel_thmj
|
||||
00001ab0 T loop
|
|
@ -0,0 +1,400 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:68:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde: In function 'void init_compass()':
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:458: warning: unused variable 'junkbool'
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_tail' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_tail' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_coll' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_coll' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_pitch' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_roll' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:433: warning: 'temp' may be used uninitialized in this function
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde: At global scope:
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1494: warning: 'void tuning()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1586: warning: 'void point_at_home_yaw()' defined but not used
|
||||
autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:135: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:127: warning: 'void decrement_WP_index()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:148: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:429: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:40: warning: 'void update_servo_switches()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:49: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:232: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:194: warning: 'void calc_altitude_smoothing_error()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:267: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:272: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:293: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:78: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:83: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:282: warning: 'void report_gains()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:420: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1099: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_min' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_max' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:280: warning: 'heli_servo_out' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:294: warning: 'rate_yaw_flag' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:296: warning: 'did_clear_yaw_control' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:303: warning: 'timer_light' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:322: warning: 'nav_gain_scaler' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:324: warning: 'last_ground_speed' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:339: warning: 'simple_bearing_is_set' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:356: warning: 'distance_error' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:388: warning: 'baro_alt_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:397: warning: 'landing_distance' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:420: warning: 'set_throttle_cruise_flag' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:437: warning: 'next_wp_index' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:447: warning: 'repeat_forever' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:454: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:473: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:474: warning: 'new_location' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:485: warning: 'imu_health' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:488: warning: 'gcs_messages_sent' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:493: warning: 'GCS_buffer' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:494: warning: 'display_PID' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:517: warning: 'elapsedTime' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:46: warning: 'trim_timer' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()':
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp'
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:46:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
autogenerated: At global scope:
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:334: warning: 'landing_distance' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()':
|
||||
/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp'
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83,
|
||||
from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6:
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,668 @@
|
|||
00000001 b _ZL10wp_control
|
||||
00000001 b _ZL11GPS_enabled
|
||||
00000001 b _ZL11home_is_set
|
||||
00000001 b _ZL11motor_armed
|
||||
00000001 b _ZL11motor_light
|
||||
00000001 b _ZL12control_mode
|
||||
00000001 b _ZL12flight_timer
|
||||
00000001 d _ZL12yaw_tracking
|
||||
00000001 b _ZL13land_complete
|
||||
00000001 b _ZL14command_may_ID
|
||||
00000001 b _ZL14wp_verify_byte
|
||||
00000001 d _ZL15altitude_sensor
|
||||
00000001 b _ZL15command_must_ID
|
||||
00000001 b _ZL15command_yaw_dir
|
||||
00000001 b _ZL16counter_one_herz
|
||||
00000001 b _ZL16delta_ms_fiftyhz
|
||||
00000001 b _ZL16did_ground_start
|
||||
00000001 b _ZL16invalid_throttle
|
||||
00000001 b _ZL16motor_auto_armed
|
||||
00000001 b _ZL16old_control_mode
|
||||
00000001 b _ZL16slow_loopCounter
|
||||
00000001 b _ZL16takeoff_complete
|
||||
00000001 b _ZL17baro_filter_index
|
||||
00000001 b _ZL17command_may_index
|
||||
00000001 b _ZL17oldSwitchPosition
|
||||
00000001 b _ZL18command_must_index
|
||||
00000001 b _ZL18delta_ms_fast_loop
|
||||
00000001 d _ZL18ground_start_count
|
||||
00000001 b _ZL18medium_loopCounter
|
||||
00000001 b _ZL20command_yaw_relative
|
||||
00000001 b _ZL20delta_ms_medium_loop
|
||||
00000001 b _ZL8event_id
|
||||
00000001 b _ZL8led_mode
|
||||
00000001 b _ZL9GPS_light
|
||||
00000001 b _ZL9loop_step
|
||||
00000001 b _ZL9trim_flag
|
||||
00000001 b _ZL9yaw_debug
|
||||
00000001 b _ZZL13dancing_lightvE4step
|
||||
00000001 b _ZZL17update_motor_ledsvE5blink
|
||||
00000001 b _ZZL18radio_input_switchvE7bouncer
|
||||
00000001 d _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE7mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T _Z19mavlink_acknowledge17mavlink_channel_thhh
|
||||
00000002 b _ZL10climb_rate
|
||||
00000002 b _ZL11event_delay
|
||||
00000002 b _ZL11event_value
|
||||
00000002 b _ZL12event_repeat
|
||||
00000002 b _ZL12nav_throttle
|
||||
00000002 b _ZL13gps_fix_count
|
||||
00000002 b _ZL13velocity_land
|
||||
00000002 b _ZL14mainLoop_count
|
||||
00000002 b _ZL14waypoint_speed
|
||||
00000002 b _ZL16command_yaw_time
|
||||
00000002 b _ZL16event_undo_value
|
||||
00000002 b _ZL16loiter_error_max
|
||||
00000002 b _ZL17command_yaw_speed
|
||||
00000002 b _ZL18auto_level_counter
|
||||
00000002 b _ZL18ground_temperature
|
||||
00000002 b _ZL20heli_manual_override
|
||||
00000002 b _ZL21superslow_loopCounter
|
||||
00000002 r _ZL5comma
|
||||
00000002 b _ZL5g_gps
|
||||
00000002 b _ZL8G_Dt_max
|
||||
00000002 b _ZL8airspeed
|
||||
00000002 b _ZL8baro_alt
|
||||
00000002 b _ZL9sonar_alt
|
||||
00000002 T _ZN11GCS_MAVLINK11acknowledgeEhhh
|
||||
00000002 b _ZZL10arm_motorsvE14arming_counter
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_0
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_1
|
||||
00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_2
|
||||
00000002 r _ZZL7test_wphPKN4Menu3argEE3__c_0
|
||||
00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c
|
||||
00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_0
|
||||
00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_1
|
||||
00000002 B adc
|
||||
00000003 r _ZZL10setup_gyrohPKN4Menu3argEE3__c
|
||||
00000003 r _ZZL11select_logshPKN4Menu3argEE3__c_4
|
||||
00000003 r _ZZL11setup_sonarhPKN4Menu3argEE3__c
|
||||
00000003 r _ZZL13print_enabledhE3__c
|
||||
00000003 r _ZZL13setup_compasshPKN4Menu3argEE3__c
|
||||
00000004 d _ZL10cos_roll_x
|
||||
00000004 b _ZL10land_start
|
||||
00000004 b _ZL10long_error
|
||||
00000004 b _ZL10sin_roll_y
|
||||
00000004 d _ZL11cos_pitch_x
|
||||
00000004 b _ZL11event_timer
|
||||
00000004 b _ZL11loiter_time
|
||||
00000004 b _ZL11nav_bearing
|
||||
00000004 d _ZL11scaleLongUp
|
||||
00000004 b _ZL11sin_pitch_y
|
||||
00000004 b _ZL11wp_distance
|
||||
00000004 b _ZL12abs_pressure
|
||||
00000004 b _ZL12current_amps
|
||||
00000004 b _ZL12original_alt
|
||||
00000004 b _ZL13bearing_error
|
||||
00000004 b _ZL13current_total
|
||||
00000004 b _ZL13nav_loopTimer
|
||||
00000004 d _ZL13scaleLongDown
|
||||
00000004 t _ZL13test_failsafehPKN4Menu3argE
|
||||
00000004 b _ZL14altitude_error
|
||||
00000004 b _ZL14fast_loopTimer
|
||||
00000004 b _ZL14perf_mon_timer
|
||||
00000004 b _ZL14target_bearing
|
||||
00000004 d _ZL15battery_voltage
|
||||
00000004 b _ZL15command_yaw_end
|
||||
00000004 b _ZL15condition_start
|
||||
00000004 b _ZL15condition_value
|
||||
00000004 b _ZL15ground_pressure
|
||||
00000004 b _ZL15loiter_time_max
|
||||
00000004 b _ZL15target_altitude
|
||||
00000004 d _ZL16battery_voltage1
|
||||
00000004 d _ZL16battery_voltage2
|
||||
00000004 d _ZL16battery_voltage3
|
||||
00000004 d _ZL16battery_voltage4
|
||||
00000004 b _ZL16crosstrack_error
|
||||
00000004 b _ZL16medium_loopTimer
|
||||
00000004 b _ZL16wp_totalDistance
|
||||
00000004 b _ZL17command_yaw_delta
|
||||
00000004 b _ZL17command_yaw_start
|
||||
00000004 b _ZL17fiftyhz_loopTimer
|
||||
00000004 b _ZL18crosstrack_bearing
|
||||
00000004 b _ZL18fast_loopTimeStamp
|
||||
00000004 b _ZL19throttle_integrator
|
||||
00000004 b _ZL20saved_target_bearing
|
||||
00000004 r _ZL21__menu_name__log_menu
|
||||
00000004 b _ZL22command_yaw_start_time
|
||||
00000004 b _ZL22initial_simple_bearing
|
||||
00000004 d _ZL4G_Dt
|
||||
00000004 b _ZL4load
|
||||
00000004 b _ZL5dTnav
|
||||
00000004 b _ZL7nav_lat
|
||||
00000004 b _ZL7nav_lon
|
||||
00000004 b _ZL7nav_yaw
|
||||
00000004 b _ZL7old_alt
|
||||
00000004 b _ZL8nav_roll
|
||||
00000004 d _ZL9cos_yaw_x
|
||||
00000004 b _ZL9lat_error
|
||||
00000004 b _ZL9nav_pitch
|
||||
00000004 b _ZL9sin_yaw_y
|
||||
00000004 b _ZL9yaw_error
|
||||
00000004 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_0
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_0
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_10
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_3
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_8
|
||||
00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_9
|
||||
00000004 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_0
|
||||
00000004 b _ZZL13mavlink_delaymE8last_1hz
|
||||
00000004 b _ZZL13mavlink_delaymE8last_3hz
|
||||
00000004 b _ZZL13mavlink_delaymE9last_10hz
|
||||
00000004 b _ZZL13mavlink_delaymE9last_50hz
|
||||
00000004 r _ZZL13print_enabledhE3__c_0
|
||||
00000004 r _ZZL13setup_compasshPKN4Menu3argEE3__c_0
|
||||
00000004 r _ZZL14print_log_menuvE3__c_4
|
||||
00000004 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c
|
||||
00000004 r _ZZL20Log_Read_PerformancevE3__c
|
||||
00000004 r _ZZL8test_adchPKN4Menu3argEE3__c_0
|
||||
00000004 V _ZZN10ParametersC1EvE3__c_32
|
||||
00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c
|
||||
00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_1
|
||||
00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_2
|
||||
00000005 r _ZL22__menu_name__test_menu
|
||||
00000005 r _ZZL10report_imuvE3__c
|
||||
00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_5
|
||||
00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_6
|
||||
00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_7
|
||||
00000005 r _ZZL12Log_Read_RawvE3__c
|
||||
00000005 r _ZZL13Log_Read_ModevE3__c
|
||||
00000005 r _ZZL14print_log_menuvE3__c_0
|
||||
00000005 r _ZZL14print_log_menuvE3__c_3
|
||||
00000005 r _ZZL14print_log_menuvE3__c_7
|
||||
00000005 r _ZZL14print_log_menuvE3__c_8
|
||||
00000005 r _ZZL8test_adchPKN4Menu3argEE3__c
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_35
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_36
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_37
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_38
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_49
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_50
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_51
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_52
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_53
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_54
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_55
|
||||
00000005 V _ZZN10ParametersC1EvE3__c_56
|
||||
00000005 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_0
|
||||
00000005 r _ZZN11GCS_MAVLINKC1EjE3__c
|
||||
00000005 r _ZZN11GCS_MAVLINKC1EjE3__c_0
|
||||
00000005 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_2
|
||||
00000006 T _Z17mavlink_send_text17mavlink_channel_thPKc
|
||||
00000006 r _ZL23__menu_name__setup_menu
|
||||
00000006 r _ZZL10report_gpsvE3__c
|
||||
00000006 r _ZZL11report_helivE3__c
|
||||
00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c
|
||||
00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c_0
|
||||
00000006 r _ZZL11zero_eepromvE3__c_0
|
||||
00000006 r _ZZL13Log_Read_ModevE3__c_0
|
||||
00000006 r _ZZL14print_log_menuvE3__c_5
|
||||
00000006 r _ZZL14print_log_menuvE3__c_6
|
||||
00000006 V _ZZN10ParametersC1EvE3__c_33
|
||||
00000006 t put_float_by_index
|
||||
00000006 T setup
|
||||
00000007 b _ZL10setup_menu
|
||||
00000007 b _ZL12planner_menu
|
||||
00000007 b _ZL8log_menu
|
||||
00000007 b _ZL9main_menu
|
||||
00000007 b _ZL9test_menu
|
||||
00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_11
|
||||
00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_13
|
||||
00000007 r _ZZL12report_framevE3__c
|
||||
00000007 r _ZZL12report_radiovE3__c
|
||||
00000007 r _ZZL12report_sonarvE3__c
|
||||
00000007 r _ZZL13print_enabledhE3__c_1
|
||||
00000007 r _ZZL7test_wphPKN4Menu3argEE3__c_2
|
||||
00000007 V _ZZN10ParametersC1EvE3__c_57
|
||||
00000007 V _ZZN10ParametersC1EvE3__c_58
|
||||
00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_6
|
||||
00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_7
|
||||
00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_8
|
||||
00000008 t _ZL11setup_erasehPKN4Menu3argE
|
||||
00000008 r _ZL25__menu_name__planner_menu
|
||||
00000008 r _ZZL11select_logshPKN4Menu3argEE3__c_12
|
||||
00000008 r _ZZL14print_log_menuvE3__c_10
|
||||
00000008 r _ZZL19report_batt_monitorvE3__c_0
|
||||
00000008 r _ZZL19report_batt_monitorvE3__c_1
|
||||
00000008 r _ZZL7test_wphPKN4Menu3argEE3__c_1
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_10
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_17
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_18
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_67
|
||||
00000008 V _ZZN10ParametersC1EvE3__c_69
|
||||
00000008 r _ZZN11GCS_MAVLINKC1EjE3__c_3
|
||||
00000009 r _ZZL11report_gyrovE3__c_0
|
||||
00000009 r _ZZL12print_switchhhE3__c
|
||||
00000009 r _ZZL14print_log_menuvE3__c_11
|
||||
00000009 r _ZZL14print_log_menuvE3__c_9
|
||||
00000009 r _ZZL14report_compassvE3__c
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_11
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_12
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_23
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_24
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_25
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_26
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_27
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_28
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_34
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_39
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_40
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_41
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_42
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_43
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_44
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_45
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_46
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_62
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_63
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_64
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_65
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_66
|
||||
00000009 V _ZZN10ParametersC1EvE3__c_68
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_1
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_2
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_4
|
||||
00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_5
|
||||
0000000a r _ZZL10test_relayhPKN4Menu3argEE3__c
|
||||
0000000a r _ZZL11test_tuninghPKN4Menu3argEE3__c
|
||||
0000000a r _ZZL13start_new_logvE3__c
|
||||
0000000a r _ZZL14print_log_menuvE3__c_13
|
||||
0000000a r _ZZL16Log_Read_StartupvE3__c
|
||||
0000000a r _ZZL7test_wphPKN4Menu3argEE3__c
|
||||
0000000a r _ZZL8test_maghPKN4Menu3argEE3__c_0
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_14
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_29
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_48
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_59
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_60
|
||||
0000000a V _ZZN10ParametersC1EvE3__c_61
|
||||
0000000b r _ZZL10test_relayhPKN4Menu3argEE3__c_0
|
||||
0000000b r _ZZL19report_batt_monitorvE3__c_2
|
||||
0000000b r _ZZL8set_modehE3__c
|
||||
0000000b V _ZZN10ParametersC1EvE3__c_8
|
||||
0000000c t _ZL12process_logshPKN4Menu3argE
|
||||
0000000c b _ZL15heli_rollFactor
|
||||
0000000c b _ZL16heli_pitchFactor
|
||||
0000000c b _ZL5omega
|
||||
0000000c t _ZL9test_modehPKN4Menu3argE
|
||||
0000000c T _ZN11GCS_MAVLINK9send_textEhPKc
|
||||
0000000c V _ZTV3IMU
|
||||
0000000c r _ZZL12report_framevE3__c_0
|
||||
0000000c r _ZZL9test_barohPKN4Menu3argEE3__c
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_2
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_30
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_47
|
||||
0000000c V _ZZN10ParametersC1EvE3__c_9
|
||||
0000000d r _ZZL10verify_RTLvE3__c
|
||||
0000000d r _ZZL11select_logshPKN4Menu3argEE3__c_2
|
||||
0000000d r _ZZL12test_batteryhPKN4Menu3argEE3__c
|
||||
0000000d r _ZZL14startup_groundvE3__c
|
||||
0000000d r _ZZL7test_wphPKN4Menu3argEE3__c_3
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_16
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_19
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_21
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_3
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_31
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_5
|
||||
0000000d V _ZZN10ParametersC1EvE3__c_6
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t _GLOBAL__D_Serial
|
||||
0000000e t _GLOBAL__I_Serial
|
||||
0000000e V _ZTV10AP_Float16
|
||||
0000000e V _ZTV7AP_VarAIfLh6EE
|
||||
0000000e V _ZTV7AP_VarSI7Matrix3IfEE
|
||||
0000000e V _ZTV7AP_VarSI7Vector3IfEE
|
||||
0000000e V _ZTV7AP_VarTIaE
|
||||
0000000e V _ZTV7AP_VarTIfE
|
||||
0000000e V _ZTV7AP_VarTIiE
|
||||
0000000e r _ZZL10erase_logshPKN4Menu3argEE3__c_0
|
||||
0000000e r _ZZL10setup_helihPKN4Menu3argEE3__c
|
||||
0000000e r _ZZL10setup_modehPKN4Menu3argEE3__c
|
||||
0000000e r _ZZL10test_sonarhPKN4Menu3argEE3__c_0
|
||||
0000000e r _ZZL11select_logshPKN4Menu3argEE3__c_1
|
||||
0000000e r _ZZL14print_log_menuvE3__c_2
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_0
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_1
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_2
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_3
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_4
|
||||
0000000e r _ZZL18print_radio_valuesvE3__c_5
|
||||
0000000e r _ZZL19report_batt_monitorvE3__c_3
|
||||
0000000e r _ZZL19report_flight_modesvE3__c
|
||||
0000000e r _ZZL8dump_loghPKN4Menu3argEE3__c
|
||||
0000000e V _ZZN10ParametersC1EvE3__c
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_0
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_1
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_13
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_15
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_20
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_22
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_4
|
||||
0000000e V _ZZN10ParametersC1EvE3__c_7
|
||||
0000000f b _ZL11current_loc
|
||||
0000000f b _ZL12next_command
|
||||
0000000f r _ZL22__menu_name__main_menu
|
||||
0000000f b _ZL4home
|
||||
0000000f b _ZL7next_WP
|
||||
0000000f b _ZL7prev_WP
|
||||
0000000f b _ZL9guided_WP
|
||||
0000000f b _ZL9simple_WP
|
||||
0000000f b _ZL9target_WP
|
||||
0000000f r _ZZL11report_helivE3__c_5
|
||||
0000000f r _ZZL14print_log_menuvE3__c
|
||||
0000000f r _ZZL14print_log_menuvE3__c_1
|
||||
0000000f r _ZZL14report_versionvE3__c
|
||||
0000000f r _ZZL19report_batt_monitorvE3__c
|
||||
0000000f r _ZZL8test_imuhPKN4Menu3argEE3__c
|
||||
0000000f V _ZZN13AP_IMU_OilpanC1EP6AP_ADCjE3__c
|
||||
00000010 r _ZL21planner_menu_commands
|
||||
00000010 b _ZL9motor_out
|
||||
00000010 W _ZNK7AP_VarTIfE13cast_to_floatEv
|
||||
00000010 r _ZZL10test_sonarhPKN4Menu3argEE3__c
|
||||
00000010 r _ZZL11report_gyrovE3__c
|
||||
00000010 r _ZZL11report_helivE3__c_6
|
||||
00000010 r _ZZL14report_compassvE3__c_0
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r _ZZL10erase_logshPKN4Menu3argEE3__c
|
||||
00000011 r _ZZL10setup_helihPKN4Menu3argEE3__c_8
|
||||
00000011 r _ZZL11zero_eepromvE3__c
|
||||
00000011 r _ZZL15update_commandsvE3__c
|
||||
00000011 r _ZZL17Log_Read_AttitudevE3__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r _ZL19flight_mode_strings
|
||||
00000012 W _ZN10AP_Float16D1Ev
|
||||
00000012 W _ZN7AP_VarAIfLh6EED1Ev
|
||||
00000012 W _ZN7AP_VarSI7Matrix3IfEED1Ev
|
||||
00000012 W _ZN7AP_VarSI7Vector3IfEED1Ev
|
||||
00000012 W _ZN7AP_VarTIaED1Ev
|
||||
00000012 W _ZN7AP_VarTIfED1Ev
|
||||
00000012 W _ZN7AP_VarTIiED1Ev
|
||||
00000012 W _ZNK7AP_VarTIaE9serializeEPvj
|
||||
00000012 r _ZZL10print_donevE3__c
|
||||
00000012 r _ZZL10setup_helihPKN4Menu3argEE3__c_12
|
||||
00000012 r _ZZL11select_logshPKN4Menu3argEE3__c
|
||||
00000012 r _ZZL11setup_framehPKN4Menu3argEE3__c_3
|
||||
00000012 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c
|
||||
00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_13
|
||||
00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_6
|
||||
00000013 r _ZZL11report_helivE3__c_1
|
||||
00000013 r _ZZL11report_helivE3__c_2
|
||||
00000013 r _ZZL11report_helivE3__c_3
|
||||
00000013 r _ZZL11report_helivE3__c_4
|
||||
00000013 r _ZZL13setup_compasshPKN4Menu3argEE3__c_1
|
||||
00000013 r _ZZL14change_commandhE3__c
|
||||
00000013 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c_0
|
||||
00000014 W _ZN7AP_VarTIaE11unserializeEPvj
|
||||
00000014 W _ZNK7AP_VarTIaE13cast_to_floatEv
|
||||
00000014 W _ZNK7AP_VarTIiE13cast_to_floatEv
|
||||
00000014 r _ZZL10setup_helihPKN4Menu3argEE3__c_1
|
||||
00000014 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_1
|
||||
00000014 r _ZZL8test_trihPKN4Menu3argEE3__c
|
||||
00000015 r _ZZL12map_baudrateamE3__c
|
||||
00000015 r _ZZL14init_ardupilotvE3__c_0
|
||||
00000015 r _ZZL15Log_Read_MotorsvE3__c
|
||||
00000015 r _ZZL15print_hit_entervE3__c
|
||||
00000015 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c_0
|
||||
00000016 r _ZZL10setup_helihPKN4Menu3argEE3__c_0
|
||||
00000016 r _ZZL14init_ardupilotvE3__c
|
||||
00000016 r _ZZN11GCS_MAVLINK6updateEvE3__c
|
||||
00000016 B sonar
|
||||
00000018 b _ZL11baro_filter
|
||||
00000018 t _ZL11setup_accelhPKN4Menu3argE
|
||||
00000018 T _ZN11GCS_MAVLINK12send_messageEhm
|
||||
00000018 W _ZNK7AP_VarTIiE9serializeEPvj
|
||||
00000019 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_1
|
||||
00000019 r _ZZN11GCS_MAVLINK6updateEvE3__c_0
|
||||
0000001a t _ZL10clear_ledsv
|
||||
0000001a r _ZZL14print_log_menuvE3__c_12
|
||||
0000001b r _ZZL10setup_helihPKN4Menu3argEE3__c_2
|
||||
0000001b r _ZZL11report_helivE3__c_0
|
||||
0000001c W _ZN7AP_VarAIfLh6EE11unserializeEPvj
|
||||
0000001c W _ZN7AP_VarSI7Matrix3IfEE11unserializeEPvj
|
||||
0000001c W _ZN7AP_VarSI7Vector3IfEE11unserializeEPvj
|
||||
0000001c W _ZN7AP_VarTIiE11unserializeEPvj
|
||||
0000001c W _ZNK7AP_VarAIfLh6EE9serializeEPvj
|
||||
0000001c W _ZNK7AP_VarSI7Matrix3IfEE9serializeEPvj
|
||||
0000001c W _ZNK7AP_VarSI7Vector3IfEE9serializeEPvj
|
||||
0000001c b _ZZ26mavlink_get_channel_statusE16m_mavlink_status
|
||||
0000001e r _ZZL11report_helivE3__c_7
|
||||
0000001e r _ZZL16Log_Read_OptflowvE3__c
|
||||
0000001f r _ZZL8test_maghPKN4Menu3argEE3__c
|
||||
00000020 r _ZZL12test_currenthPKN4Menu3argEE3__c
|
||||
00000021 r _ZZL10setup_helihPKN4Menu3argEE3__c_7
|
||||
00000021 r _ZZL14print_log_menuvE3__c_14
|
||||
00000021 r _ZZL14report_compassvE3__c_1
|
||||
00000021 r _ZZL16Log_Read_CurrentvE3__c
|
||||
00000022 t _ZL12print_blanksi
|
||||
00000022 W _ZN10AP_Float16D0Ev
|
||||
00000022 W _ZN7AP_VarAIfLh6EED0Ev
|
||||
00000022 W _ZN7AP_VarSI7Matrix3IfEED0Ev
|
||||
00000022 W _ZN7AP_VarSI7Vector3IfEED0Ev
|
||||
00000022 W _ZN7AP_VarTIaED0Ev
|
||||
00000022 W _ZN7AP_VarTIfED0Ev
|
||||
00000022 W _ZN7AP_VarTIiED0Ev
|
||||
00000023 r _ZZL10setup_helihPKN4Menu3argEE3__c_4
|
||||
00000023 r _ZZL10setup_modehPKN4Menu3argEE3__c_1
|
||||
00000023 r _ZZL18print_gyro_offsetsvE3__c
|
||||
00000024 r _ZZL10setup_helihPKN4Menu3argEE3__c_3
|
||||
00000024 r _ZZL19print_accel_offsetsvE3__c
|
||||
00000025 r _ZZL13setup_factoryhPKN4Menu3argEE3__c_0
|
||||
00000026 t _ZL10print_donev
|
||||
00000026 t _ZL15print_hit_enterv
|
||||
00000026 t _ZL16Log_Read_Startupv
|
||||
00000026 r _ZZL19Log_Read_Nav_TuningvE3__c
|
||||
00000026 B barometer
|
||||
00000027 r _ZZL9test_xbeehPKN4Menu3argEE3__c
|
||||
00000028 t _ZL12test_batteryhPKN4Menu3argE
|
||||
00000028 t _ZL14main_menu_helphPKN4Menu3argE
|
||||
00000028 t _ZL8help_loghPKN4Menu3argE
|
||||
00000028 W _ZN7AP_VarTIfE11unserializeEPvj
|
||||
00000028 W _ZNK7AP_VarTIfE9serializeEPvj
|
||||
00000028 r _ZZL12Log_Read_CmdvE3__c
|
||||
00000029 r _ZZL10setup_helihPKN4Menu3argEE3__c_9
|
||||
00000029 r _ZZL10setup_modehPKN4Menu3argEE3__c_0
|
||||
00000029 r _ZZL8test_gpshPKN4Menu3argEE3__c
|
||||
0000002a t _ZL11reset_nav_Iv
|
||||
0000002a t _ZL17setup_declinationhPKN4Menu3argE
|
||||
0000002b r _ZZL12planner_modehPKN4Menu3argEE3__c
|
||||
0000002c t _ZL7freeRAMv
|
||||
0000002e t _ZL12setup_motorshPKN4Menu3argE
|
||||
0000002e t _ZL13print_dividerv
|
||||
0000002e t _ZL9send_ratejj
|
||||
0000002e W _ZN12AP_Var_groupC1EjPK11prog_char_th
|
||||
0000002f r _ZZL10test_radiohPKN4Menu3argEE3__c
|
||||
00000030 t _ZL12planner_modehPKN4Menu3argE
|
||||
00000030 t put_int32_t_by_index
|
||||
00000032 T _ZN11GCS_MAVLINK4initEP12BetterStream
|
||||
00000032 r _ZZL10setup_helihPKN4Menu3argEE3__c_5
|
||||
00000034 t _ZL14heli_get_servoi
|
||||
00000034 W _ZNK10AP_Float169serializeEPvj
|
||||
00000035 r _ZZL14test_radio_pwmhPKN4Menu3argEE3__c
|
||||
00000036 t _ZL12report_radiov
|
||||
00000036 r _ZZL12Log_Read_GPSvE3__c
|
||||
00000037 r _ZZL8print_wpP8LocationhE3__c
|
||||
00000038 t _ZL20init_throttle_cruisev
|
||||
00000038 r _ZZL11setup_radiohPKN4Menu3argEE3__c
|
||||
00000038 r _ZZL13setup_factoryhPKN4Menu3argEE3__c
|
||||
0000003a t _ZL10report_gpsv
|
||||
0000003a t _ZL10report_imuv
|
||||
0000003a t _ZL12comm_send_ch17mavlink_channel_th
|
||||
0000003a W _ZN3PIDD1Ev
|
||||
0000003c W _ZN10RC_ChannelD1Ev
|
||||
0000003d r _ZZL23Log_Read_Control_TuningvE3__c
|
||||
0000003d B g_gps_driver
|
||||
0000003e t _ZL10verify_RTLv
|
||||
0000003e T _ZN11GCS_MAVLINK9send_textEhPK11prog_char_t
|
||||
0000003e W _ZN7AP_VarTIaEC1EajPK11prog_char_th
|
||||
00000040 W _ZN10AP_Float1611unserializeEPvj
|
||||
00000042 T _Z10output_minv
|
||||
00000042 t _ZL12report_sonarv
|
||||
00000042 r _ZZL10setup_helihPKN4Menu3argEE3__c_10
|
||||
00000044 W _ZN7AP_VarTIiEC1EijPK11prog_char_th
|
||||
0000004a t _ZL19read_control_switchv
|
||||
0000004a W _ZN7AP_VarTIiEC1EP12AP_Var_groupjiPK11prog_char_th
|
||||
0000004a t mavlink_msg_waypoint_current_send
|
||||
0000004a t mavlink_update_checksum
|
||||
0000004c t _ZL10setup_showhPKN4Menu3argE
|
||||
0000004c t _ZL14update_nav_yawv
|
||||
0000004c B imu
|
||||
0000004e t mavlink_msg_waypoint_ack_send
|
||||
00000050 t _ZL14report_versionv
|
||||
00000050 r _ZL17log_menu_commands
|
||||
00000050 r _ZL18main_menu_commands
|
||||
00000050 t _ZL9read_AHRSv
|
||||
00000050 T _ZN11GCS_MAVLINK15_find_parameterEj
|
||||
00000050 t mavlink_msg_waypoint_request_send
|
||||
00000052 t _ZL14change_commandh
|
||||
00000054 t _ZL13print_enabledh
|
||||
00000054 t _ZL17update_motor_ledsv
|
||||
00000054 t _ZL19report_flight_modesv
|
||||
00000055 r _ZZL14main_menu_helphPKN4Menu3argEE3__c
|
||||
00000055 r _ZZL17setup_flightmodeshPKN4Menu3argEE3__c
|
||||
00000056 t _ZL10readSwitchv
|
||||
00000056 t _ZL13dancing_lightv
|
||||
00000057 r _ZZL8help_loghPKN4Menu3argEE3__c
|
||||
00000058 t _ZL11test_tuninghPKN4Menu3argE
|
||||
00000058 t _ZL14startup_groundv
|
||||
00000058 t _ZL18Log_Write_Attitudev
|
||||
0000005a t _ZL12report_framev
|
||||
0000005a t mavlink_msg_statustext_send
|
||||
0000005c t _ZL12get_num_logsv
|
||||
0000005c t _ZL9setup_eschPKN4Menu3argE
|
||||
0000005e t _ZL16update_GPS_lightv
|
||||
0000005e t _ZL18radio_input_switchv
|
||||
0000005e T _ZN11GCS_MAVLINK17_count_parametersEv
|
||||
0000005f r _ZZL10setup_helihPKN4Menu3argEE3__c_11
|
||||
00000060 t _ZL12print_switchhh
|
||||
00000060 W _ZN10AP_Float16C1EP12AP_Var_groupjfPK11prog_char_th
|
||||
00000064 t _ZL9test_xbeehPKN4Menu3argE
|
||||
00000068 t _ZL11zero_eepromv
|
||||
00000068 t _ZL18find_last_log_pagei
|
||||
0000006a t _ZL20read_num_from_serialv
|
||||
0000006a W _ZN11GCS_MAVLINKD1Ev
|
||||
0000006c t _ZL11setup_sonarhPKN4Menu3argE
|
||||
00000074 t _ZL19output_motors_armedv
|
||||
00000078 t _ZL18setup_batt_monitorhPKN4Menu3argE
|
||||
0000007a t _ZL13setup_factoryhPKN4Menu3argE
|
||||
0000007a t _ZL18get_nav_yaw_offsetii
|
||||
0000007a t _ZL9test_barohPKN4Menu3argE
|
||||
0000007e t _ZL11test_rawgpshPKN4Menu3argE
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t _ZL6do_RTLv
|
||||
00000084 t mavlink_send_uart
|
||||
00000086 t _ZL17Log_Read_Attitudev
|
||||
00000088 t _ZL12Log_Read_Rawv
|
||||
0000008c t _ZL11setup_framehPKN4Menu3argE
|
||||
0000008c t _ZL18print_gyro_offsetsv
|
||||
0000008c t _ZL19print_accel_offsetsv
|
||||
00000090 t _ZL11report_gyrov
|
||||
00000095 r _ZZL14init_ardupilotvE3__c_1
|
||||
00000096 t _ZL12map_baudrateam
|
||||
00000096 t _ZL8print_wpP8Locationh
|
||||
0000009a t _ZL12init_compassv
|
||||
0000009a t _ZL14init_barometerv
|
||||
0000009a t _ZL15Log_Read_Motorsv
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t _ZL10setup_modehPKN4Menu3argE
|
||||
0000009e t _ZL13Log_Read_Modev
|
||||
0000009e t _ZL13Log_Write_CmdhP8Location
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000a6 t mavlink_msg_param_value_send
|
||||
000000a8 t _ZL10test_sonarhPKN4Menu3argE
|
||||
000000ac t _ZL20Log_Read_Performancev
|
||||
000000ae t _ZL13auto_throttlev
|
||||
000000b0 t _ZL10read_radiov
|
||||
000000b0 t _ZL8dump_loghPKN4Menu3argE
|
||||
000000b2 t _ZL10erase_logshPKN4Menu3argE
|
||||
000000b4 t _ZL10test_relayhPKN4Menu3argE
|
||||
000000b4 t _ZL11planner_gcshPKN4Menu3argE
|
||||
000000b6 t _ZL18get_log_boundarieshRiS_
|
||||
000000b7 B compass
|
||||
000000c2 t _ZL11test_eedumphPKN4Menu3argE
|
||||
000000c2 t _ZL13setup_compasshPKN4Menu3argE
|
||||
000000c4 t _ZL12get_distanceP8LocationS0_
|
||||
000000c4 t _ZL13update_eventsv
|
||||
000000c4 r _ZZL9setup_eschPKN4Menu3argEE3__c
|
||||
000000c6 t _ZL8Log_Readii
|
||||
000000c6 t _ZL8test_trihPKN4Menu3argE
|
||||
000000c7 B dcm
|
||||
000000c8 t _ZL14read_barometerv
|
||||
000000ca t _ZL12get_throttlei
|
||||
000000ce W _ZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKi
|
||||
000000d0 t _ZL11get_bearingP8LocationS0_
|
||||
000000d8 t _ZL10test_radiohPKN4Menu3argE
|
||||
000000dc t _ZL18read_baro_filteredv
|
||||
000000dc t _ZL8test_adchPKN4Menu3argE
|
||||
000000e4 t _ZL14test_radio_pwmhPKN4Menu3argE
|
||||
000000e4 t _ZL16Log_Read_Optflowv
|
||||
000000e6 t _ZL17setup_flightmodeshPKN4Menu3argE
|
||||
000000e6 t _ZL19Log_Read_Nav_Tuningv
|
||||
000000e6 t mavlink_finalize_message_chan
|
||||
000000e8 t _ZL16Log_Read_Currentv
|
||||
000000ec t put_uint64_t_by_index
|
||||
000000ee t _ZL19report_batt_monitorv
|
||||
000000f0 r _ZL19setup_menu_commands
|
||||
000000f2 t _ZL18get_stabilize_rolll
|
||||
000000f2 t _ZL19get_stabilize_pitchl
|
||||
000000f6 t _ZL12Log_Read_Cmdv
|
||||
000000fc T _ZN11GCS_MAVLINK12_queued_sendEv
|
||||
00000108 t _ZL10setup_gyrohPKN4Menu3argE
|
||||
0000010a t _ZL8test_gpshPKN4Menu3argE
|
||||
0000010c W _ZN10RC_ChannelC1EjPK11prog_char_t
|
||||
00000112 t _ZL12test_currenthPKN4Menu3argE
|
||||
00000112 t _ZL15adjust_altitudev
|
||||
00000112 T _ZN11GCS_MAVLINKC1Ej
|
||||
00000112 T _ZN11GCS_MAVLINKC2Ej
|
||||
00000118 t _ZL22set_command_with_index8Locationi
|
||||
00000120 r _ZL18test_menu_commands
|
||||
00000128 t _ZL22get_command_with_indexi
|
||||
0000012c t _ZL23Log_Read_Control_Tuningv
|
||||
00000130 t _ZL14report_compassv
|
||||
00000144 t _ZL15calc_nav_outputv
|
||||
0000014c T _ZN11GCS_MAVLINK6updateEv
|
||||
00000150 t _ZL11update_trigv
|
||||
00000152 t _ZL11set_next_WPP8Location
|
||||
00000156 t _ZL12Log_Read_GPSv
|
||||
0000015c t _ZL10arm_motorsv
|
||||
00000166 t _ZL11select_logshPKN4Menu3argE
|
||||
0000016c t _ZL15update_commandsv
|
||||
00000170 t _ZL8test_maghPKN4Menu3argE
|
||||
0000017e t _ZL17get_stabilize_yawlf
|
||||
0000018e T _ZN11GCS_MAVLINK16data_stream_sendEjj
|
||||
00000196 t _ZL8set_modeh
|
||||
000001a0 t _ZL9init_homev
|
||||
000001a8 t _ZL18print_radio_valuesv
|
||||
000001ae t _ZL13mavlink_delaym
|
||||
000001b8 t _ZL8test_imuhPKN4Menu3argE
|
||||
000001c4 t _ZL17update_crosstrackv
|
||||
000001ce t _ZL13start_new_logv
|
||||
0000020c b _ZZ18mavlink_parse_charE17m_mavlink_message
|
||||
0000021c t _ZL7test_wphPKN4Menu3argE
|
||||
00000228 t _ZL11setup_radiohPKN4Menu3argE
|
||||
00000264 t _ZL13update_nav_wpv
|
||||
00000288 t _ZL13calc_rate_navi
|
||||
000002b8 t _ZL15heli_init_swashv
|
||||
000002d0 t _ZL11report_heliv
|
||||
0000031e t _ZL12read_batteryv
|
||||
00000368 t _ZL15heli_move_swashiiii
|
||||
00000382 t _ZL14print_log_menuv
|
||||
0000055e t mavlink_parse_char
|
||||
00000628 t _ZL14init_ardupilotv
|
||||
00000718 t _ZL10setup_helihPKN4Menu3argE
|
||||
00000800 t _Z41__static_initialization_and_destruction_0ii
|
||||
00000866 T _Z26update_current_flight_modev
|
||||
000008f4 t _ZL20process_next_commandv
|
||||
0000097e W _ZN10ParametersC1Ev
|
||||
00000b3c b _ZL1g
|
||||
00001148 T _ZN11GCS_MAVLINK13handleMessageEP17__mavlink_message
|
||||
000015be T _Z20mavlink_send_message17mavlink_channel_thmj
|
||||
00001aae T loop
|
|
@ -0,0 +1,343 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,611 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 t setup_accel(unsigned char, Menu::arg const*)
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000052 t report_version()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000062 t print_switch(unsigned char, unsigned char)
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007c t test_baro(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t init_compass()
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a0 t Log_Read_Mode()
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000c7 B dcm
|
||||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000de t test_adc(unsigned char, Menu::arg const*)
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001e2 t arm_motors()
|
||||
000001fc t setup_motors(unsigned char, Menu::arg const*)
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
0000212a T loop
|
|
@ -0,0 +1,343 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,611 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 t setup_accel(unsigned char, Menu::arg const*)
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 t report_version()
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t print_switch(unsigned char, unsigned char)
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007a t test_baro(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t init_compass()
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Read_Mode()
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000a8 t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000c7 B dcm
|
||||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000dc t test_adc(unsigned char, Menu::arg const*)
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001e2 t arm_motors()
|
||||
000001fc t setup_motors(unsigned char, Menu::arg const*)
|
||||
00000200 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00002128 T loop
|
|
@ -0,0 +1,355 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:135: warning: 'void Log_Write_Raw()' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:141: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/Log.pde:760: warning: 'void Log_Write_Attitude()' defined but not used
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void init_barometer()' declared 'static' but never defined
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:273: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||
autogenerated:275: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:353: warning: 'old_altitude' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:371: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:372: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:373: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:378: warning: 'baro_alt' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:24: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,599 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b sonar_alt
|
||||
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b current_amps
|
||||
00000004 b gps_base_alt
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 W AP_IMU_Shim::update()
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t setup_accel(unsigned char, Menu::arg const*)
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for AP_IMU_Shim
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r arm_motors()::__c
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r arm_motors()::__c
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000012 B adc
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 t startup_ground()
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000028 B imu
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 t _MAV_RETURN_float
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003a B g_gps_driver
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000052 t report_version()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000057 B dcm
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t _mavlink_send_uart
|
||||
00000062 t print_switch(unsigned char, unsigned char)
|
||||
00000064 t print_gyro_offsets()
|
||||
00000064 t print_accel_offsets()
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
00000090 t init_compass()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a0 t Log_Read_Mode()
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ab B compass
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
00000100 r test_menu_commands
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000126 t arm_motors()
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
0000029e t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
00000568 t __static_initialization_and_destruction_0(int, int)
|
||||
000005ea T update_roll_pitch_mode()
|
||||
00000616 t init_ardupilot()
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011be t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001494 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001a6a T loop
|
|
@ -0,0 +1,355 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:135: warning: 'void Log_Write_Raw()' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:141: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/Log.pde:760: warning: 'void Log_Write_Attitude()' defined but not used
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
autogenerated:270: warning: 'void ReadSCP1000()' declared 'static' but never defined
|
||||
autogenerated:271: warning: 'void init_barometer()' declared 'static' but never defined
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
autogenerated:273: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||
autogenerated:274: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||
autogenerated:275: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:353: warning: 'old_altitude' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:371: warning: 'abs_pressure' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:372: warning: 'ground_pressure' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:373: warning: 'ground_temperature' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:378: warning: 'baro_alt' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:24: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,599 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b sonar_alt
|
||||
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long))
|
||||
00000002 W AP_IMU_Shim::init_gyro(void (*)(unsigned long))
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b current_amps
|
||||
00000004 b gps_base_alt
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 W AP_IMU_Shim::update()
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t setup_accel(unsigned char, Menu::arg const*)
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for AP_IMU_Shim
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r arm_motors()::__c
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r arm_motors()::__c
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000012 B adc
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 t startup_ground()
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000028 B imu
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 t _MAV_RETURN_float
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003a B g_gps_driver
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 t report_version()
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000057 B dcm
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t print_switch(unsigned char, unsigned char)
|
||||
00000060 t _mavlink_send_uart
|
||||
00000064 t print_gyro_offsets()
|
||||
00000064 t print_accel_offsets()
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
00000090 t init_compass()
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Read_Mode()
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000a8 t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ab B compass
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
00000100 r test_menu_commands
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000126 t arm_motors()
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
00000200 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
0000029e t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
00000568 t __static_initialization_and_destruction_0(int, int)
|
||||
000005ea T update_roll_pitch_mode()
|
||||
00000616 t init_ardupilot()
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011be t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001494 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
00001a68 T loop
|
|
@ -0,0 +1,343 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,611 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 t setup_accel(unsigned char, Menu::arg const*)
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000052 t report_version()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000062 t print_switch(unsigned char, unsigned char)
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007c t test_baro(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t init_compass()
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a0 t Log_Read_Mode()
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000c7 B dcm
|
||||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000de t test_adc(unsigned char, Menu::arg const*)
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001ff8 T loop
|
|
@ -0,0 +1,343 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,611 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r report_frame()::__c
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 t setup_accel(unsigned char, Menu::arg const*)
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 t report_version()
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t print_switch(unsigned char, unsigned char)
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007a t test_baro(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
0000008e t dump_log(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t init_compass()
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Read_Mode()
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000a8 t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000c7 B dcm
|
||||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000dc t test_adc(unsigned char, Menu::arg const*)
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001b6 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
0000021c t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000382 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001ff6 T loop
|
|
@ -0,0 +1,343 @@
|
|||
|
||||
%%%% Making all in ArduCopterMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
%% ArduCopterMega.cpp
|
||||
%% ArduCopterMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1412: warning: 'void tuning()' defined but not used
|
||||
autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined
|
||||
autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined
|
||||
autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined
|
||||
autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined
|
||||
autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
|
||||
autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined
|
||||
autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined
|
||||
autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined
|
||||
autogenerated:92: warning: 'void print_position()' declared 'static' but never defined
|
||||
autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
|
||||
autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined
|
||||
autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
|
||||
autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
|
||||
autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:46: warning: 'void low_battery_event()' defined but not used
|
||||
autogenerated:210: warning: 'void heli_init_swash()' declared 'static' but never defined
|
||||
autogenerated:211: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
|
||||
autogenerated:212: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
|
||||
autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined
|
||||
autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used
|
||||
autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined
|
||||
autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
|
||||
autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
|
||||
autogenerated:286: warning: 'void report_heli()' declared 'static' but never defined
|
||||
autogenerated:287: warning: 'void report_gyro()' declared 'static' but never defined
|
||||
autogenerated:295: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
|
||||
autogenerated:296: warning: 'int read_num_from_serial()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used
|
||||
autogenerated:310: warning: 'void init_optflow()' declared 'static' but never defined
|
||||
autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never defined
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1040: warning: 'void print_motor_out()' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:442: warning: 'undo_event' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'condition_rate' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:462: warning: 'simple_WP' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:467: warning: 'optflow_offset' defined but not used
|
||||
/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:468: warning: 'new_location' defined but not used
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_PI/APM_PI.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function
|
||||
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
|
||||
/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduCopterMega.elf
|
||||
%% ArduCopterMega.eep
|
||||
%% ArduCopterMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega'
|
||||
|
||||
%%%% Making all in ArduPilotMega/ %%%%
|
||||
|
||||
make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
||||
%% ArduPilotMega.cpp
|
||||
%% ArduPilotMega.o
|
||||
In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||
%% libraries/APM_BMP085/APM_BMP085.o
|
||||
%% libraries/APM_RC/APM_RC.o
|
||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||
%% libraries/AP_ADC/AP_ADC.o
|
||||
%% libraries/AP_ADC/AP_ADC_HIL.o
|
||||
%% libraries/AP_Common/AP_Common.o
|
||||
%% libraries/AP_Common/AP_Loop.o
|
||||
%% libraries/AP_Common/AP_MetaClass.o
|
||||
%% libraries/AP_Common/AP_Var.o
|
||||
%% libraries/AP_Common/AP_Var_menufuncs.o
|
||||
%% libraries/AP_Common/c++.o
|
||||
%% libraries/AP_Common/menu.o
|
||||
%% libraries/AP_Compass/AP_Compass_HIL.o
|
||||
%% libraries/AP_Compass/AP_Compass_HMC5843.o
|
||||
%% libraries/AP_Compass/Compass.o
|
||||
%% libraries/AP_DCM/AP_DCM.o
|
||||
%% libraries/AP_DCM/AP_DCM_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_406.o
|
||||
%% libraries/AP_GPS/AP_GPS_Auto.o
|
||||
%% libraries/AP_GPS/AP_GPS_HIL.o
|
||||
%% libraries/AP_GPS/AP_GPS_IMU.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK16.o
|
||||
%% libraries/AP_GPS/AP_GPS_MTK.o
|
||||
%% libraries/AP_GPS/AP_GPS_NMEA.o
|
||||
%% libraries/AP_GPS/AP_GPS_SIRF.o
|
||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||
%% libraries/AP_GPS/GPS.o
|
||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||
%% libraries/DataFlash/DataFlash.o
|
||||
In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/FastSerial/BetterStream.o
|
||||
%% libraries/FastSerial/FastSerial.o
|
||||
%% libraries/FastSerial/vprintf.o
|
||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||
%% libraries/ModeFilter/ModeFilter.o
|
||||
%% libraries/PID/PID.o
|
||||
%% libraries/RC_Channel/RC_Channel.o
|
||||
%% libraries/memcheck/memcheck.o
|
||||
%% libraries/FastSerial/ftoa_engine.o
|
||||
%% libraries/FastSerial/ultoa_invert.o
|
||||
%% libraries/SPI/SPI.o
|
||||
In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12:
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
||||
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
|
||||
%% libraries/Wire/Wire.o
|
||||
%% libraries/Wire/utility/twi.o
|
||||
cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C
|
||||
%% arduino/HardwareSerial.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/main.o
|
||||
%% arduino/Print.o
|
||||
%% arduino/Tone.o
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area
|
||||
%% arduino/WMath.o
|
||||
%% arduino/WString.o
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast
|
||||
/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30,
|
||||
from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25:
|
||||
/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to <util/delay.h>."
|
||||
%% arduino/core.a
|
||||
%% ArduPilotMega.elf
|
||||
%% ArduPilotMega.eep
|
||||
%% ArduPilotMega.hex
|
||||
make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega'
|
|
@ -0,0 +1,611 @@
|
|||
00000001 b wp_control
|
||||
00000001 b GPS_enabled
|
||||
00000001 b home_is_set
|
||||
00000001 b motor_armed
|
||||
00000001 b motor_light
|
||||
00000001 b control_mode
|
||||
00000001 b simple_timer
|
||||
00000001 d yaw_tracking
|
||||
00000001 b land_complete
|
||||
00000001 b throttle_mode
|
||||
00000001 b command_may_ID
|
||||
00000001 b wp_verify_byte
|
||||
00000001 b xtrack_enabled
|
||||
00000001 d altitude_sensor
|
||||
00000001 b command_must_ID
|
||||
00000001 b command_yaw_dir
|
||||
00000001 b roll_pitch_mode
|
||||
00000001 b counter_one_herz
|
||||
00000001 b delta_ms_fiftyhz
|
||||
00000001 b did_ground_start
|
||||
00000001 b in_mavlink_delay
|
||||
00000001 b invalid_throttle
|
||||
00000001 b motor_auto_armed
|
||||
00000001 b old_control_mode
|
||||
00000001 b slow_loopCounter
|
||||
00000001 b takeoff_complete
|
||||
00000001 b command_may_index
|
||||
00000001 b oldSwitchPosition
|
||||
00000001 b command_must_index
|
||||
00000001 b delta_ms_fast_loop
|
||||
00000001 d ground_start_count
|
||||
00000001 b medium_loopCounter
|
||||
00000001 b command_yaw_relative
|
||||
00000001 b delta_ms_medium_loop
|
||||
00000001 b event_id
|
||||
00000001 b led_mode
|
||||
00000001 b yaw_mode
|
||||
00000001 b GPS_light
|
||||
00000001 b alt_timer
|
||||
00000001 b loop_step
|
||||
00000001 b trim_flag
|
||||
00000001 b dancing_light()::step
|
||||
00000001 b update_motor_leds()::blink
|
||||
00000001 b radio_input_switch()::bouncer
|
||||
00000001 b read_control_switch()::switch_debouncer
|
||||
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
|
||||
00000001 B mavdelay
|
||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
||||
00000002 b climb_rate
|
||||
00000002 b event_delay
|
||||
00000002 b event_value
|
||||
00000002 b event_repeat
|
||||
00000002 b nav_throttle
|
||||
00000002 b altitude_rate
|
||||
00000002 b gps_fix_count
|
||||
00000002 b velocity_land
|
||||
00000002 b mainLoop_count
|
||||
00000002 b command_yaw_time
|
||||
00000002 b event_undo_value
|
||||
00000002 b command_yaw_speed
|
||||
00000002 b auto_level_counter
|
||||
00000002 b ground_temperature
|
||||
00000002 b superslow_loopCounter
|
||||
00000002 r comma
|
||||
00000002 b g_gps
|
||||
00000002 b G_Dt_max
|
||||
00000002 b airspeed
|
||||
00000002 b baro_alt
|
||||
00000002 b sonar_alt
|
||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
||||
00000002 b arm_motors()::arming_counter
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000002 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000002 B adc
|
||||
00000002 B x_actual_speed
|
||||
00000002 B x_rate_error
|
||||
00000002 B y_actual_speed
|
||||
00000002 B y_rate_error
|
||||
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000003 r print_enabled(unsigned char)::__c
|
||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 d cos_roll_x
|
||||
00000004 b land_start
|
||||
00000004 b long_error
|
||||
00000004 b sin_roll_y
|
||||
00000004 d cos_pitch_x
|
||||
00000004 b event_timer
|
||||
00000004 b loiter_time
|
||||
00000004 b nav_bearing
|
||||
00000004 d scaleLongUp
|
||||
00000004 b sin_pitch_y
|
||||
00000004 b wp_distance
|
||||
00000004 b abs_pressure
|
||||
00000004 b current_amps
|
||||
00000004 b old_altitude
|
||||
00000004 b original_alt
|
||||
00000004 b bearing_error
|
||||
00000004 b current_total
|
||||
00000004 b nav_loopTimer
|
||||
00000004 d scaleLongDown
|
||||
00000004 t test_failsafe(unsigned char, Menu::arg const*)
|
||||
00000004 b altitude_error
|
||||
00000004 b fast_loopTimer
|
||||
00000004 b perf_mon_timer
|
||||
00000004 b target_bearing
|
||||
00000004 d battery_voltage
|
||||
00000004 b command_yaw_end
|
||||
00000004 b condition_start
|
||||
00000004 b condition_value
|
||||
00000004 b ground_pressure
|
||||
00000004 b loiter_time_max
|
||||
00000004 b target_altitude
|
||||
00000004 d battery_voltage1
|
||||
00000004 d battery_voltage2
|
||||
00000004 d battery_voltage3
|
||||
00000004 d battery_voltage4
|
||||
00000004 b medium_loopTimer
|
||||
00000004 b wp_totalDistance
|
||||
00000004 b command_yaw_delta
|
||||
00000004 b command_yaw_start
|
||||
00000004 b fiftyhz_loopTimer
|
||||
00000004 b crosstrack_bearing
|
||||
00000004 b fast_loopTimeStamp
|
||||
00000004 b throttle_integrator
|
||||
00000004 b saved_target_bearing
|
||||
00000004 r __menu_name__log_menu
|
||||
00000004 b command_yaw_start_time
|
||||
00000004 b initial_simple_bearing
|
||||
00000004 d G_Dt
|
||||
00000004 b load
|
||||
00000004 b dTnav
|
||||
00000004 b nav_lat
|
||||
00000004 b nav_lon
|
||||
00000004 b nav_yaw
|
||||
00000004 b old_alt
|
||||
00000004 b auto_yaw
|
||||
00000004 b nav_roll
|
||||
00000004 d cos_yaw_x
|
||||
00000004 b lat_error
|
||||
00000004 b nav_pitch
|
||||
00000004 b sin_yaw_y
|
||||
00000004 b yaw_error
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_3hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_10hz
|
||||
00000004 b mavlink_delay(unsigned long)::last_50hz
|
||||
00000004 r print_enabled(unsigned char)::__c
|
||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r print_log_menu()::__c
|
||||
00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000004 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000004 V Parameters::Parameters()::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r __menu_name__test_menu
|
||||
00000005 r report_imu()::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000005 r Log_Read_Raw()::__c
|
||||
00000005 r Log_Read_Mode()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r print_log_menu()::__c
|
||||
00000005 r test_adc(unsigned char, Menu::arg const*)::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V Parameters::Parameters()::__c
|
||||
00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c
|
||||
00000006 r __menu_name__setup_menu
|
||||
00000006 r report_gps()::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r test_eedump(unsigned char, Menu::arg const*)::__c
|
||||
00000006 r zero_eeprom()::__c
|
||||
00000006 r Log_Read_Mode()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 r print_log_menu()::__c
|
||||
00000006 V Parameters::Parameters()::__c
|
||||
00000007 b setup_menu
|
||||
00000007 b planner_menu
|
||||
00000007 b log_menu
|
||||
00000007 b main_menu
|
||||
00000007 b test_menu
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000007 r report_frame()::__c
|
||||
00000007 r report_radio()::__c
|
||||
00000007 r report_sonar()::__c
|
||||
00000007 r print_enabled(unsigned char)::__c
|
||||
00000007 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 V Parameters::Parameters()::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000008 t setup_erase(unsigned char, Menu::arg const*)
|
||||
00000008 r __menu_name__planner_menu
|
||||
00000008 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r report_frame()::__c
|
||||
00000008 r print_log_menu()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r report_batt_monitor()::__c
|
||||
00000008 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 V Parameters::Parameters()::__c
|
||||
00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r print_switch(unsigned char, unsigned char)::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r print_log_menu()::__c
|
||||
00000009 r report_compass()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 V Parameters::Parameters()::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_tuning(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r start_new_log()::__c
|
||||
0000000a r print_log_menu()::__c
|
||||
0000000a r Log_Read_Startup()::__c
|
||||
0000000a r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a V Parameters::Parameters()::__c
|
||||
0000000a T setup
|
||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||
0000000b r report_frame()::__c
|
||||
0000000b r report_batt_monitor()::__c
|
||||
0000000b V Parameters::Parameters()::__c
|
||||
0000000c t process_logs(unsigned char, Menu::arg const*)
|
||||
0000000c b omega
|
||||
0000000c t test_mode(unsigned char, Menu::arg const*)
|
||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
||||
0000000c V vtable for IMU
|
||||
0000000c r test_baro(unsigned char, Menu::arg const*)::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000c V Parameters::Parameters()::__c
|
||||
0000000d r verify_RTL()::__c
|
||||
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
|
||||
0000000d r startup_ground()::__c
|
||||
0000000d r test_wp(unsigned char, Menu::arg const*)::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d V Parameters::Parameters()::__c
|
||||
0000000d B sonar_mode_filter
|
||||
0000000e t global destructors keyed to Serial
|
||||
0000000e t global constructors keyed to Serial
|
||||
0000000e V vtable for AP_Float16
|
||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||
0000000e V vtable for AP_VarT<signed char>
|
||||
0000000e V vtable for AP_VarT<float>
|
||||
0000000e V vtable for AP_VarT<int>
|
||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
0000000e r print_log_menu()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r print_radio_values()::__c
|
||||
0000000e r report_batt_monitor()::__c
|
||||
0000000e r report_flight_modes()::__c
|
||||
0000000e r dump_log(unsigned char, Menu::arg const*)::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000e V Parameters::Parameters()::__c
|
||||
0000000f b current_loc
|
||||
0000000f b next_command
|
||||
0000000f r __menu_name__main_menu
|
||||
0000000f b home
|
||||
0000000f b next_WP
|
||||
0000000f b prev_WP
|
||||
0000000f b guided_WP
|
||||
0000000f b target_WP
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r print_log_menu()::__c
|
||||
0000000f r report_version()::__c
|
||||
0000000f r report_batt_monitor()::__c
|
||||
0000000f r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||
00000010 r planner_menu_commands
|
||||
00000010 b motor_out
|
||||
00000010 W AP_VarT<float>::cast_to_float() const
|
||||
00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000010 r report_compass()::__c
|
||||
00000010 t mavlink_get_channel_status
|
||||
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000011 r zero_eeprom()::__c
|
||||
00000011 r update_commands()::__c
|
||||
00000011 r Log_Read_Attitude()::__c
|
||||
00000012 B Serial
|
||||
00000012 B Serial1
|
||||
00000012 B Serial3
|
||||
00000012 r flight_mode_strings
|
||||
00000012 W AP_Float16::~AP_Float16()
|
||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000012 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000012 W AP_VarT<float>::~AP_VarT()
|
||||
00000012 W AP_VarT<int>::~AP_VarT()
|
||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||
00000012 r print_done()::__c
|
||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r setup_frame(unsigned char, Menu::arg const*)::__c
|
||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||
00000013 r change_command(unsigned char)::__c
|
||||
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||
00000014 W AP_VarT<int>::cast_to_float() const
|
||||
00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c
|
||||
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
|
||||
00000015 r map_baudrate(signed char, unsigned long)::__c
|
||||
00000015 r init_ardupilot()::__c
|
||||
00000015 r Log_Read_Motors()::__c
|
||||
00000015 r print_hit_enter()::__c
|
||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||
00000016 r init_ardupilot()::__c
|
||||
00000016 r GCS_MAVLINK::update()::__c
|
||||
00000016 B sonar
|
||||
00000018 t setup_accel(unsigned char, Menu::arg const*)
|
||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
||||
00000018 b mavlink_get_channel_status::m_mavlink_status
|
||||
00000019 r GCS_MAVLINK::update()::__c
|
||||
0000001a r print_log_menu()::__c
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarS<Vector3<float> >::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarT<int>::unserialize(void*, unsigned int)
|
||||
0000001c W AP_VarA<float, (unsigned char)6>::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
|
||||
0000001e r Log_Read_Optflow()::__c
|
||||
0000001e r Log_Read_Nav_Tuning()::__c
|
||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||
00000020 t byte_swap_4
|
||||
00000021 r print_log_menu()::__c
|
||||
00000021 r report_compass()::__c
|
||||
00000021 r Log_Read_Current()::__c
|
||||
00000022 t clear_leds()
|
||||
00000022 t print_blanks(int)
|
||||
00000022 t reset_hold_I()
|
||||
00000022 W AP_Float16::~AP_Float16()
|
||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||
00000022 W AP_VarT<signed char>::~AP_VarT()
|
||||
00000022 W AP_VarT<float>::~AP_VarT()
|
||||
00000022 W AP_VarT<int>::~AP_VarT()
|
||||
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000023 r print_gyro_offsets()::__c
|
||||
00000024 t startup_ground()
|
||||
00000024 r init_ardupilot()::__c
|
||||
00000024 r print_accel_offsets()::__c
|
||||
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
00000026 t print_done()
|
||||
00000026 b mavlink_queue
|
||||
00000026 t print_hit_enter()
|
||||
00000026 t Log_Read_Startup()
|
||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||
00000028 t test_battery(unsigned char, Menu::arg const*)
|
||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
||||
00000028 t help_log(unsigned char, Menu::arg const*)
|
||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
|
||||
00000028 r Log_Read_Cmd()::__c
|
||||
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
|
||||
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||
0000002a r Log_Read_Control_Tuning()::__c
|
||||
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
|
||||
0000002e t print_divider()
|
||||
0000002e t send_rate(unsigned int, unsigned int)
|
||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||
0000002e r Log_Read_Performance()::__c
|
||||
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||
00000032 T GCS_MAVLINK::init(BetterStream*)
|
||||
00000032 W APM_PI::~APM_PI()
|
||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||
00000034 t _mav_put_int8_t_array
|
||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||
00000036 t report_radio()
|
||||
00000036 r Log_Read_GPS()::__c
|
||||
00000037 r print_wp(Location*, unsigned char)::__c
|
||||
00000038 t init_throttle_cruise()
|
||||
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
|
||||
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||
0000003a t report_gps()
|
||||
0000003a t report_imu()
|
||||
0000003c W RC_Channel::~RC_Channel()
|
||||
0000003d B g_gps_driver
|
||||
0000003e t verify_RTL()
|
||||
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*)
|
||||
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||
00000040 t byte_swap_8
|
||||
00000040 t crc_accumulate
|
||||
00000042 t report_sonar()
|
||||
00000043 r test_imu(unsigned char, Menu::arg const*)::__c
|
||||
00000044 t setup_show(unsigned char, Menu::arg const*)
|
||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
|
||||
0000004c t update_auto_yaw()
|
||||
0000004c B imu
|
||||
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
|
||||
00000050 r log_menu_commands
|
||||
00000050 r main_menu_commands
|
||||
00000050 t read_AHRS()
|
||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||
00000052 t change_command(unsigned char)
|
||||
00000052 t report_version()
|
||||
00000054 t print_enabled(unsigned char)
|
||||
00000054 t update_motor_leds()
|
||||
00000054 t report_flight_modes()
|
||||
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||
00000056 t readSwitch()
|
||||
00000056 t dancing_light()
|
||||
00000057 r help_log(unsigned char, Menu::arg const*)::__c
|
||||
00000058 t test_tuning(unsigned char, Menu::arg const*)
|
||||
00000058 t Log_Write_Attitude()
|
||||
0000005a t read_control_switch()
|
||||
0000005c t get_num_logs()
|
||||
0000005c t setup_esc(unsigned char, Menu::arg const*)
|
||||
0000005e t update_GPS_light()
|
||||
0000005e t radio_input_switch()
|
||||
0000005e T GCS_MAVLINK::_count_parameters()
|
||||
00000060 t _mavlink_send_uart
|
||||
00000060 B barometer
|
||||
00000062 t print_switch(unsigned char, unsigned char)
|
||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||
00000064 t mavlink_msg_param_value_send
|
||||
00000068 t zero_eeprom()
|
||||
00000068 t find_last_log_page(int)
|
||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||
0000006c t setup_sonar(unsigned char, Menu::arg const*)
|
||||
0000006e T output_min()
|
||||
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||
0000007a t setup_factory(unsigned char, Menu::arg const*)
|
||||
0000007c t test_baro(unsigned char, Menu::arg const*)
|
||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||
00000080 T __vector_25
|
||||
00000080 T __vector_36
|
||||
00000080 T __vector_54
|
||||
00000082 t do_RTL()
|
||||
00000086 t Log_Read_Attitude()
|
||||
00000088 t Log_Read_Raw()
|
||||
0000008c t setup_frame(unsigned char, Menu::arg const*)
|
||||
0000008c t print_gyro_offsets()
|
||||
0000008c t print_accel_offsets()
|
||||
00000090 t dump_log(unsigned char, Menu::arg const*)
|
||||
00000095 r init_ardupilot()::__c
|
||||
00000096 t map_baudrate(signed char, unsigned long)
|
||||
00000096 t print_wp(Location*, unsigned char)
|
||||
0000009a t init_compass()
|
||||
0000009a t Log_Read_Motors()
|
||||
0000009d B gcs
|
||||
0000009d B hil
|
||||
0000009e t setup_mode(unsigned char, Menu::arg const*)
|
||||
0000009e t Log_Write_Cmd(unsigned char, Location*)
|
||||
000000a0 t Log_Read_Mode()
|
||||
000000a4 T __vector_26
|
||||
000000a4 T __vector_37
|
||||
000000a4 T __vector_55
|
||||
000000aa t test_sonar(unsigned char, Menu::arg const*)
|
||||
000000ae t report_frame()
|
||||
000000b2 t erase_logs(unsigned char, Menu::arg const*)
|
||||
000000b4 t test_relay(unsigned char, Menu::arg const*)
|
||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
||||
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||
000000b7 B compass
|
||||
000000be t Log_Read_Nav_Tuning()
|
||||
000000c2 t setup_compass(unsigned char, Menu::arg const*)
|
||||
000000c4 t get_distance(Location*, Location*)
|
||||
000000c4 t update_events()
|
||||
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
|
||||
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||
000000c6 t Log_Read(int, int)
|
||||
000000c6 t test_tri(unsigned char, Menu::arg const*)
|
||||
000000c7 B dcm
|
||||
000000ca t init_barometer()
|
||||
000000cc t read_radio()
|
||||
000000d0 t get_bearing(Location*, Location*)
|
||||
000000d0 r setup_menu_commands
|
||||
000000d8 t test_radio(unsigned char, Menu::arg const*)
|
||||
000000d8 t setup_motors(unsigned char, Menu::arg const*)
|
||||
000000d8 t read_barometer()
|
||||
000000de t Log_Read_Performance()
|
||||
000000de t Log_Read_Control_Tuning()
|
||||
000000de t test_adc(unsigned char, Menu::arg const*)
|
||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||
000000e4 t Log_Read_Optflow()
|
||||
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
|
||||
000000e6 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||
000000e8 t Log_Read_Current()
|
||||
000000ee t report_batt_monitor()
|
||||
000000f4 t _mav_finalize_message_chan_send
|
||||
000000f6 t Log_Read_Cmd()
|
||||
000000fa t calc_nav_pitch_roll()
|
||||
0000010a t test_gps(unsigned char, Menu::arg const*)
|
||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||
00000112 t test_current(unsigned char, Menu::arg const*)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||
00000118 t set_command_with_index(Location, int)
|
||||
00000118 T GCS_MAVLINK::_queued_send()
|
||||
00000120 r test_menu_commands
|
||||
00000128 t get_command_with_index(int)
|
||||
00000130 t report_compass()
|
||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
||||
0000014e T GCS_MAVLINK::update()
|
||||
00000150 t update_trig()
|
||||
00000152 t set_next_WP(Location*)
|
||||
00000156 t Log_Read_GPS()
|
||||
00000166 t select_logs(unsigned char, Menu::arg const*)
|
||||
0000016c t update_commands()
|
||||
00000170 t test_mag(unsigned char, Menu::arg const*)
|
||||
00000172 t update_nav_wp()
|
||||
000001a0 t init_home()
|
||||
000001a8 t print_radio_values()
|
||||
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||
000001ca t mavlink_delay(unsigned long)
|
||||
000001ce t start_new_log()
|
||||
000001e2 t arm_motors()
|
||||
00000200 t set_mode(unsigned char)
|
||||
00000220 t test_wp(unsigned char, Menu::arg const*)
|
||||
00000228 t setup_radio(unsigned char, Menu::arg const*)
|
||||
00000286 t test_imu(unsigned char, Menu::arg const*)
|
||||
0000031e t read_battery()
|
||||
00000330 t calc_nav_rate(int, int, int, int)
|
||||
00000358 T update_throttle_mode()
|
||||
00000384 t print_log_menu()
|
||||
000003dc T update_yaw_mode()
|
||||
000004b2 t mavlink_parse_char
|
||||
000005ea T update_roll_pitch_mode()
|
||||
0000062e t init_ardupilot()
|
||||
00000798 t __static_initialization_and_destruction_0(int, int)
|
||||
000007c1 b g
|
||||
000007d6 W Parameters::Parameters()
|
||||
000008e4 t process_next_command()
|
||||
000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||
000017d0 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
||||
00001f58 T loop
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue