This commit is contained in:
Jason Short 2011-09-10 15:21:16 -07:00
commit 597510012d
66 changed files with 9807 additions and 3119 deletions

4
Tools/ArdupilotMegaPlanner/.gitignore vendored Normal file
View File

@ -0,0 +1,4 @@
*.pfx
*.suo
*.user

View File

@ -346,6 +346,7 @@
</Compile>
<EmbeddedResource Include="AGauge.resx">
<DependentUpon>AGauge.cs</DependentUpon>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="Log.zh-Hans.resx">
<DependentUpon>Log.cs</DependentUpon>

View File

@ -1,13 +0,0 @@
<?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>

View File

@ -384,7 +384,7 @@ namespace ArdupilotMega
public static Type getModes()
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
return typeof(apmmodes);
}

View File

@ -145,7 +145,7 @@ namespace ArdupilotMega
public ushort rcoverridech4 { get; set; }
// current firmware
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPilotMega;
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane;
public float freemem { get; set; }
public float brklevel { get; set; }

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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
00002000 T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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
00001ffe T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -23,22 +19,23 @@ autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' bu
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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
@ -51,22 +48,22 @@ autogenerated:286: warning: 'void report_heli()' declared 'static' but never def
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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:353: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/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
@ -97,41 +94,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -215,141 +212,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -96,6 +96,7 @@
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b circle_angle
00000004 b current_amps
00000004 b gps_base_alt
00000004 b original_alt
@ -327,7 +328,6 @@
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
@ -382,6 +382,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -596,4 +597,4 @@
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
0000194a T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -23,22 +19,23 @@ autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' bu
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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
@ -51,22 +48,22 @@ autogenerated:286: warning: 'void report_heli()' declared 'static' but never def
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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:353: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:371: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:372: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/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
@ -97,41 +94,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -215,141 +212,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -96,6 +96,7 @@
00000004 d scaleLongUp
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b circle_angle
00000004 b current_amps
00000004 b gps_base_alt
00000004 b original_alt
@ -327,7 +328,6 @@
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
@ -382,6 +382,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -596,4 +597,4 @@
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
00001948 T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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
00001ece T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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
00001ecc T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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
00001e2e T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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)
00001f56 T loop
00001e2c T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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)
00002038 T loop
00001f0e T loop

View File

@ -1,13 +1,9 @@
%%%% 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:
%% ArduCopter.cpp
%% ArduCopter.o
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:1398: 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
@ -22,39 +18,40 @@ autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never
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
/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/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
/root/apm/ardupilot-mega/ArduCopter/test.pde:1040: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:442: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:462: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:467: warning: 'optflow_offset' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.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
@ -85,41 +82,41 @@ autogenerated:318: warning: 'void fake_out_gps()' declared 'static' but never de
%% 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:
In file included from /root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of |
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of &
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)':
/root/apm/ardupilot-mega/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
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i'
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)':
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function
/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()':
/root/apm/ardupilot-mega/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:
In file included from /root/apm/ardupilot-mega/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
@ -203,141 +200,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi
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'
%% ArduCopter.elf
%% ArduCopter.eep
%% ArduCopter.hex

View File

@ -97,6 +97,7 @@
00000004 b sin_pitch_y
00000004 b wp_distance
00000004 b abs_pressure
00000004 b circle_angle
00000004 b current_amps
00000004 b old_altitude
00000004 b original_alt
@ -329,7 +330,6 @@
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
@ -383,6 +383,7 @@
00000016 r init_ardupilot()::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r __menu_name__main_menu
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
@ -608,4 +609,4 @@
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)
00002036 T loop
00001f0c T loop

View File

@ -0,0 +1,129 @@
%% ArduPlane.cpp
%% ArduPlane.o
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.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/ardupilot-mega/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
%% ArduPlane.elf
%% ArduPlane.eep
%% ArduPlane.hex

View File

@ -0,0 +1,699 @@
00000001 b GPS_enabled
00000001 b crash_timer
00000001 b home_is_set
00000001 b ch3_failsafe
00000001 b land_complete
00000001 b command_may_ID
00000001 b command_must_ID
00000001 b failsafeCounter
00000001 b counter_one_herz
00000001 b in_mavlink_delay
00000001 b slow_loopCounter
00000001 d takeoff_complete
00000001 b command_may_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b rc_override_active
00000001 b delta_ms_medium_loop
00000001 b superslow_loopCounter
00000001 b event_id
00000001 b GPS_light
00000001 b radio_input_switch()::bouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 D control_mode
00000001 B hindex
00000001 B inverted_flight
00000001 B mavdelay
00000001 B n
00000001 B oldSwitchPosition
00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
00000002 d elevon1_trim
00000002 d elevon2_trim
00000002 b event_repeat
00000002 b loiter_delta
00000002 b loiter_total
00000002 b gps_fix_count
00000002 b landing_pitch
00000002 b takeoff_pitch
00000002 b airspeed_nudge
00000002 b condition_rate
00000002 b mainLoop_count
00000002 b throttle_nudge
00000002 b loiter_time_max
00000002 b event_undo_value
00000002 b ground_start_avg
00000002 b airspeed_pressure
00000002 b adc
00000002 r comma
00000002 b g_gps
00000002 b pmTest1
00000002 b G_Dt_max
00000002 b airspeed
00000002 d ch1_temp
00000002 d ch2_temp
00000002 b failsafe
00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(bool)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c
00000003 r report_compass()::__c
00000004 b event_timer
00000004 d hold_course
00000004 b loiter_time
00000004 b nav_bearing
00000004 d scaleLongUp
00000004 b wp_distance
00000004 b abs_pressure
00000004 b airspeed_raw
00000004 b current_amps
00000004 b energy_error
00000004 b bearing_error
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b airspeed_error
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b condition_start
00000004 b condition_value
00000004 d nav_gain_scaler
00000004 b offset_altitude
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b crosstrack_error
00000004 b medium_loopTimer
00000004 b takeoff_altitude
00000004 b wp_totalDistance
00000004 b ch3_failsafe_timer
00000004 b crosstrack_bearing
00000004 b fast_loopTimeStamp
00000004 b old_target_bearing
00000004 b rc_override_fs_timer
00000004 r __menu_name__log_menu
00000004 b airspeed_energy_error
00000004 d G_Dt
00000004 b load
00000004 b dTnav
00000004 b nav_roll
00000004 b nav_pitch
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 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(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r report_compass()::__c
00000004 r Log_Read_Performance()::__c
00000004 r test_adc(unsigned char, Menu::arg 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
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B xi
00000004 B xi2
00000004 B xiyi
00000004 B xoffset
00000004 B yi
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_Cmd()::__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 PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
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 init_ardupilot()::__c
00000006 r Log_Read_Control_Tuning()::__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 report_gains()::__c
00000007 r report_radio()::__c
00000007 r print_enabled(bool)::__c
00000007 r test_airspeed(unsigned char, Menu::arg const*)::__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 r __menu_name__planner_menu
00000008 r report_compass()::__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 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 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 __menu_name__main_menu
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__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 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_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c
0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r report_gains()::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r test_current(unsigned char, Menu::arg const*)::__c
0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__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 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 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 V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c
0000000e r print_log_menu()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r test_wp(unsigned char, Menu::arg const*)::__c
0000000e r test_gyro(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
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
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f r report_gains()::__c
0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
00000010 r report_gains()::__c
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
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<long>::~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 init_barometer()::__c
00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r report_gains()::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r Log_Read_Startup()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r dump_log(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 set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c
00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__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
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000022 t print_blanks(int)
00000022 t reset_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()
00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c
00000022 r verify_loiter_time()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c
0000002b r verify_must()::__c
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch()
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 verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c
00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c
0000003a t report_imu()
0000003a W PID::~PID()
0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
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
00000040 B history
00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000054 t print_divider()
00000054 t print_enabled(bool)
00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char)
00000058 t radio_input_switch()
0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000062 t print_switch(unsigned char, unsigned char)
00000064 t Log_Write_Attitude(int, int, unsigned int)
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_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time()
00000076 t startup_IMU_ground()
00000078 t read_control_switch()
0000007c t failsafe_short_on_event()
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL()
00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches()
0000009c t print_PID(PID*)
0000009d B gcs
0000009d B hil
000000a0 t report_xtrack()
000000a4 t Log_Read_Cmd()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ac t Log_Read_Performance()
000000b2 t Log_Read_Startup()
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
000000bc t Log_Read_Control_Tuning()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed()
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000da t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f2 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000110 t test_radio(unsigned char, Menu::arg const*)
00000112 t get_distance(Location*, Location*)
00000112 t startup_ground()
00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t read_barometer()
00000116 t erase_logs(unsigned char, Menu::arg const*)
00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
0000013e t process_may()
0000013e t calc_nav_roll()
00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may()
0000014e T GCS_MAVLINK::update()
00000152 t report_gains()
0000015a t test_airspeed(unsigned char, Menu::arg const*)
0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must()
0000016a t set_guided_WP()
00000172 t navigate()
00000174 t report_compass()
0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*)
000001ae T init_home()
000001b2 t update_crosstrack()
000001be t Log_Read_GPS()
000001c8 t read_airspeed()
000001ca t mavlink_delay(unsigned long)
000001ca t start_new_log(unsigned char)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001ec t init_barometer()
00000202 t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle()
00000226 t Log_Read(int, int)
0000022c t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char)
00000232 t verify_must()
0000023e t print_radio_values()
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
000002e4 t read_radio()
0000031e t read_battery()
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000404 t process_next_command()
0000041c t set_servos()
0000044c t print_log_menu()
000004b2 t mavlink_parse_char
0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot()
00000831 b g
0000090a W Parameters::Parameters()
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001ae8 T loop

View File

@ -0,0 +1,129 @@
%% ArduPlane.cpp
%% ArduPlane.o
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.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/ardupilot-mega/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
%% ArduPlane.elf
%% ArduPlane.eep
%% ArduPlane.hex

View File

@ -0,0 +1,699 @@
00000001 b GPS_enabled
00000001 b crash_timer
00000001 b home_is_set
00000001 b ch3_failsafe
00000001 b land_complete
00000001 b command_may_ID
00000001 b command_must_ID
00000001 b failsafeCounter
00000001 b counter_one_herz
00000001 b in_mavlink_delay
00000001 b slow_loopCounter
00000001 d takeoff_complete
00000001 b command_may_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b rc_override_active
00000001 b delta_ms_medium_loop
00000001 b superslow_loopCounter
00000001 b event_id
00000001 b GPS_light
00000001 b radio_input_switch()::bouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 D control_mode
00000001 B hindex
00000001 B inverted_flight
00000001 B mavdelay
00000001 B n
00000001 B oldSwitchPosition
00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
00000002 d elevon1_trim
00000002 d elevon2_trim
00000002 b event_repeat
00000002 b loiter_delta
00000002 b loiter_total
00000002 b gps_fix_count
00000002 b landing_pitch
00000002 b takeoff_pitch
00000002 b airspeed_nudge
00000002 b condition_rate
00000002 b mainLoop_count
00000002 b throttle_nudge
00000002 b loiter_time_max
00000002 b event_undo_value
00000002 b ground_start_avg
00000002 b airspeed_pressure
00000002 b adc
00000002 r comma
00000002 b g_gps
00000002 b pmTest1
00000002 b G_Dt_max
00000002 b airspeed
00000002 d ch1_temp
00000002 d ch2_temp
00000002 b failsafe
00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(bool)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c
00000003 r report_compass()::__c
00000004 b event_timer
00000004 d hold_course
00000004 b loiter_time
00000004 b nav_bearing
00000004 d scaleLongUp
00000004 b wp_distance
00000004 b abs_pressure
00000004 b airspeed_raw
00000004 b current_amps
00000004 b energy_error
00000004 b bearing_error
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b airspeed_error
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b condition_start
00000004 b condition_value
00000004 d nav_gain_scaler
00000004 b offset_altitude
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b crosstrack_error
00000004 b medium_loopTimer
00000004 b takeoff_altitude
00000004 b wp_totalDistance
00000004 b ch3_failsafe_timer
00000004 b crosstrack_bearing
00000004 b fast_loopTimeStamp
00000004 b old_target_bearing
00000004 b rc_override_fs_timer
00000004 r __menu_name__log_menu
00000004 b airspeed_energy_error
00000004 d G_Dt
00000004 b load
00000004 b dTnav
00000004 b nav_roll
00000004 b nav_pitch
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 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(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r report_compass()::__c
00000004 r Log_Read_Performance()::__c
00000004 r test_adc(unsigned char, Menu::arg 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
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B xi
00000004 B xi2
00000004 B xiyi
00000004 B xoffset
00000004 B yi
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_Cmd()::__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 PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
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 init_ardupilot()::__c
00000006 r Log_Read_Control_Tuning()::__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 report_gains()::__c
00000007 r report_radio()::__c
00000007 r print_enabled(bool)::__c
00000007 r test_airspeed(unsigned char, Menu::arg const*)::__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 r __menu_name__planner_menu
00000008 r report_compass()::__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 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 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 __menu_name__main_menu
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__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 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_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c
0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r report_gains()::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r test_current(unsigned char, Menu::arg const*)::__c
0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__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 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 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 V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c
0000000e r print_log_menu()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r test_wp(unsigned char, Menu::arg const*)::__c
0000000e r test_gyro(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
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
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f r report_gains()::__c
0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
00000010 r report_gains()::__c
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
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<long>::~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 init_barometer()::__c
00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r report_gains()::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r Log_Read_Startup()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r dump_log(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 set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c
00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__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
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000022 t print_blanks(int)
00000022 t reset_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()
00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c
00000022 r verify_loiter_time()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c
0000002b r verify_must()::__c
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch()
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 verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c
00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c
0000003a t report_imu()
0000003a W PID::~PID()
0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
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
00000040 B history
00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000054 t print_divider()
00000054 t print_enabled(bool)
00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char)
00000058 t radio_input_switch()
0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 t print_switch(unsigned char, unsigned char)
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000064 t Log_Write_Attitude(int, int, unsigned int)
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_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time()
00000076 t startup_IMU_ground()
00000078 t read_control_switch()
0000007c t failsafe_short_on_event()
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL()
00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches()
0000009c t print_PID(PID*)
0000009d B gcs
0000009d B hil
000000a0 t report_xtrack()
000000a4 t Log_Read_Cmd()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ac t Log_Read_Performance()
000000b0 t Log_Read_Startup()
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
000000bc t Log_Read_Control_Tuning()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000c7 B dcm
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed()
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000d8 t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f0 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000110 t test_radio(unsigned char, Menu::arg const*)
00000112 t get_distance(Location*, Location*)
00000112 t startup_ground()
00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t erase_logs(unsigned char, Menu::arg const*)
00000114 t read_barometer()
00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
0000013e t process_may()
0000013e t calc_nav_roll()
00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may()
0000014e T GCS_MAVLINK::update()
00000152 t report_gains()
00000158 t test_airspeed(unsigned char, Menu::arg const*)
0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must()
0000016a t set_guided_WP()
00000172 t navigate()
00000174 t report_compass()
0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*)
000001ae T init_home()
000001b2 t update_crosstrack()
000001be t Log_Read_GPS()
000001c8 t read_airspeed()
000001ca t mavlink_delay(unsigned long)
000001ca t start_new_log(unsigned char)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001ec t init_barometer()
000001fe t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle()
00000222 t Log_Read(int, int)
00000228 t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char)
00000232 t verify_must()
0000023e t print_radio_values()
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
000002e4 t read_radio()
0000031e t read_battery()
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000404 t process_next_command()
0000041c t set_servos()
00000436 t print_log_menu()
000004b2 t mavlink_parse_char
0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot()
00000831 b g
0000090a W Parameters::Parameters()
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001ae8 T loop

View File

@ -0,0 +1,129 @@
%% ArduPlane.cpp
%% ArduPlane.o
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.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/ardupilot-mega/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
%% ArduPlane.elf
%% ArduPlane.eep
%% ArduPlane.hex

View File

@ -0,0 +1,699 @@
00000001 b GPS_enabled
00000001 b crash_timer
00000001 b home_is_set
00000001 b ch3_failsafe
00000001 b land_complete
00000001 b command_may_ID
00000001 b command_must_ID
00000001 b failsafeCounter
00000001 b counter_one_herz
00000001 b in_mavlink_delay
00000001 b slow_loopCounter
00000001 d takeoff_complete
00000001 b command_may_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b rc_override_active
00000001 b delta_ms_medium_loop
00000001 b superslow_loopCounter
00000001 b event_id
00000001 b GPS_light
00000001 b radio_input_switch()::bouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 D control_mode
00000001 B hindex
00000001 B inverted_flight
00000001 B mavdelay
00000001 B n
00000001 B oldSwitchPosition
00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
00000002 d elevon1_trim
00000002 d elevon2_trim
00000002 b event_repeat
00000002 b loiter_delta
00000002 b loiter_total
00000002 b gps_fix_count
00000002 b landing_pitch
00000002 b takeoff_pitch
00000002 b airspeed_nudge
00000002 b condition_rate
00000002 b mainLoop_count
00000002 b throttle_nudge
00000002 b loiter_time_max
00000002 b event_undo_value
00000002 b ground_start_avg
00000002 b airspeed_pressure
00000002 b adc
00000002 r comma
00000002 b g_gps
00000002 b pmTest1
00000002 b G_Dt_max
00000002 b airspeed
00000002 d ch1_temp
00000002 d ch2_temp
00000002 b failsafe
00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(bool)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c
00000003 r report_compass()::__c
00000004 b event_timer
00000004 d hold_course
00000004 b loiter_time
00000004 b nav_bearing
00000004 d scaleLongUp
00000004 b wp_distance
00000004 b abs_pressure
00000004 b airspeed_raw
00000004 b current_amps
00000004 b energy_error
00000004 b bearing_error
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b airspeed_error
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b condition_start
00000004 b condition_value
00000004 d nav_gain_scaler
00000004 b offset_altitude
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b crosstrack_error
00000004 b medium_loopTimer
00000004 b takeoff_altitude
00000004 b wp_totalDistance
00000004 b ch3_failsafe_timer
00000004 b crosstrack_bearing
00000004 b fast_loopTimeStamp
00000004 b old_target_bearing
00000004 b rc_override_fs_timer
00000004 r __menu_name__log_menu
00000004 b airspeed_energy_error
00000004 d G_Dt
00000004 b load
00000004 b dTnav
00000004 b nav_roll
00000004 b nav_pitch
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 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(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r report_compass()::__c
00000004 r Log_Read_Performance()::__c
00000004 r test_adc(unsigned char, Menu::arg 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
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B xi
00000004 B xi2
00000004 B xiyi
00000004 B xoffset
00000004 B yi
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_Cmd()::__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 PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
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 init_ardupilot()::__c
00000006 r Log_Read_Control_Tuning()::__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 report_gains()::__c
00000007 r report_radio()::__c
00000007 r print_enabled(bool)::__c
00000007 r test_airspeed(unsigned char, Menu::arg const*)::__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 r __menu_name__planner_menu
00000008 r report_compass()::__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 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 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 __menu_name__main_menu
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__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 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_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c
0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r report_gains()::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r test_current(unsigned char, Menu::arg const*)::__c
0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__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 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 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 V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c
0000000e r print_log_menu()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r test_wp(unsigned char, Menu::arg const*)::__c
0000000e r test_gyro(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
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
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f r report_gains()::__c
0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
00000010 r report_gains()::__c
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
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<long>::~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 init_barometer()::__c
00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r report_gains()::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r Log_Read_Startup()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r dump_log(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 set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c
00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__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
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000022 t print_blanks(int)
00000022 t reset_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()
00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c
00000022 r verify_loiter_time()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c
0000002b r verify_must()::__c
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch()
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 verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c
00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c
0000003a t report_imu()
0000003a W PID::~PID()
0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
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
00000040 B history
00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000054 t print_divider()
00000054 t print_enabled(bool)
00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char)
00000058 t radio_input_switch()
0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000062 t print_switch(unsigned char, unsigned char)
00000064 t Log_Write_Attitude(int, int, unsigned int)
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_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time()
00000076 t startup_IMU_ground()
00000078 t read_control_switch()
0000007c t failsafe_short_on_event()
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL()
00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches()
0000009c t print_PID(PID*)
0000009d B gcs
0000009d B hil
000000a0 t report_xtrack()
000000a4 t Log_Read_Cmd()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ac t Log_Read_Performance()
000000b2 t Log_Read_Startup()
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
000000bc t Log_Read_Control_Tuning()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed()
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000da t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f2 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000110 t test_radio(unsigned char, Menu::arg const*)
00000112 t get_distance(Location*, Location*)
00000112 t startup_ground()
00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t read_barometer()
00000116 t erase_logs(unsigned char, Menu::arg const*)
00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
0000013e t process_may()
0000013e t calc_nav_roll()
00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may()
0000014e T GCS_MAVLINK::update()
00000152 t report_gains()
0000015a t test_airspeed(unsigned char, Menu::arg const*)
0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must()
0000016a t set_guided_WP()
00000172 t navigate()
00000174 t report_compass()
0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*)
000001ae T init_home()
000001b2 t update_crosstrack()
000001be t Log_Read_GPS()
000001c8 t read_airspeed()
000001ca t mavlink_delay(unsigned long)
000001ca t start_new_log(unsigned char)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001ec t init_barometer()
00000202 t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle()
00000226 t Log_Read(int, int)
0000022c t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char)
00000232 t verify_must()
0000023e t print_radio_values()
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
000002e4 t read_radio()
0000031e t read_battery()
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000404 t process_next_command()
0000041c t set_servos()
0000044c t print_log_menu()
000004b2 t mavlink_parse_char
0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot()
00000831 b g
0000090a W Parameters::Parameters()
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001ae8 T loop

View File

@ -0,0 +1,129 @@
%% ArduPlane.cpp
%% ArduPlane.o
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.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/ardupilot-mega/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
%% ArduPlane.elf
%% ArduPlane.eep
%% ArduPlane.hex

View File

@ -0,0 +1,699 @@
00000001 b GPS_enabled
00000001 b crash_timer
00000001 b home_is_set
00000001 b ch3_failsafe
00000001 b land_complete
00000001 b command_may_ID
00000001 b command_must_ID
00000001 b failsafeCounter
00000001 b counter_one_herz
00000001 b in_mavlink_delay
00000001 b slow_loopCounter
00000001 d takeoff_complete
00000001 b command_may_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b rc_override_active
00000001 b delta_ms_medium_loop
00000001 b superslow_loopCounter
00000001 b event_id
00000001 b GPS_light
00000001 b radio_input_switch()::bouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 D control_mode
00000001 B hindex
00000001 B inverted_flight
00000001 B mavdelay
00000001 B n
00000001 B oldSwitchPosition
00000002 T ReadSCP1000()
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
00000002 d elevon1_trim
00000002 d elevon2_trim
00000002 b event_repeat
00000002 b loiter_delta
00000002 b loiter_total
00000002 b gps_fix_count
00000002 b landing_pitch
00000002 b takeoff_pitch
00000002 b airspeed_nudge
00000002 b condition_rate
00000002 b mainLoop_count
00000002 b throttle_nudge
00000002 b loiter_time_max
00000002 b event_undo_value
00000002 b ground_start_avg
00000002 b airspeed_pressure
00000002 b adc
00000002 r comma
00000002 b g_gps
00000002 b pmTest1
00000002 b G_Dt_max
00000002 b airspeed
00000002 d ch1_temp
00000002 d ch2_temp
00000002 b failsafe
00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 r print_divider()::__c
00000002 d throttle_slew_limit()::last
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000003 r select_logs(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(bool)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
00000003 r print_log_menu()::__c
00000003 r report_compass()::__c
00000004 b event_timer
00000004 d hold_course
00000004 b loiter_time
00000004 b nav_bearing
00000004 d scaleLongUp
00000004 b wp_distance
00000004 b abs_pressure
00000004 b airspeed_raw
00000004 b current_amps
00000004 b energy_error
00000004 b bearing_error
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b airspeed_error
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b condition_start
00000004 b condition_value
00000004 d nav_gain_scaler
00000004 b offset_altitude
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b crosstrack_error
00000004 b medium_loopTimer
00000004 b takeoff_altitude
00000004 b wp_totalDistance
00000004 b ch3_failsafe_timer
00000004 b crosstrack_bearing
00000004 b fast_loopTimeStamp
00000004 b old_target_bearing
00000004 b rc_override_fs_timer
00000004 r __menu_name__log_menu
00000004 b airspeed_energy_error
00000004 d G_Dt
00000004 b load
00000004 b dTnav
00000004 b nav_roll
00000004 b nav_pitch
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 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(bool)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r print_log_menu()::__c
00000004 r report_compass()::__c
00000004 r Log_Read_Performance()::__c
00000004 r test_adc(unsigned char, Menu::arg 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
00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 B xi
00000004 B xi2
00000004 B xiyi
00000004 B xoffset
00000004 B yi
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_Cmd()::__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 PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000006 r __menu_name__setup_menu
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 init_ardupilot()::__c
00000006 r Log_Read_Control_Tuning()::__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 report_gains()::__c
00000007 r report_radio()::__c
00000007 r print_enabled(bool)::__c
00000007 r test_airspeed(unsigned char, Menu::arg const*)::__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 r __menu_name__planner_menu
00000008 r report_compass()::__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 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 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 __menu_name__main_menu
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
0000000a r report_compass()::__c
0000000a r report_throttle()::__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 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_gains()::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r test_airspeed(unsigned char, Menu::arg const*)::__c
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
0000000c V vtable for IMU
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
0000000c r report_xtrack()::__c
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000c r control_failsafe(unsigned int)::__c
0000000c r test_mode(unsigned char, Menu::arg const*)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c
0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__c
0000000d r select_logs(unsigned char, Menu::arg const*)::__c
0000000d r report_gains()::__c
0000000d r test_battery(unsigned char, Menu::arg const*)::__c
0000000d r test_current(unsigned char, Menu::arg const*)::__c
0000000d r print_log_menu()::__c
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
0000000d r Log_Read_Startup()::__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 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 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 V vtable for AP_VarT<long>
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
0000000e r process_may()::__c
0000000e r select_logs(unsigned char, Menu::arg const*)::__c
0000000e r report_gains()::__c
0000000e r print_log_menu()::__c
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
0000000e r report_batt_monitor()::__c
0000000e r report_flight_modes()::__c
0000000e r test_wp(unsigned char, Menu::arg const*)::__c
0000000e r test_gyro(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
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
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f r report_gains()::__c
0000000f r print_log_menu()::__c
0000000f r failsafe_short_on_event()::__c
0000000f r test_mag(unsigned char, Menu::arg const*)::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
00000010 r setup_radio(unsigned char, Menu::arg const*)::__c
00000010 r report_gains()::__c
00000010 r Log_Read_Startup()::__c
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
00000010 r dump_log(unsigned char, Menu::arg const*)::__c
00000010 t mavlink_get_channel_status
00000011 r erase_logs(unsigned char, Menu::arg const*)::__c
00000011 r set_next_WP(Location*)::__c
00000011 r zero_eeprom()::__c
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
00000011 r startup_ground()::__c
00000011 r Log_Read_Attitude()::__c
00000011 r load_next_command_from_EEPROM()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
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<long>::~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 init_barometer()::__c
00000012 r startup_IMU_ground()::__c
00000012 r report_batt_monitor()::__c
00000012 r report_batt_monitor()::__c
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000013 r report_gains()::__c
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r Log_Read_Startup()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r print_radio_values()::__c
00000013 r dump_log(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 set_guided_WP()::__c
00000014 r test_wp(unsigned char, Menu::arg const*)::__c
00000014 r test_imu(unsigned char, Menu::arg const*)::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r report_gains()::__c
00000015 r init_ardupilot()::__c
00000015 r print_hit_enter()::__c
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000016 r report_batt_monitor()::__c
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000017 r test_pressure(unsigned char, Menu::arg const*)::__c
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000018 b mavlink_get_channel_status::m_mavlink_status
00000018 r process_must()::__c
00000018 r report_compass()::__c
00000018 r Log_Read_Startup()::__c
00000019 r report_batt_monitor()::__c
00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c
0000001a r Log_Read(int, int)::__c
0000001b r failsafe_short_off_event()::__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
0000001c r Log_Read_Current()::__c
0000001c r Log_Read(int, int)::__c
0000001c r Log_Read(int, int)::__c
0000001d r setup_radio(unsigned char, Menu::arg const*)::__c
0000001d r startup_ground()::__c
0000001d r report_batt_monitor()::__c
0000001e r flight_mode_strings
0000001e t failsafe_short_off_event()
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
0000001e r startup_ground()::__c
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
0000001f r init_ardupilot()::__c
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
00000020 r test_current(unsigned char, Menu::arg const*)::__c
00000020 r report_xtrack()::__c
00000020 r init_barometer()::__c
00000020 r Log_Read(int, int)::__c
00000020 t byte_swap_4
00000021 r print_log_menu()::__c
00000021 r print_log_menu()::__c
00000022 t print_blanks(int)
00000022 t reset_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()
00000022 W AP_VarT<long>::~AP_VarT()
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000022 r report_compass()::__c
00000022 r increment_WP_index()::__c
00000022 r verify_loiter_time()::__c
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
00000023 r navigate()::__c
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000024 r print_accel_offsets()::__c
00000024 r verify_loiter_turns()::__c
00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter()
00000026 r init_ardupilot()::__c
00000026 r print_PID(PID*)::__c
00000027 r init_ardupilot()::__c
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t increment_WP_index()
00000028 t help_log(unsigned char, Menu::arg const*)
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002a r init_ardupilot()::__c
0000002a r startup_ground()::__c
0000002b r verify_must()::__c
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
0000002b r change_command(unsigned char)::__c
0000002c t freeRAM()
0000002d r startup_IMU_ground()::__c
0000002e t reset_control_switch()
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 verify_nav_wp()::__c
00000030 t setup_mode(unsigned char, Menu::arg const*)
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t test_mode(unsigned char, Menu::arg const*)
00000030 r verify_may()::__c
00000030 r print_log_menu()::__c
00000031 r start_new_log(unsigned char)::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
00000034 t _mav_put_int8_t_array
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000035 r Log_Read_Nav_Tuning()::__c
00000036 t report_radio()
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
00000039 r setup_radio(unsigned char, Menu::arg const*)::__c
00000039 r planner_mode(unsigned char, Menu::arg const*)::__c
00000039 r init_ardupilot()::__c
0000003a t report_imu()
0000003a W PID::~PID()
0000003c t Log_Write_Mode(unsigned char)
0000003c t verify_loiter_turns()
0000003c W RC_Channel::~RC_Channel()
0000003c r test_wp_print(Location*, unsigned char)::__c
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
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
00000040 B history
00000043 r Log_Read_GPS()::__c
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000044 r report_throttle()::__c
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char)
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
0000004c t setup_erase(unsigned char, Menu::arg const*)
0000004c t Log_Read_Mode()
0000004c B imu
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
00000050 r log_menu_commands
00000050 r main_menu_commands
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000054 t print_divider()
00000054 t print_enabled(bool)
00000054 t report_flight_modes()
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
00000056 t change_command(unsigned char)
00000058 t radio_input_switch()
0000005a t update_GPS_light()
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005b r setup_erase(unsigned char, Menu::arg const*)::__c
0000005c t readSwitch()
0000005c t get_num_logs()
0000005e T GCS_MAVLINK::_count_parameters()
00000060 t print_switch(unsigned char, unsigned char)
00000060 b barometer
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000064 t Log_Write_Attitude(int, int, unsigned int)
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_show(unsigned char, Menu::arg const*)
0000006c t demo_servos(unsigned char)
0000006e t setup_factory(unsigned char, Menu::arg const*)
00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time()
00000076 t startup_IMU_ground()
00000078 t read_control_switch()
0000007c t failsafe_short_on_event()
0000007e t test_rawgps(unsigned char, Menu::arg const*)
00000080 r setup_menu_commands
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000086 t Log_Read_Attitude()
00000088 t Log_Read_Raw()
0000008a t Log_Write_Cmd(unsigned char, Location*)
0000008c t print_gyro_offsets()
0000008c t print_accel_offsets()
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
00000090 t do_RTL()
00000096 t map_baudrate(signed char, unsigned long)
00000096 t test_wp_print(Location*, unsigned char)
0000009c t update_servo_switches()
0000009c t print_PID(PID*)
0000009d B gcs
0000009d B hil
000000a0 t report_xtrack()
000000a4 t Log_Read_Cmd()
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ac t Log_Read_Performance()
000000b0 t Log_Read_Startup()
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
000000bc t Log_Read_Control_Tuning()
000000c0 t report_throttle()
000000c0 t calc_bearing_error()
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000c7 B dcm
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
000000ca t control_failsafe(unsigned int)
000000ce t zero_airspeed()
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000ce r setup_mode(unsigned char, Menu::arg const*)::__c
000000ce r help_log(unsigned char, Menu::arg const*)::__c
000000d0 t get_bearing(Location*, Location*)
000000d8 t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e7 r init_ardupilot()::__c
000000ec t dump_log(unsigned char, Menu::arg const*)
000000f0 t throttle_slew_limit()
000000f0 t test_adc(unsigned char, Menu::arg const*)
000000f4 t _mav_finalize_message_chan_send
000000fa t Log_Read_Current()
00000100 t trim_radio()
00000102 t setup_compass(unsigned char, Menu::arg const*)
00000106 t test_current(unsigned char, Menu::arg const*)
00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
00000108 t test_battery(unsigned char, Menu::arg const*)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000110 t test_radio(unsigned char, Menu::arg const*)
00000112 t get_distance(Location*, Location*)
00000112 t startup_ground()
00000112 t report_batt_monitor()
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000114 t erase_logs(unsigned char, Menu::arg const*)
00000114 t read_barometer()
00000118 t test_gps(unsigned char, Menu::arg const*)
00000118 T GCS_MAVLINK::_queued_send()
00000120 t test_pressure(unsigned char, Menu::arg const*)
00000130 t test_dipswitches(unsigned char, Menu::arg const*)
00000130 t set_wp_with_index(Location, int)
00000130 t setup_flightmodes(unsigned char, Menu::arg const*)
00000130 r test_menu_commands
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
0000013e t process_may()
0000013e t calc_nav_roll()
00000146 t select_logs(unsigned char, Menu::arg const*)
0000014e t verify_may()
0000014e T GCS_MAVLINK::update()
00000152 t report_gains()
00000158 t test_airspeed(unsigned char, Menu::arg const*)
0000015e t test_gyro(unsigned char, Menu::arg const*)
0000016a t process_must()
0000016a t set_guided_WP()
00000172 t navigate()
00000174 t report_compass()
0000017e t Log_Read_Nav_Tuning()
000001a2 t test_imu(unsigned char, Menu::arg const*)
000001ae T init_home()
000001b2 t update_crosstrack()
000001be t Log_Read_GPS()
000001c8 t read_airspeed()
000001ca t mavlink_delay(unsigned long)
000001ca t start_new_log(unsigned char)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001ec t init_barometer()
000001fe t test_failsafe(unsigned char, Menu::arg const*)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle()
00000222 t Log_Read(int, int)
00000228 t test_wp(unsigned char, Menu::arg const*)
0000022c t set_mode(unsigned char)
00000232 t verify_must()
0000023e t print_radio_values()
0000024c t update_loiter()
0000025c t setup_radio(unsigned char, Menu::arg const*)
000002e4 t read_radio()
0000031e t read_battery()
0000032e t test_mag(unsigned char, Menu::arg const*)
0000033a W Parameters::~Parameters()
00000404 t process_next_command()
0000041c t set_servos()
00000436 t print_log_menu()
000004b2 t mavlink_parse_char
0000059c t __static_initialization_and_destruction_0(int, int)
000006da t init_ardupilot()
00000831 b g
0000090a W Parameters::Parameters()
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001ae8 T loop

View File

@ -0,0 +1,177 @@
%% ArduPlane.cpp
%% ArduPlane.o
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.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:25: warning: 'bool print_log_menu()' declared 'static' but never defined
autogenerated:28: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
autogenerated:29: warning: 'int find_last_log_page(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:745: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Control_Tuning()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:40: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:41: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:42: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:43: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:44: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:45: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:46: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:47: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:48: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:49: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:50: warning: 'void Log_Read(int, int)' declared 'static' but never defined
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
autogenerated:149: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:150: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:152: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:154: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:155: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:156: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:157: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:158: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:159: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:160: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:161: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:162: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:163: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:164: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:165: warning: 'void print_done()' declared 'static' but never defined
autogenerated:166: warning: 'void print_blanks(int)' declared 'static' but never defined
autogenerated:167: warning: 'void print_divider()' declared 'static' but never defined
autogenerated:168: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
autogenerated:169: warning: 'void zero_eeprom()' declared 'static' but never defined
autogenerated:170: warning: 'void print_enabled(bool)' declared 'static' but never defined
autogenerated:171: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:172: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:183: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:210: warning: 'comma' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:212: warning: 'flight_mode_strings' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:317: warning: 'airspeed_raw' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:318: warning: 'airspeed_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:322: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:742: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' 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_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/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
%% ArduPlane.elf
%% ArduPlane.eep
%% ArduPlane.hex

View File

@ -0,0 +1,412 @@
00000001 b GPS_enabled
00000001 b crash_timer
00000001 b home_is_set
00000001 b ch3_failsafe
00000001 b land_complete
00000001 b command_may_ID
00000001 b command_must_ID
00000001 b failsafeCounter
00000001 b counter_one_herz
00000001 b in_mavlink_delay
00000001 b slow_loopCounter
00000001 d takeoff_complete
00000001 b command_may_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b rc_override_active
00000001 b delta_ms_medium_loop
00000001 b superslow_loopCounter
00000001 b event_id
00000001 b GPS_light
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 D control_mode
00000001 B hindex
00000001 B inverted_flight
00000001 B mavdelay
00000001 B n
00000001 B oldSwitchPosition
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
00000002 d elevon1_trim
00000002 d elevon2_trim
00000002 b event_repeat
00000002 b loiter_delta
00000002 b loiter_total
00000002 b gps_fix_count
00000002 b landing_pitch
00000002 b takeoff_pitch
00000002 b airspeed_nudge
00000002 b condition_rate
00000002 b mainLoop_count
00000002 b throttle_nudge
00000002 b loiter_time_max
00000002 b event_undo_value
00000002 b ground_start_avg
00000002 b g_gps
00000002 b pmTest1
00000002 b G_Dt_max
00000002 b airspeed
00000002 d ch1_temp
00000002 d ch2_temp
00000002 b failsafe
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 d throttle_slew_limit()::last
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000004 b event_timer
00000004 d hold_course
00000004 b loiter_time
00000004 b nav_bearing
00000004 d scaleLongUp
00000004 b wp_distance
00000004 b current_amps
00000004 b energy_error
00000004 b bearing_error
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b airspeed_error
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b condition_start
00000004 b condition_value
00000004 d nav_gain_scaler
00000004 b offset_altitude
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b crosstrack_error
00000004 b medium_loopTimer
00000004 b takeoff_altitude
00000004 b wp_totalDistance
00000004 b ch3_failsafe_timer
00000004 b crosstrack_bearing
00000004 b fast_loopTimeStamp
00000004 b old_target_bearing
00000004 b rc_override_fs_timer
00000004 b airspeed_energy_error
00000004 d G_Dt
00000004 b load
00000004 b dTnav
00000004 b nav_roll
00000004 b nav_pitch
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 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
00000004 B xi
00000004 B xi2
00000004 B xiyi
00000004 B xoffset
00000004 B yi
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 PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000006 r init_ardupilot()::__c
00000007 b planner_menu
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 r __menu_name__planner_menu
00000008 W AP_IMU_Shim::update()
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 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 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 V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU
0000000c r control_failsafe(unsigned int)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c
0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__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 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 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 V vtable for AP_VarT<long>
0000000e r process_may()::__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
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
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f r failsafe_short_on_event()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
00000010 t mavlink_get_channel_status
00000011 r set_next_WP(Location*)::__c
00000011 r startup_ground()::__c
00000011 r load_next_command_from_EEPROM()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
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<long>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000012 B adc
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 set_guided_WP()::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__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
00000018 r process_must()::__c
00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c
0000001a t startup_IMU_ground()
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c
0000001b r failsafe_short_off_event()::__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 t failsafe_short_off_event()
0000001e r startup_ground()::__c
00000020 t byte_swap_4
00000022 t reset_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()
00000022 W AP_VarT<long>::~AP_VarT()
00000022 r increment_WP_index()::__c
00000022 r verify_loiter_time()::__c
00000023 r navigate()::__c
00000024 r verify_loiter_turns()::__c
00000026 b mavlink_queue
00000026 r init_ardupilot()::__c
00000027 r init_ardupilot()::__c
00000028 t increment_WP_index()
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000028 B imu
0000002a t demo_servos(unsigned char)
0000002b r verify_must()::__c
0000002b r change_command(unsigned char)::__c
0000002e t reset_control_switch()
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 verify_nav_wp()::__c
00000030 r verify_may()::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000039 r init_ardupilot()::__c
0000003a W PID::~PID()
0000003a B g_gps_driver
0000003c t verify_loiter_turns()
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
00000040 B history
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)
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000056 t change_command(unsigned char)
00000057 B dcm
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e T GCS_MAVLINK::_count_parameters()
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000064 t mavlink_msg_param_value_send
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time()
0000007c t failsafe_short_on_event()
00000080 t do_RTL()
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000096 t map_baudrate(signed char, unsigned long)
0000009c t update_servo_switches()
0000009d B gcs
0000009d B hil
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ab B compass
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
000000c0 t calc_bearing_error()
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000ca t control_failsafe(unsigned int)
000000cc t read_control_switch()
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000d0 t get_bearing(Location*, Location*)
000000da t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000f0 t throttle_slew_limit()
000000f4 t _mav_finalize_message_chan_send
00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t get_distance(Location*, Location*)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 T GCS_MAVLINK::_queued_send()
00000130 t set_wp_with_index(Location, int)
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
0000013e t process_may()
0000013e t calc_nav_roll()
0000014e t verify_may()
0000014e T GCS_MAVLINK::update()
0000016a t process_must()
0000016a t set_guided_WP()
00000172 t navigate()
0000019e t startup_ground()
000001ae T init_home()
000001b2 t update_crosstrack()
000001ca t mavlink_delay(unsigned long)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle()
0000021c t set_mode(unsigned char)
00000232 t verify_must()
0000024c t update_loiter()
000002e4 t read_radio()
00000320 t __static_initialization_and_destruction_0(int, int)
0000033a W Parameters::~Parameters()
000003c0 t process_next_command()
000004b2 t mavlink_parse_char
00000518 t init_ardupilot()
00000831 b g
0000090a W Parameters::Parameters()
00001240 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001868 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001aac T loop

View File

@ -0,0 +1,177 @@
%% ArduPlane.cpp
%% ArduPlane.o
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.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:25: warning: 'bool print_log_menu()' declared 'static' but never defined
autogenerated:28: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
autogenerated:29: warning: 'int find_last_log_page(int)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/Log.pde:745: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Control_Tuning()' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Raw()' defined but not used
autogenerated:40: warning: 'void Log_Read_Current()' declared 'static' but never defined
autogenerated:41: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
autogenerated:42: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
autogenerated:43: warning: 'void Log_Read_Performance()' declared 'static' but never defined
autogenerated:44: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
autogenerated:45: warning: 'void Log_Read_Startup()' declared 'static' but never defined
autogenerated:46: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
autogenerated:47: warning: 'void Log_Read_Mode()' declared 'static' but never defined
autogenerated:48: warning: 'void Log_Read_GPS()' declared 'static' but never defined
autogenerated:49: warning: 'void Log_Read_Raw()' declared 'static' but never defined
autogenerated:50: warning: 'void Log_Read(int, int)' declared 'static' but never defined
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
autogenerated:149: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:150: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:152: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:154: warning: 'void report_batt_monitor()' declared 'static' but never defined
autogenerated:155: warning: 'void report_radio()' declared 'static' but never defined
autogenerated:156: warning: 'void report_gains()' declared 'static' but never defined
autogenerated:157: warning: 'void report_xtrack()' declared 'static' but never defined
autogenerated:158: warning: 'void report_throttle()' declared 'static' but never defined
autogenerated:159: warning: 'void report_imu()' declared 'static' but never defined
autogenerated:160: warning: 'void report_compass()' declared 'static' but never defined
autogenerated:161: warning: 'void report_flight_modes()' declared 'static' but never defined
autogenerated:162: warning: 'void print_PID(PID*)' declared 'static' but never defined
autogenerated:163: warning: 'void print_radio_values()' declared 'static' but never defined
autogenerated:164: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
autogenerated:165: warning: 'void print_done()' declared 'static' but never defined
autogenerated:166: warning: 'void print_blanks(int)' declared 'static' but never defined
autogenerated:167: warning: 'void print_divider()' declared 'static' but never defined
autogenerated:168: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
autogenerated:169: warning: 'void zero_eeprom()' declared 'static' but never defined
autogenerated:170: warning: 'void print_enabled(bool)' declared 'static' but never defined
autogenerated:171: warning: 'void print_accel_offsets()' declared 'static' but never defined
autogenerated:172: warning: 'void print_gyro_offsets()' declared 'static' but never defined
autogenerated:183: warning: 'void print_hit_enter()' declared 'static' but never defined
autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:210: warning: 'comma' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:212: warning: 'flight_mode_strings' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:317: warning: 'airspeed_raw' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:318: warning: 'airspeed_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:322: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduPlane/Log.pde:742: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
/root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' 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_MaxsonarXL.o
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
%% libraries/AP_RangeFinder/RangeFinder.o
%% libraries/DataFlash/DataFlash.o
In file included from /root/apm/ardupilot-mega/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
%% ArduPlane.elf
%% ArduPlane.eep
%% ArduPlane.hex

View File

@ -0,0 +1,412 @@
00000001 b GPS_enabled
00000001 b crash_timer
00000001 b home_is_set
00000001 b ch3_failsafe
00000001 b land_complete
00000001 b command_may_ID
00000001 b command_must_ID
00000001 b failsafeCounter
00000001 b counter_one_herz
00000001 b in_mavlink_delay
00000001 b slow_loopCounter
00000001 d takeoff_complete
00000001 b command_may_index
00000001 b command_must_index
00000001 b delta_ms_fast_loop
00000001 d ground_start_count
00000001 b medium_loopCounter
00000001 b rc_override_active
00000001 b delta_ms_medium_loop
00000001 b superslow_loopCounter
00000001 b event_id
00000001 b GPS_light
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 D control_mode
00000001 B hindex
00000001 B inverted_flight
00000001 B mavdelay
00000001 B n
00000001 B oldSwitchPosition
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
00000002 d elevon1_trim
00000002 d elevon2_trim
00000002 b event_repeat
00000002 b loiter_delta
00000002 b loiter_total
00000002 b gps_fix_count
00000002 b landing_pitch
00000002 b takeoff_pitch
00000002 b airspeed_nudge
00000002 b condition_rate
00000002 b mainLoop_count
00000002 b throttle_nudge
00000002 b loiter_time_max
00000002 b event_undo_value
00000002 b ground_start_avg
00000002 b g_gps
00000002 b pmTest1
00000002 b G_Dt_max
00000002 b airspeed
00000002 d ch1_temp
00000002 d ch2_temp
00000002 b failsafe
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 d throttle_slew_limit()::last
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000002 V PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000004 b event_timer
00000004 d hold_course
00000004 b loiter_time
00000004 b nav_bearing
00000004 d scaleLongUp
00000004 b wp_distance
00000004 b current_amps
00000004 b energy_error
00000004 b bearing_error
00000004 b current_total
00000004 b nav_loopTimer
00000004 d scaleLongDown
00000004 b airspeed_error
00000004 b altitude_error
00000004 b fast_loopTimer
00000004 b perf_mon_timer
00000004 b target_bearing
00000004 d battery_voltage
00000004 b condition_start
00000004 b condition_value
00000004 d nav_gain_scaler
00000004 b offset_altitude
00000004 b target_altitude
00000004 d battery_voltage1
00000004 d battery_voltage2
00000004 d battery_voltage3
00000004 d battery_voltage4
00000004 b crosstrack_error
00000004 b medium_loopTimer
00000004 b takeoff_altitude
00000004 b wp_totalDistance
00000004 b ch3_failsafe_timer
00000004 b crosstrack_bearing
00000004 b fast_loopTimeStamp
00000004 b old_target_bearing
00000004 b rc_override_fs_timer
00000004 b airspeed_energy_error
00000004 d G_Dt
00000004 b load
00000004 b dTnav
00000004 b nav_roll
00000004 b nav_pitch
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 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
00000004 B xi
00000004 B xi2
00000004 B xiyi
00000004 B xoffset
00000004 B yi
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 PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)::__c
00000006 r init_ardupilot()::__c
00000007 b planner_menu
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 r __menu_name__planner_menu
00000008 W AP_IMU_Shim::update()
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 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 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 V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r control_failsafe(unsigned int)::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000b V Parameters::Parameters()::__c
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU
0000000c r control_failsafe(unsigned int)::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000c V Parameters::Parameters()::__c
0000000d r init_home()::__c
0000000d r verify_RTL()::__c
0000000d r demo_servos(unsigned char)::__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 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 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 V vtable for AP_VarT<long>
0000000e r process_may()::__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
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
0000000e V Parameters::Parameters()::__c
0000000f b current_loc
0000000f b next_command
0000000f b home
0000000f b next_WP
0000000f b prev_WP
0000000f b guided_WP
0000000f r failsafe_short_on_event()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
0000000f V Parameters::Parameters()::__c
00000010 b rc_override
00000010 r planner_menu_commands
00000010 W AP_VarT<float>::cast_to_float() const
00000010 W AP_VarT<long>::cast_to_float() const
00000010 t mavlink_get_channel_status
00000011 r set_next_WP(Location*)::__c
00000011 r startup_ground()::__c
00000011 r load_next_command_from_EEPROM()::__c
00000012 B Serial
00000012 B Serial1
00000012 B Serial3
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<long>::~AP_VarT()
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000012 B adc
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 set_guided_WP()::__c
00000015 r map_baudrate(signed char, unsigned long)::__c
00000015 r init_ardupilot()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__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
00000018 r process_must()::__c
00000019 r failsafe_long_on_event()::__c
00000019 r GCS_MAVLINK::update()::__c
0000001a t startup_IMU_ground()
0000001a r reset_control_switch()::__c
0000001a r failsafe_short_on_event()::__c
0000001b r failsafe_short_off_event()::__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 t failsafe_short_off_event()
0000001e r startup_ground()::__c
00000020 t byte_swap_4
00000022 t reset_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()
00000022 W AP_VarT<long>::~AP_VarT()
00000022 r increment_WP_index()::__c
00000022 r verify_loiter_time()::__c
00000023 r navigate()::__c
00000024 r verify_loiter_turns()::__c
00000026 b mavlink_queue
00000026 r init_ardupilot()::__c
00000027 r init_ardupilot()::__c
00000028 t increment_WP_index()
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
00000028 W AP_VarT<float>::serialize(void*, unsigned int) const
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
00000028 B imu
0000002a t demo_servos(unsigned char)
0000002b r verify_must()::__c
0000002b r change_command(unsigned char)::__c
0000002e t reset_control_switch()
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 verify_nav_wp()::__c
00000030 r verify_may()::__c
00000032 T GCS_MAVLINK::init(FastSerial*)
00000034 t _MAV_RETURN_float
00000034 W AP_Float16::serialize(void*, unsigned int) const
00000034 t _mav_put_int8_t_array
00000039 r init_ardupilot()::__c
0000003a W PID::~PID()
0000003a B g_gps_driver
0000003c t verify_loiter_turns()
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
00000040 B history
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)
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*)
00000050 t failsafe_long_on_event()
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
00000056 t change_command(unsigned char)
00000057 B dcm
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
0000005e T GCS_MAVLINK::_count_parameters()
00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char)
00000060 t _mavlink_send_uart
00000064 t mavlink_msg_param_value_send
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
00000070 r init_ardupilot()::__c
00000074 t verify_loiter_time()
0000007c t failsafe_short_on_event()
00000080 t do_RTL()
00000080 T __vector_25
00000080 T __vector_36
00000080 T __vector_54
00000096 t map_baudrate(signed char, unsigned long)
0000009c t update_servo_switches()
0000009d B gcs
0000009d B hil
000000a4 T __vector_26
000000a4 T __vector_37
000000a4 T __vector_55
000000ab B compass
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
000000c0 t calc_bearing_error()
000000c4 t update_events()
000000c4 t load_next_command_from_EEPROM()
000000ca t control_failsafe(unsigned int)
000000cc t read_control_switch()
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
000000d0 t get_bearing(Location*, Location*)
000000d8 t verify_nav_wp()
000000e0 b mavlink_parse_char::m_mavlink_message
000000f0 t throttle_slew_limit()
000000f4 t _mav_finalize_message_chan_send
00000106 t calc_nav_pitch()
00000106 t get_wp_with_index(int)
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t get_distance(Location*, Location*)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 T GCS_MAVLINK::_queued_send()
00000130 t set_wp_with_index(Location, int)
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
0000013e t process_may()
0000013e t calc_nav_roll()
0000014e t verify_may()
0000014e T GCS_MAVLINK::update()
0000016a t process_must()
0000016a t set_guided_WP()
00000172 t navigate()
0000019e t startup_ground()
000001ae T init_home()
000001b2 t update_crosstrack()
000001ca t mavlink_delay(unsigned long)
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000206 t set_next_WP(Location*)
00000208 t calc_throttle()
0000021c t set_mode(unsigned char)
00000232 t verify_must()
0000024c t update_loiter()
000002e4 t read_radio()
00000320 t __static_initialization_and_destruction_0(int, int)
0000033a W Parameters::~Parameters()
000003c0 t process_next_command()
000004b2 t mavlink_parse_char
00000518 t init_ardupilot()
00000831 b g
0000090a W Parameters::Parameters()
00001240 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
00001868 T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001aac T loop

View File

@ -1,28 +1,28 @@
<?xml version="1.0" encoding="utf-8" ?>
<options>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/crap-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/crap-2560.hex</url2560>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/crap-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/crap-2560.hex</url2560>
<name> Please Update</name>
<desc></desc>
<format_version>0</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/APM2-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/APM2-2560.hex</url2560>
<name>ArduPilotMega V2.23 </name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
<name>ArduPlane V2.24 </name>
<desc></desc>
<format_version>11</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/APM2HIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/APM2HIL-2560.hex</url2560>
<name>ArduPilotMega V2.23 HIL</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
<name>ArduPlane V2.24 HIL</name>
<desc>
#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_3 FLY_BY_WIRE_A
#define FLIGHT_MODE_4 FLY_BY_WIRE_B
#define FLIGHT_MODE_5 STABILIZE
#define FLIGHT_MODE_6 MANUAL
@ -49,16 +49,16 @@
<format_version>11</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/APM-trunk-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/APM-trunk-2560.hex</url2560>
<name>ArduPilotMega V2.23 APM trunk</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
<name>ArduPlane V2.24 APM trunk</name>
<desc></desc>
<format_version>11</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<name>AC 2.0.40 Beta Quad</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<name>ArduCopter 2.0.40 Beta Quad</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -67,9 +67,9 @@
<format_version>107</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<name>AC 2.0.40 Beta Tri</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<name>ArduCopter 2.0.40 Beta Tri</name>
<desc>
#define FRAME_CONFIG TRI_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -78,9 +78,9 @@
<format_version>107</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<name>AC 2.0.40 Beta Hexa</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<name>ArduCopter 2.0.40 Beta Hexa</name>
<desc>
#define FRAME_CONFIG HEXA_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -89,9 +89,9 @@
<format_version>107</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<name>AC 2.0.40 Beta Y6</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<name>ArduCopter 2.0.40 Beta Y6</name>
<desc>
#define FRAME_CONFIG Y6_FRAME
#define FRAME_ORIENTATION X_FRAME
@ -100,9 +100,9 @@
<format_version>107</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
<name>AC 2.0.40 Beta Heli (2560 only)</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
<name>ArduCopter 2.0.40 Beta Heli (2560 only)</name>
<desc>
#define AUTO_RESET_LOITER 0
#define FRAME_CONFIG HELI_FRAME
@ -147,9 +147,9 @@
<format_version>107</format_version>
</Firmware>
<Firmware>
<url>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
<name>AC 2.0.40 Beta Quad Hil</name>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
<name>ArduCopter 2.0.40 Beta Quad Hil</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME

View File

@ -0,0 +1 @@
Already up-to-date.

View File

@ -52,7 +52,7 @@ namespace ArdupilotMega.GCSViews
// enable disable relevbant hardware tabs
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{
ConfigTabs.SelectedIndex = 0;
TabAPM2.Enabled = true;
@ -524,7 +524,7 @@ namespace ArdupilotMega.GCSViews
{
StreamWriter sw = new StreamWriter(sfd.OpenFile());
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{
input = DateTime.Now + " Plane: Skywalker";
}

View File

@ -250,7 +250,7 @@ namespace ArdupilotMega.GCSViews
{
if (keyData == (Keys.Control | Keys.B))
{
findfirmware("APM-trunk");
findfirmware("AP-trunk");
return true;
}
if (keyData == (Keys.Control | Keys.A))
@ -273,8 +273,6 @@ namespace ArdupilotMega.GCSViews
public int k_format_version;
}
FRAMETYPES currentframe = FRAMETYPES.NONE;
public enum FRAMETYPES
{
NONE,
@ -306,7 +304,7 @@ namespace ArdupilotMega.GCSViews
try
{
using (XmlTextReader xmlreader = new XmlTextReader("http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/firmware2.xml"))
using (XmlTextReader xmlreader = new XmlTextReader("http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml"))
{
while (xmlreader.Read())
{
@ -378,49 +376,41 @@ namespace ArdupilotMega.GCSViews
private void pictureBoxAPM_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.APM;
findfirmware("APM2-");
findfirmware("firmware/AP-");
}
private void pictureBoxAPMHIL_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.APMHIL;
findfirmware("APM2HIL-");
findfirmware("firmware/APHIL-");
}
private void pictureBoxQuad_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.QUAD;
findfirmware("AC2-Quad-");
}
private void pictureBoxHexa_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.HEXA;
findfirmware("AC2-Hexa-");
}
private void pictureBoxTri_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.TRI;
findfirmware("AC2-Tri-");
}
private void pictureBoxY6_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.Y6;
findfirmware("AC2-Y6-");
}
private void pictureBoxHeli_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.HELI;
findfirmware("AC2-Heli-");
}
private void pictureBoxQuadHil_Click(object sender, EventArgs e)
{
currentframe = FRAMETYPES.QUAD;
findfirmware("AC2-QUADHIL");
}
@ -502,15 +492,19 @@ namespace ArdupilotMega.GCSViews
this.Refresh();
while (dataStream.CanRead && bytes > 0)
dataStream.ReadTimeout = 30000;
while (dataStream.CanRead)
{
try
{
progress.Value = (int)(((float)(response.ContentLength - bytes) / (float)response.ContentLength) * 100);
progress.Value = 50;// (int)(((float)(response.ContentLength - bytes) / (float)response.ContentLength) * 100);
this.progress.Refresh();
}
catch { }
int len = dataStream.Read(buf1, 0, 1024);
if (len == 0)
break;
bytes -= len;
fs.Write(buf1, 0, len);
}
@ -704,420 +698,6 @@ namespace ArdupilotMega.GCSViews
}
}
private void ACSetup_Click(object sender, EventArgs e)
{
MainV2.givecomport = true;
MessageBox.Show("Please make sure you are in CLI/Setup mode");
ICommsSerial comPortT = MainV2.comPort.BaseStream;
if (comPortT.IsOpen)
comPortT.Close();
comPortT.DtrEnable = true;
if (MainV2.comportname == null)
{
MessageBox.Show("Please select a valid comport! look in the Options menu");
MainV2.givecomport = false;
return;
}
try
{
comPortT.Open();
}
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
lbl_status.Text = "Comport Opened";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
string data = "";
DateTime timeout = DateTime.Now;
///////////////////////// FIX ME////////////////////////////////////////////////////////
int step = 0;
//System.Threading.Thread.Sleep(2000);
//comPortT.Write("IMU\r");
comPortT.ReadTimeout = -1;
while (comPortT.IsOpen)
{
string line;
try
{
line = comPortT.ReadLine();
}
catch
{
try { line = comPortT.ReadExisting(); }
catch { MessageBox.Show("Can not read from serial port - existing"); return; }
}
this.Refresh();
Console.Write(line + "\n");
switch (step)
{
case 0:
if (line.Contains("interactive"))
{
lbl_status.Text = "Erasing EEPROM.. (20 seconds)";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("erase\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("y\r");
step = 0;
}
if (line.Contains("done"))
{
lbl_status.Text = "Rebooting APM..";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
step = 1;
}
break;
case 1:
if (line.Contains("interactive")) // becuase we rebooted
{
lbl_status.Text = "Setup Radio..";
this.Refresh();
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(200);
MessageBox.Show("Ensure that your RC transmitter is on, and that you have your ArduCopter battery plugged in or are otherwise powering APM's RC pins (USB power does NOT power the RC receiver)", "Radio Setup");
comPortT.Write("radio\r");
MessageBox.Show("Move all your radio controls to each extreme. Hit OK when done.", "Radio Setup");
//comPortT.DiscardInBuffer();
comPortT.Write("\r\r");
step = 2;
}
break;
case 2:
if (data.Contains("----"))
data = "";
data += line;
if (line.Contains("CH7")) //
{
MessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
lbl_status.Text = "Setup Accel Offsets..";
this.Refresh();
MessageBox.Show("Ensure your quad is level, and click OK to continue", "Offset Setup");
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("level\r");
System.Threading.Thread.Sleep(1000);
step = 3;
}
break;
case 3:
if (line.Contains("IMU")) //
{
lbl_status.Text = "Setup Options";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
DialogResult dr;
/*
dr = MessageBox.Show("Do you have a Current sensor attached?","Current Sensor",MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("current on\r");
System.Threading.Thread.Sleep(100);
}*/
dr = MessageBox.Show("Do you have a Sonar sensor attached?", "Sonar Sensor", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("sonar on\r");
System.Threading.Thread.Sleep(100);
}
dr = MessageBox.Show("Do you have a Compass sensor attached?", "Compass Sensor", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("compass on\r");
System.Threading.Thread.Sleep(100);
MessageBox.Show("Next a webpage will appear to get your magnetic declination,\nenter it in the box that appears next", "Mag Dec");
try
{
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
}
catch { MessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
//This can be taken from
try
{
string declination = "0";
Common.InputBox("Declination", "Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3", ref declination);
float dec = 0.0f;
float.TryParse(declination, out dec);
float deg = (float)((int)dec);
float mins = (dec - deg);
if (dec > 0)
{
dec += ((mins) / 60.0f);
}
else
{
dec -= ((mins) / 60.0f);
}
comPortT.Write("exit\rsetup\rdeclination " + dec.ToString("0.00") + "\r");
}
catch { MessageBox.Show("Invalid input!"); }
}
if (currentframe == FRAMETYPES.Y6 || currentframe == FRAMETYPES.Y6)
{
}
else
{
string frame = "+";
Common.InputBox("Frame", "Enter Frame type (options +, x)", ref frame);
System.Text.ASCIIEncoding encoding = new System.Text.ASCIIEncoding();
byte[] data2 = encoding.GetBytes("exit\rsetup\rframe " + frame.ToLower() + "\r");
comPortT.Write(data2, 0, data2.Length);
}
Console.WriteLine(comPortT.ReadExisting());
MessageBox.Show("NOTE: this setup has defaulted all modes to stabilize.\n To change your flight modes, please use the CLI menu via the Terminal tab");
comPortT.Close();
MainV2.givecomport = false;
return;
//step = 4;
}
break;
//
}
}
}
private void APMSetup_Click(object sender, EventArgs e)
{
MainV2.givecomport = true;
MessageBox.Show("Please make sure you are in CLI/Setup mode");
ICommsSerial comPortT = MainV2.comPort.BaseStream;
if (comPortT.IsOpen)
comPortT.Close();
comPortT.DtrEnable = true;
if (MainV2.comportname == null)
{
MessageBox.Show("Please select a valid comport! look in the Options menu");
MainV2.givecomport = false;
return;
}
try
{
comPortT.Open();
}
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
lbl_status.Text = "Comport Opened";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
string data = "";
DateTime timeout = DateTime.Now;
///////////////////////// FIX ME////////////////////////////////////////////////////////
int step = 0;
//System.Threading.Thread.Sleep(2000);
//comPortT.Write("CH7\r");
comPortT.ReadTimeout = -1;
while (comPortT.IsOpen)
{
string line;
try
{
line = comPortT.ReadLine();
}
catch
{
try { line = comPortT.ReadExisting(); }
catch { MessageBox.Show("Can not read from serial port - existing"); return; }
}
this.Refresh();
Console.Write(line + "\n");
switch (step)
{
case 0:
if (line.Contains("interactive"))
{
lbl_status.Text = "Erasing EEPROM.. (20 seconds)";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("erase\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("y\r");
step = 0;
}
if (line.Contains("done"))
{
lbl_status.Text = "Rebooting APM..";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
step = 1;
}
break;
case 1:
if (line.Contains("interactive")) // becuase we rebooted
{
lbl_status.Text = "Setup Radio..";
this.Refresh();
System.Threading.Thread.Sleep(1000);
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(200);
MessageBox.Show("Ensure that your RC transmitter is on, and that you have your ArduPilot battery plugged in or are otherwise powering APM's RC pins (USB power does NOT power the RC receiver)", "Radio Setup");
comPortT.Write("radio\r");
Console.WriteLine(comPortT.ReadExisting());
MessageBox.Show("Move all your radio controls to each extreme. Hit OK when done.", "Radio Setup");
comPortT.Write("\r\r");
step = 2;
}
break;
case 2:
if (data.Contains("----"))
data = "";
data += line;
if (line.Contains("CH7")) //
{
MessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
lbl_status.Text = "Clearing Log Dataflash (this may take a minute)";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("exit\rlogs\rerase\r");
System.Threading.Thread.Sleep(200);
Console.WriteLine(comPortT.ReadExisting());
step = 3;
}
break;
case 3:
if (line.Contains("Log erased"))
{
lbl_status.Text = "Setup Options";
this.Refresh();
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(50);
comPortT.Write("exit\rsetup\r");
DialogResult dr;
dr = MessageBox.Show("Do you have a Compass sensor attached?", "Compass Sensor", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("compass on\r");
System.Threading.Thread.Sleep(100);
MessageBox.Show("Next a webpage will appear to get your magnetic declination,\nenter it in the box that appears next", "Mag Dec");
try
{
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
}
catch { MessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
//This can be taken from
string declination = "0";
Common.InputBox("Declination", "Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3", ref declination);
float dec = 0.0f;
float.TryParse(declination, out dec);
float deg = (float)((int)dec);
float mins = (dec - deg);
if (dec > 0)
{
dec += ((mins) / 60.0f);
}
else
{
dec -= ((mins) / 60.0f);
}
comPortT.Write("exit\rsetup\rdeclination " + dec.ToString() + "\r");
}
MessageBox.Show("NOTE: this setup has defaulted all modes to there default.\n As you are new these are the safest.\n To change this option please use the modes option in the CLI");
Console.WriteLine(comPortT.ReadExisting());
comPortT.Close();
MainV2.givecomport = false;
lbl_status.Text = "Setup Done";
this.Refresh();
return;
//step = 4;
}
break;
//
}
}
}
private void BUT_setup_Click(object sender, EventArgs e)
{
Form temp = new Setup.Setup();

View File

@ -368,7 +368,7 @@ namespace ArdupilotMega.GCSViews
PointLatLng currentloc = new PointLatLng(MainV2.cs.lat, MainV2.cs.lng);
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing,MainV2.cs.target_bearing));
}

View File

@ -616,16 +616,16 @@ namespace ArdupilotMega.GCSViews
switch (command)
{
case MAVLink.MAV_CMD.WAYPOINT:
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
Commands.Columns[1].HeaderText = "N/A";
break;
case MAVLink.MAV_CMD.LAND:
Commands.Columns[1].HeaderText = "N/A";
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
Commands.Columns[2].HeaderText = "N/A";
break;
case MAVLink.MAV_CMD.TAKEOFF:
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
Commands.Columns[1].HeaderText = "N/A";
break;
}
@ -1248,11 +1248,13 @@ namespace ArdupilotMega.GCSViews
}
catch (Exception ex) { MessageBox.Show("Error : " + ex.ToString()); }
MainV2.givecomport = false;
try
{
this.BeginInvoke((System.Threading.ThreadStart)delegate()
{
MainV2.givecomport = false;
BUT_write.Enabled = true;
});
}

View File

@ -167,28 +167,34 @@ System.ComponentModel.Category("Values")]
if (this.DesignMode)
return;
GraphicsMode test = this.GraphicsMode;
Console.WriteLine(test.ToString());
Console.WriteLine("Vendor: "+GL.GetString(StringName.Vendor));
Console.WriteLine("Version: " + GL.GetString(StringName.Version));
Console.WriteLine("Device: " + GL.GetString(StringName.Renderer));
//Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions));
try
{
int[] viewPort = new int[4];
GL.GetInteger(GetPName.Viewport, viewPort);
GL.MatrixMode(MatrixMode.Projection);
GL.LoadIdentity();
GL.Ortho(0, Width, Height, 0, -1, 1);
GL.MatrixMode(MatrixMode.Modelview);
GL.LoadIdentity();
GraphicsMode test = this.GraphicsMode;
Console.WriteLine(test.ToString());
Console.WriteLine("Vendor: " + GL.GetString(StringName.Vendor));
Console.WriteLine("Version: " + GL.GetString(StringName.Version));
Console.WriteLine("Device: " + GL.GetString(StringName.Renderer));
//Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions));
GL.PushAttrib(AttribMask.DepthBufferBit);
GL.Disable(EnableCap.DepthTest);
//GL.Enable(EnableCap.Texture2D);
GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
GL.Enable(EnableCap.Blend);
int[] viewPort = new int[4];
GL.GetInteger(GetPName.Viewport, viewPort);
GL.MatrixMode(MatrixMode.Projection);
GL.LoadIdentity();
GL.Ortho(0, Width, Height, 0, -1, 1);
GL.MatrixMode(MatrixMode.Modelview);
GL.LoadIdentity();
GL.PushAttrib(AttribMask.DepthBufferBit);
GL.Disable(EnableCap.DepthTest);
//GL.Enable(EnableCap.Texture2D);
GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
GL.Enable(EnableCap.Blend);
}
catch (Exception ex) { Console.WriteLine("HUD opengl onload "+ex.ToString()); }
try
{

View File

@ -38,8 +38,6 @@ namespace ArdupilotMega
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "logs";
Common.getFilefromNet("url", Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "dataflashlog.xml");
if (openFileDialog1.ShowDialog() == DialogResult.OK)
{
try
@ -156,7 +154,7 @@ namespace ArdupilotMega
{
reader.Read();
reader.ReadStartElement("LOGFORMAT");
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{
reader.ReadToFollowing("APM");
}

View File

@ -1021,7 +1021,7 @@ namespace ArdupilotMega
break;
case (byte)MAV_CMD.LOITER_TIME:
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{
loc.p1 = (byte)(wp.param1 / 10); // APM loiter time is in ten second increments
}

View File

@ -36,7 +36,7 @@ namespace ArdupilotMega
public static string comportname = "";
public static Hashtable config = new Hashtable();
public static bool givecomport = false;
public static Firmwares APMFirmware = Firmwares.ArduPilotMega;
public static Firmwares APMFirmware = Firmwares.ArduPlane;
public static bool MAC = false;
public static bool speechenable = false;
@ -60,7 +60,7 @@ namespace ArdupilotMega
public enum Firmwares
{
ArduPilotMega,
ArduPlane,
ArduCopter2,
}
@ -595,7 +595,7 @@ namespace ArdupilotMega
}
else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 0)
{
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPilotMega);
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
}
}
@ -1224,7 +1224,7 @@ namespace ArdupilotMega
{
try
{
string baseurl = "http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/bin/Release/";
string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/";
bool update = updatecheck(loadinglabel, baseurl, "");
System.Diagnostics.Process P = new System.Diagnostics.Process();
if (MAC)
@ -1266,6 +1266,7 @@ namespace ArdupilotMega
List<string> files = new List<string>();
// Create a request using a URL that can receive a post.
Console.WriteLine(baseurl);
WebRequest request = WebRequest.Create(baseurl);
request.Timeout = 10000;
// Set the Method property of the request to POST.
@ -1308,6 +1309,10 @@ namespace ArdupilotMega
Directory.CreateDirectory(dir);
foreach (string file in files)
{
if (file.Equals("/"))
{
continue;
}
if (file.EndsWith("/"))
{
update = updatecheck(loadinglabel, baseurl + file, file) && update;
@ -1336,10 +1341,10 @@ namespace ArdupilotMega
{
FileInfo fi = new FileInfo(path);
if (fi.Length != response.ContentLength || fi.LastWriteTimeUtc < DateTime.Parse(response.Headers["Last-Modified"].ToString()))
if (fi.Length != response.ContentLength)
{
getfile = true;
Console.WriteLine("NEW FILE " + file + " " + fi.LastWriteTime + " < " + DateTime.Parse(response.Headers["Last-Modified"].ToString()));
Console.WriteLine("NEW FILE " + file);
}
}
else
@ -1390,7 +1395,9 @@ namespace ArdupilotMega
DateTime dt = DateTime.Now;
while (dataStream.CanRead && bytes > 0)
dataStream.ReadTimeout = 30000;
while (dataStream.CanRead)
{
Application.DoEvents();
try
@ -1398,13 +1405,15 @@ namespace ArdupilotMega
if (dt.Second != DateTime.Now.Second)
{
if (loadinglabel != null)
loadinglabel.Text = "Getting " + file + ":" + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
loadinglabel.Text = "Getting " + file + ": " + Math.Abs(bytes) + " bytes";//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
dt = DateTime.Now;
}
}
catch { }
Console.WriteLine(file + " " + bytes);
int len = dataStream.Read(buf1, 0, 1024);
if (len == 0)
break;
bytes -= len;
fs.Write(buf1, 0, len);
}

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.0.66")]
[assembly: AssemblyFileVersion("1.0.67")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -48,7 +48,7 @@ namespace ArdupilotMega.Setup
float pwm = 0;
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) // APM
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{
pwm = MainV2.cs.ch8in;
LBL_flightmodepwm.Text = "8: " + MainV2.cs.ch8in.ToString();
@ -251,7 +251,7 @@ namespace ArdupilotMega.Setup
{
if (tabControl1.SelectedTab == tabModes)
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) // APM
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{
CMB_fmode1.Items.Clear();
CMB_fmode2.Items.Clear();
@ -339,7 +339,7 @@ namespace ArdupilotMega.Setup
if (tabControl1.SelectedTab == tabArducopter)
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
tabArducopter.Enabled = false;
return;
@ -394,7 +394,7 @@ namespace ArdupilotMega.Setup
{
try
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) // APM
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{
MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode1.Text));
MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode2.Text));

View File

@ -0,0 +1,3 @@
*.pdb
*.xml

View File

@ -0,0 +1 @@
<AVRStudio><MANAGEMENT><ProjectName>ap_ppm_encoder</ProjectName><Created>03-Dec-2009 19:19:14</Created><LastEdit>23-Jan-2010 22:43:53</LastEdit><ICON>241</ICON><ProjectType>0</ProjectType><Created>03-Dec-2009 19:19:14</Created><Version>4</Version><Build>4, 17, 0, 655</Build><ProjectTypeName>AVR GCC</ProjectTypeName></MANAGEMENT><CODE_CREATION><ObjectFile>default\ap_ppm_encoder.elf</ObjectFile><EntryFile></EntryFile><SaveFolder>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\</SaveFolder></CODE_CREATION><DEBUG_TARGET><CURRENT_TARGET>AVR Simulator</CURRENT_TARGET><CURRENT_PART>ATmega328P.xml</CURRENT_PART><BREAKPOINTS></BREAKPOINTS><IO_EXPAND><HIDE>false</HIDE></IO_EXPAND><REGISTERNAMES><Register>R00</Register><Register>R01</Register><Register>R02</Register><Register>R03</Register><Register>R04</Register><Register>R05</Register><Register>R06</Register><Register>R07</Register><Register>R08</Register><Register>R09</Register><Register>R10</Register><Register>R11</Register><Register>R12</Register><Register>R13</Register><Register>R14</Register><Register>R15</Register><Register>R16</Register><Register>R17</Register><Register>R18</Register><Register>R19</Register><Register>R20</Register><Register>R21</Register><Register>R22</Register><Register>R23</Register><Register>R24</Register><Register>R25</Register><Register>R26</Register><Register>R27</Register><Register>R28</Register><Register>R29</Register><Register>R30</Register><Register>R31</Register></REGISTERNAMES><COM>Auto</COM><COMType>0</COMType><WATCHNUM>0</WATCHNUM><WATCHNAMES><Pane0></Pane0><Pane1></Pane1><Pane2></Pane2><Pane3></Pane3></WATCHNAMES><BreakOnTrcaeFull>0</BreakOnTrcaeFull></DEBUG_TARGET><Debugger><modules><module></module></modules><Triggers></Triggers></Debugger><AVRGCCPLUGIN><FILES><SOURCEFILE>ap_ppm_encoder.c</SOURCEFILE><HEADERFILE>servo2ppm_settings.h</HEADERFILE><OTHERFILE>default\ap_ppm_encoder.lss</OTHERFILE><OTHERFILE>default\ap_ppm_encoder.map</OTHERFILE></FILES><CONFIGS><CONFIG><NAME>default</NAME><USESEXTERNALMAKEFILE>NO</USESEXTERNALMAKEFILE><EXTERNALMAKEFILE></EXTERNALMAKEFILE><PART>atmega328p</PART><HEX>1</HEX><LIST>1</LIST><MAP>1</MAP><OUTPUTFILENAME>ap_ppm_encoder.elf</OUTPUTFILENAME><OUTPUTDIR>default\</OUTPUTDIR><ISDIRTY>0</ISDIRTY><OPTIONS/><INCDIRS/><LIBDIRS/><LIBS/><LINKOBJECTS/><OPTIONSFORALL>-Wall -gdwarf-2 -std=gnu99 -DF_CPU=8000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums</OPTIONSFORALL><LINKEROPTIONS></LINKEROPTIONS><SEGMENTS/></CONFIG></CONFIGS><LASTCONFIG>default</LASTCONFIG><USES_WINAVR>1</USES_WINAVR><GCC_LOC>C:\WinAVR-20090313\bin\avr-gcc.exe</GCC_LOC><MAKE_LOC>C:\WinAVR-20090313\utils\bin\make.exe</MAKE_LOC></AVRGCCPLUGIN><ProjectFiles><Files><Name>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\servo2ppm_settings.h</Name><Name>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\ap_ppm_encoder.c</Name></Files></ProjectFiles><IOView><usergroups/><sort sorted="0" column="0" ordername="1" orderaddress="1" ordergroup="1"/></IOView><Files><File00000><FileId>00000</FileId><FileName>ap_ppm_encoder.c</FileName><Status>259</Status></File00000><File00001><FileId>00001</FileId><FileName>servo2ppm_settings.h</FileName><Status>1</Status></File00001></Files><Events><Bookmarks></Bookmarks></Events><Trace><Filters></Filters></Trace></AVRStudio>

View File

@ -0,0 +1 @@
<AVRWorkspace><IOSettings><CurrentRegisters/></IOSettings><part name="ATMEGA328P"/><Files><File00000 Name="C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\ap_ppm_encoder.c" Position="266 97 1157 411" LineCol="1016 8" State="Maximized"/><File00001 Name="C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\servo2ppm_settings.h" Position="258 67 1286 518" LineCol="96 47" State="Maximized"/></Files></AVRWorkspace>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,77 @@
###############################################################################
# Makefile for the project ap_ppm_encoder
###############################################################################
## General Flags
PROJECT = ap_ppm_encoder
MCU = atmega328p
TARGET = ap_ppm_encoder.elf
CC = avr-gcc
CPP = avr-g++
## Options common to compile, link and assembly rules
COMMON = -mmcu=$(MCU)
## Compile options common for all C compilation units.
CFLAGS = $(COMMON)
CFLAGS += -Wall -gdwarf-2 -std=gnu99 -DF_CPU=8000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
CFLAGS += -MD -MP -MT $(*F).o -MF dep/$(@F).d
## Assembly specific flags
ASMFLAGS = $(COMMON)
ASMFLAGS += $(CFLAGS)
ASMFLAGS += -x assembler-with-cpp -Wa,-gdwarf2
## Linker flags
LDFLAGS = $(COMMON)
LDFLAGS += -Wl,-Map=ap_ppm_encoder.map
## Intel Hex file production flags
HEX_FLASH_FLAGS = -R .eeprom -R .fuse -R .lock -R .signature
HEX_EEPROM_FLAGS = -j .eeprom
HEX_EEPROM_FLAGS += --set-section-flags=.eeprom="alloc,load"
HEX_EEPROM_FLAGS += --change-section-lma .eeprom=0 --no-change-warnings
## Objects that must be built in order to link
OBJECTS = ap_ppm_encoder.o
## Objects explicitly added by the user
LINKONLYOBJECTS =
## Build
all: $(TARGET) ap_ppm_encoder.hex ap_ppm_encoder.eep ap_ppm_encoder.lss size
## Compile
ap_ppm_encoder.o: ../ap_ppm_encoder.c
$(CC) $(INCLUDES) $(CFLAGS) -c $<
##Link
$(TARGET): $(OBJECTS)
$(CC) $(LDFLAGS) $(OBJECTS) $(LINKONLYOBJECTS) $(LIBDIRS) $(LIBS) -o $(TARGET)
%.hex: $(TARGET)
avr-objcopy -O ihex $(HEX_FLASH_FLAGS) $< $@
%.eep: $(TARGET)
-avr-objcopy $(HEX_EEPROM_FLAGS) -O ihex $< $@ || exit 0
%.lss: $(TARGET)
avr-objdump -h -S $< > $@
size: ${TARGET}
@echo
@avr-size -C --mcu=${MCU} ${TARGET}
## Clean target
.PHONY: clean
clean:
-rm -rf $(OBJECTS) ap_ppm_encoder.elf dep/* ap_ppm_encoder.hex ap_ppm_encoder.eep ap_ppm_encoder.lss ap_ppm_encoder.map
## Other dependencies
-include $(shell mkdir dep 2>/dev/null) $(wildcard dep/*)

View File

@ -0,0 +1,5 @@
:1000000001000100010001000100010001000100E8
:1000100001000100E907E907E907E907E907E9073E
:10002000E907E907E907E907E90702020202020214
:050030000202020202C1
:00000001FF

Binary file not shown.

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,419 @@
Archive member included because of file (symbol)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
ap_ppm_encoder.o (__udivmodhi4)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o (exit)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
ap_ppm_encoder.o (__do_copy_data)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
ap_ppm_encoder.o (__do_clear_bss)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
ap_ppm_encoder.o (__eerd_word)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
ap_ppm_encoder.o (__eewr_word)
Allocating common symbols
Common symbol size file
timer0 0x2 ap_ppm_encoder.o
isr_channel_pw 0x12 ap_ppm_encoder.o
Memory Configuration
Name Origin Length Attributes
text 0x00000000 0x00020000 xr
data 0x00800060 0x0000ffa0 rw !x
eeprom 0x00810000 0x00010000 rw !x
fuse 0x00820000 0x00000400 rw !x
lock 0x00830000 0x00000400 rw !x
signature 0x00840000 0x00000400 rw !x
*default* 0x00000000 0xffffffff
Linker script and memory map
Address of section .data set to 0x800100
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
LOAD ap_ppm_encoder.o
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a
.hash
*(.hash)
.dynsym
*(.dynsym)
.dynstr
*(.dynstr)
.gnu.version
*(.gnu.version)
.gnu.version_d
*(.gnu.version_d)
.gnu.version_r
*(.gnu.version_r)
.rel.init
*(.rel.init)
.rela.init
*(.rela.init)
.rel.text
*(.rel.text)
*(.rel.text.*)
*(.rel.gnu.linkonce.t*)
.rela.text
*(.rela.text)
*(.rela.text.*)
*(.rela.gnu.linkonce.t*)
.rel.fini
*(.rel.fini)
.rela.fini
*(.rela.fini)
.rel.rodata
*(.rel.rodata)
*(.rel.rodata.*)
*(.rel.gnu.linkonce.r*)
.rela.rodata
*(.rela.rodata)
*(.rela.rodata.*)
*(.rela.gnu.linkonce.r*)
.rel.data
*(.rel.data)
*(.rel.data.*)
*(.rel.gnu.linkonce.d*)
.rela.data
*(.rela.data)
*(.rela.data.*)
*(.rela.gnu.linkonce.d*)
.rel.ctors
*(.rel.ctors)
.rela.ctors
*(.rela.ctors)
.rel.dtors
*(.rel.dtors)
.rela.dtors
*(.rela.dtors)
.rel.got
*(.rel.got)
.rela.got
*(.rela.got)
.rel.bss
*(.rel.bss)
.rela.bss
*(.rela.bss)
.rel.plt
*(.rel.plt)
.rela.plt
*(.rela.plt)
.text 0x00000000 0xc1e
*(.vectors)
.vectors 0x00000000 0x68 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x00000000 __vectors
0x00000000 __vector_default
*(.vectors)
*(.progmem.gcc*)
*(.progmem*)
0x00000068 . = ALIGN (0x2)
0x00000068 __trampolines_start = .
*(.trampolines)
.trampolines 0x00000068 0x0 linker stubs
*(.trampolines*)
0x00000068 __trampolines_end = .
*(.jumptables)
*(.jumptables*)
*(.lowtext)
*(.lowtext*)
0x00000068 __ctors_start = .
*(.ctors)
0x00000068 __ctors_end = .
0x00000068 __dtors_start = .
*(.dtors)
0x00000068 __dtors_end = .
SORT(*)(.ctors)
SORT(*)(.dtors)
*(.init0)
.init0 0x00000068 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x00000068 __init
*(.init0)
*(.init1)
*(.init1)
*(.init2)
.init2 0x00000068 0xc c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
*(.init2)
*(.init3)
*(.init3)
*(.init4)
.init4 0x00000074 0x16 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
0x00000074 __do_copy_data
.init4 0x0000008a 0x10 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
0x0000008a __do_clear_bss
*(.init4)
*(.init5)
*(.init5)
*(.init6)
*(.init6)
*(.init7)
*(.init7)
*(.init8)
*(.init8)
*(.init9)
.init9 0x0000009a 0x8 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
*(.init9)
*(.text)
.text 0x000000a2 0x4 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x000000a2 __vector_22
0x000000a2 __vector_1
0x000000a2 __vector_24
0x000000a2 __bad_interrupt
0x000000a2 __vector_6
0x000000a2 __vector_3
0x000000a2 __vector_23
0x000000a2 __vector_25
0x000000a2 __vector_11
0x000000a2 __vector_13
0x000000a2 __vector_17
0x000000a2 __vector_19
0x000000a2 __vector_7
0x000000a2 __vector_4
0x000000a2 __vector_9
0x000000a2 __vector_2
0x000000a2 __vector_21
0x000000a2 __vector_15
0x000000a2 __vector_8
0x000000a2 __vector_14
0x000000a2 __vector_10
0x000000a2 __vector_18
0x000000a2 __vector_20
.text 0x000000a6 0xaf6 ap_ppm_encoder.o
0x0000038a load_failsafe_values
0x00000428 __vector_12
0x00000528 check_for_setup_mode
0x0000047e __vector_5
0x0000026c get_channel_pw
0x000004ca write_default_values_to_eeprom
0x000008ae main
0x000001d6 detect_connected_channels
0x000000d0 initialize_mcu
0x0000072e load_values_from_eeprom
0x000002fe wait_for_rx
0x000003e2 mux_control
0x00000406 __vector_16
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.text 0x00000b9c 0x2c c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
0x00000b9c __eerd_word
.text 0x00000bc8 0x2a c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
0x00000bc8 __eewr_word
0x00000bf2 . = ALIGN (0x2)
*(.text.*)
.text.libgcc 0x00000bf2 0x28 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
0x00000bf2 __udivmodhi4
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
0x00000c1a . = ALIGN (0x2)
*(.fini9)
.fini9 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
0x00000c1a exit
0x00000c1a _exit
*(.fini9)
*(.fini8)
*(.fini8)
*(.fini7)
*(.fini7)
*(.fini6)
*(.fini6)
*(.fini5)
*(.fini5)
*(.fini4)
*(.fini4)
*(.fini3)
*(.fini3)
*(.fini2)
*(.fini2)
*(.fini1)
*(.fini1)
*(.fini0)
.fini0 0x00000c1a 0x4 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
*(.fini0)
0x00000c1e _etext = .
.data 0x00800100 0x14 load address 0x00000c1e
0x00800100 PROVIDE (__data_start, .)
*(.data)
.data 0x00800100 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
.data 0x00800100 0x13 ap_ppm_encoder.o
0x00800112 rc_lost_channel
0x00800100 version_info
0x00800110 ppm_off_threshold
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
*(.data*)
*(.rodata)
*(.rodata*)
*(.gnu.linkonce.d*)
0x00800114 . = ALIGN (0x2)
*fill* 0x00800113 0x1 00
0x00800114 _edata = .
0x00800114 PROVIDE (__data_end, .)
.bss 0x00800114 0x1c
0x00800114 PROVIDE (__bss_start, .)
*(.bss)
.bss 0x00800114 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
.bss 0x00800114 0x8 ap_ppm_encoder.o
0x00800119 channel_mask
0x0080011a isr_timer0
0x00800115 isr_channel_number
0x00800118 channels_in_use
0x00800114 pin_interrupt_detected
0x00800116 isr_timer0_16
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
*(.bss*)
*(COMMON)
COMMON 0x0080011c 0x14 ap_ppm_encoder.o
0x0080011c timer0
0x0080011e isr_channel_pw
0x00800130 PROVIDE (__bss_end, .)
0x00000c1e __data_load_start = LOADADDR (.data)
0x00000c32 __data_load_end = (__data_load_start + SIZEOF (.data))
.noinit 0x00800130 0x0
0x00800130 PROVIDE (__noinit_start, .)
*(.noinit*)
0x00800130 PROVIDE (__noinit_end, .)
0x00800130 _end = .
0x00800130 PROVIDE (__heap_start, .)
.eeprom 0x00810000 0x35
*(.eeprom*)
.eeprom 0x00810000 0x35 ap_ppm_encoder.o
0x00810014 ppm_off_threshold_e
0x00810000 dummy_int
0x0081002a rc_lost_channel_e
0x00810035 __eeprom_end = .
.fuse
*(.fuse)
*(.lfuse)
*(.hfuse)
*(.efuse)
.lock
*(.lock*)
.signature
*(.signature*)
.stab
*(.stab)
.stabstr
*(.stabstr)
.stab.excl
*(.stab.excl)
.stab.exclstr
*(.stab.exclstr)
.stab.index
*(.stab.index)
.stab.indexstr
*(.stab.indexstr)
.comment
*(.comment)
.debug
*(.debug)
.line
*(.line)
.debug_srcinfo
*(.debug_srcinfo)
.debug_sfnames
*(.debug_sfnames)
.debug_aranges 0x00000000 0x20
*(.debug_aranges)
.debug_aranges
0x00000000 0x20 ap_ppm_encoder.o
.debug_pubnames
0x00000000 0x22c
*(.debug_pubnames)
.debug_pubnames
0x00000000 0x22c ap_ppm_encoder.o
.debug_info 0x00000000 0x914
*(.debug_info)
.debug_info 0x00000000 0x914 ap_ppm_encoder.o
*(.gnu.linkonce.wi.*)
.debug_abbrev 0x00000000 0x262
*(.debug_abbrev)
.debug_abbrev 0x00000000 0x262 ap_ppm_encoder.o
.debug_line 0x00000000 0xc94
*(.debug_line)
.debug_line 0x00000000 0xc94 ap_ppm_encoder.o
.debug_frame 0x00000000 0x100
*(.debug_frame)
.debug_frame 0x00000000 0x100 ap_ppm_encoder.o
.debug_str 0x00000000 0x43c
*(.debug_str)
.debug_str 0x00000000 0x43c ap_ppm_encoder.o
0x4ac (size before relaxing)
.debug_loc 0x00000000 0x3b4
*(.debug_loc)
.debug_loc 0x00000000 0x3b4 ap_ppm_encoder.o
.debug_macinfo
*(.debug_macinfo)
OUTPUT(ap_ppm_encoder.elf elf32-avr)
LOAD linker stubs
.debug_ranges 0x00000000 0x18
.debug_ranges 0x00000000 0x18 ap_ppm_encoder.o

View File

@ -0,0 +1,46 @@
ap_ppm_encoder.o: ../ap_ppm_encoder.c \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/io.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/sfr_defs.h \
c:/winavr-20090313/lib/gcc/../../avr/include/inttypes.h \
c:/winavr-20090313/lib/gcc/../../avr/include/stdint.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/iom328p.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/portpins.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/common.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/version.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/fuse.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/lock.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/interrupt.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/wdt.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/eeprom.h \
c:\winavr-20090313\bin\../lib/gcc/avr/4.3.2/include/stddef.h \
../servo2ppm_settings.h
c:/winavr-20090313/lib/gcc/../../avr/include/avr/io.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/sfr_defs.h:
c:/winavr-20090313/lib/gcc/../../avr/include/inttypes.h:
c:/winavr-20090313/lib/gcc/../../avr/include/stdint.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/iom328p.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/portpins.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/common.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/version.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/fuse.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/lock.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/interrupt.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/wdt.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/eeprom.h:
c:\winavr-20090313\bin\../lib/gcc/avr/4.3.2/include/stddef.h:
../servo2ppm_settings.h:

View File

@ -0,0 +1,17 @@
@echo *********************************
@echo Visit DIYdrones.com!
@echo This Bat is for PPM_encoder!
@echo *********************************
@echo Press enter to do some Magic!
pause
:A
@echo Programming Arduino...
"C:\Program Files\Atmel\AVR Tools\STK500\Stk500.exe" -cUSB -dATmega328P -fD9E2 -EFD -FD9E2 -GFD -e -ifap_ppm_encoder.hex -pf -lCF -LCF
@echo ****************************************************************
@echo Jordi: CHECK FOR PROBLEMS ABOVE before closing this window!
@echo Press enter to do the Magic again!
@echo ****************************************************************
pause
Goto A

View File

@ -0,0 +1,128 @@
/*********************************************************************************************************
Title : header file for the rc ppm encoder (servo2ppm_settings.h)
Author: Chris Efstathiou
E-mail: hendrix at vivodinet dot gr
Homepage: ........................
Date: 03/Aug/2009
Compiler: AVR-GCC with AVR-AS
MCU type: ATmega168
Comments: This software is FREE. Use it at your own risk.
*********************************************************************************************************/
#ifndef SERVO2PPM_SETTINGS_H
#define SERVO2PPM_SETTINGS_H
/********************************************************************************************************/
/* USER CONFIGURATION BLOCK START */
/********************************************************************************************************/
/*
The cpu frequency is defined in the makefile, the below definition is used only if the cpu frequency
is not defined in the makefile.
*/
#ifndef F_CPU
#define F_CPU 8000000UL /* CPU CLOCK FREQUENCY */
#endif
/*
Those values are the failsafe servo values and the values for the non used channels
If for example you leave unconnected channel 7, the servo pulse of channel 7 in the PPM train
will be the failsafe value set below as "RC_FAILSAFE_CHANNEL_7" thus 1000 microseconds.
*/
#define RC_FAILSAFE_CHANNEL_1 1500UL
#define RC_FAILSAFE_CHANNEL_2 1500UL
#define RC_FAILSAFE_CHANNEL_3 1000UL
#define RC_FAILSAFE_CHANNEL_4 1500UL
#define RC_FAILSAFE_CHANNEL_5 1000UL
#define RC_FAILSAFE_CHANNEL_6 1000UL
#define RC_FAILSAFE_CHANNEL_7 1000UL
#define RC_FAILSAFE_CHANNEL_8 1000UL
/*
When signal is lost 1= ppm waveform remain on with failsafe values, 0= ppm waveform is off
For use with Paparazzi use "0", the autopilot has it's own failsafe values when PPM signal is lost.
The above failsafe values will kick in only if the servo inputs are lost which cannot happen with
a receiver with dsp processing that provides "hold" or "failsafe" features.
If the receiver only provides "hold" on the last good servo signals received it is not suitable
for use with the Paparazzi autopilot as it will prohibit the autopilot entering the "AUTO2" or "HOME" mode.
If you use a receiver with failsafe ability then remember to set the failsafe value of the receiver
to 2000 microseconds for the "MODE" channel so the autopilot can go to "AUTO2" or "HOME" mode when the receiver
loose the tx signal. The servo signals on receivers like PCM, IPD and any receiver with servo hold AND failsafe
will not stop outputing servo pulses thus the encoder will never stop producing a PPM pulse train
except if the throttle channel is used as an indication by setting the "RC_LOST_CHANNEL" to a value above 0.
If you use the throttle channel as an indication that the TX signal is lost then:
RC_USE_FAILSAFE set to 0 means that the ppm output will be shut down and if you set
RC_USE_FAILSAFE to 1 the ppm output will NOT shut down but it will now output the failsafe values
defined above.
*/
#define RC_USE_FAILSAFE 1
/*
The channel number (1,2,3...7,8) that will be used as a receiver ready indicator.
If set above 0 then this channel should be always connected otherwise
the PPM output will not be enabled as the ppm encoder will wait for ever for this channel
to produce a valid servo pulse.
If 0 then the first connected channel going from channel 1 to 8 will be used, in other words
which ever connected channel comes on first it will indicate that the receiver is operational.
The detection of all connected channels is independent of this setting, this channel
is used as an indication that the receiver is up and running only.
Valid only if greater than 0.
*/
#define RC_RX_READY_CHANNEL 0 /* 0 = No channel will be exclusively checked. */
/*
The default value for the rc signal lost indicator channel and it's threshold value in microseconds .
If the value is above 1500 microseconds then when the signal lost indicator channel servo pulse exceeds
RC_LOST_THRESHOLD then the ppm output will be shut down.
If the value is below 1500 microseconds then when the signal lost indicator channel servo pulse gets lower than
RC_LOST_THRESHOLD then the ppm output will be shut down.
If the RC_USE_FAILSAFE is set to 1 then the ppm output will not stop producing pulses but now
the ppm wavetrain will contain the failsafe values defined in the beginning of this file.
Valid only if RC_LOST_CHANNEL > 0
*/
#define RC_LOST_CHANNEL 3 /* Defaul is the throttle channel. You can use any channel. */
#define RC_LOST_THRESHOLD 2025 /* Any value below 1300 or above 1700 microseconds. */
#define RC_PPM_GEN_CHANNELS 8 /* How many channels the PPM output frame will have. */
#define RC_PPM_OUTPUT_TYPE 0 /* 1 = POSITIVE PULSE, 0= NEGATIVE PULSE */
#define RC_MUX_CHANNEL 8 /*Jordi: Channel that will control the MUX */
#define RC_MUX_REVERSE 0 /*Jordi: Inverted the MUX output (NOT), 0 = normal, 1 = Rev*/
#define RC_MUX_MIN 0 /*Jordi: the min point */
#define RC_MUX_MAX 1250 /*Jordi: the max point */
/*
0 = the reset period is constant but the total PPM frame period is varying.
1 = the reset period is varying but the total PPM frame period is constant (always 23,5 ms for example).
*/
#define RC_CONSTANT_PPM_FRAME_TIME 0
/********************************************************************************************************/
/*
D A N G E R
The below settings are good for almost every situation and probably you don't need to change them.
Be carefull because you can cause a lot of problems if you change anything without knowing
exactly what you are doing.
*/
#define RC_SERVO_MIN_PW 800UL /* in microseconds */
#define RC_SERVO_CENTER_PW 1500UL /* in microseconds */
#define RC_SERVO_MAX_PW 2200UL /* in microseconds */
#define RC_PPM_CHANNEL_SYNC_PW 300UL /* the width of the PPM channel sync pulse in microseconds. */
#define RC_PPM_RESET_PW 0UL /* Min reset time in microseconds(ie. 7500UL), 0=AUTO */
#define RC_PPM_FRAME_LENGTH_MS 0UL /* Max PPM frame period in microseconds(ie. 23500UL), 0=AUTO */
#define RC_MAX_TIMEOUT 30000UL /* in microseconds, max ~65000 @ 8 mHZ, ~32000 @ 16 Mhz */
#define RC_MAX_BAD_PPM_FRAMES 4 /* Max consecutive bad servo pulse samples before failsafe */
#define RC_LED_FREQUENCY 5UL /* In Hertz, not accurate, min=1, max=you will get a warning */
#define RC_THROTTLE_CH_OFFSET_PW 25 /* in microseconds. */
/********************************************************************************************************/
/* USER CONFIGURATION BLOCK END */
/********************************************************************************************************/
#endif //#ifndef SERVO2PPM_SETTINGS_H

View File

@ -1,277 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include "Camera.h"
#include "../RC_Channel/RC_Channel.h"
void
Camera::move()
{
Vector3<float> target_vector(0,0,1); // x, y, z to target before rotating to planes axis, values are in meters
//decide what happens to camera depending on camera mode
switch(mode)
{
case 0:
//do nothing, i.e lock camera in place
return;
break;
case 1:
//stabilize
target_vector.x=0; //east to west gives +tive value (i.e. longitude)
target_vector.y=0; //south to north gives +tive value (i.e. latitude)
target_vector.z=100; //downwards is +tive
break;
case 2:
//track target
if(g_gps->fix)
{
target_vector=get_location_vector(&current_loc,&camera_target);
}
break;
case 3: // radio manual control
case 4: // test (level the camera and point north)
break; // see code 25 lines bellow
}
Matrix3f m = dcm.get_dcm_transposed();
Vector3<float> targ = m*target_vector; //to do: find out notion of x y convention
switch(gimbal_type)
{
case 0: // pitch & roll (tilt & roll)
cam_pitch = degrees(atan2(-targ.x, targ.z)); //pitch
cam_roll = degrees(atan2(targ.y, targ.z)); //roll
break;
case 1: // yaw & pitch (pan & tilt)
cam_pitch = atan2((sqrt(sq(targ.y) + sq(targ.x)) * .01113195), targ.z) * -1;
cam_yaw = 9000 + atan2(-targ.y, targ.x) * 5729.57795;
break;
/* case 2: // pitch, roll & yaw - not started
cam_ritch = 0;
cam_yoll = 0;
cam_paw = 0;
break; */
}
//some camera modes overwrite the gimbal_type calculations
switch(mode)
{
case 3: // radio manual control
if (rc_function[CAM_PITCH])
cam_pitch = map(rc_function[CAM_PITCH]->radio_in,
rc_function[CAM_PITCH]->radio_min,
rc_function[CAM_PITCH]->radio_max,
rc_function[CAM_PITCH]->angle_min,
rc_function[CAM_PITCH]->radio_max);
if (rc_function[CAM_ROLL])
cam_roll = map(rc_function[CAM_ROLL]->radio_in,
rc_function[CAM_ROLL]->radio_min,
rc_function[CAM_ROLL]->radio_max,
rc_function[CAM_ROLL]->angle_min,
rc_function[CAM_ROLL]->radio_max);
if (rc_function[CAM_YAW])
cam_yaw = map(rc_function[CAM_YAW]->radio_in,
rc_function[CAM_YAW]->radio_min,
rc_function[CAM_YAW]->radio_max,
rc_function[CAM_YAW]->angle_min,
rc_function[CAM_YAW]->radio_max);
break;
case 4: // test (level the camera and point north)
cam_pitch = -dcm.pitch_sensor;
cam_yaw = dcm.yaw_sensor; // do not invert because the servo is mounted upside-down on my system
// TODO: the "trunk" code can invert using parameters, but this branch still can't
cam_roll = -dcm.roll_sensor;
break;
}
#if CAM_DEBUG == ENABLED
//for debugging purposes
Serial.println();
Serial.print("current_loc: lat: ");
Serial.print(current_loc.lat);
Serial.print(", lng: ");
Serial.print(current_loc.lng);
Serial.print(", alt: ");
Serial.print(current_loc.alt);
Serial.println();
Serial.print("target_loc: lat: ");
Serial.print(camera_target.lat);
Serial.print(", lng: ");
Serial.print(camera_target.lng);
Serial.print(", alt: ");
Serial.print(camera_target.alt);
Serial.print(", distance: ");
Serial.print(get_distance(&current_loc,&camera_target));
Serial.print(", bearing: ");
Serial.print(get_bearing(&current_loc,&camera_target));
Serial.println();
Serial.print("dcm_angles: roll: ");
Serial.print(degrees(dcm.roll));
Serial.print(", pitch: ");
Serial.print(degrees(dcm.pitch));
Serial.print(", yaw: ");
Serial.print(degrees(dcm.yaw));
Serial.println();
Serial.print("target_vector: x: ");
Serial.print(target_vector.x,2);
Serial.print(", y: ");
Serial.print(target_vector.y,2);
Serial.print(", z: ");
Serial.print(target_vector.z,2);
Serial.println();
Serial.print("rotated_target_vector: x: ");
Serial.print(targ.x,2);
Serial.print(", y: ");
Serial.print(targ.y,2);
Serial.print(", z: ");
Serial.print(targ.z,2);
Serial.println();
Serial.print("gimbal type 0: roll: ");
Serial.print(roll);
Serial.print(", pitch: ");
Serial.print(pitch);
Serial.println();
/* Serial.print("gimbal type 1: pitch: ");
Serial.print(pan);
Serial.print(", roll: ");
Serial.print(tilt);
Serial.println(); */
/* Serial.print("gimbal type 2: pitch: ");
Serial.print(ritch);
Serial.print(", roll: ");
Serial.print(yoll);
Serial.print(", yaw: ");
Serial.print(paw);
Serial.println(); */
#endif
}
void
Camera::set_target(struct Location target)
{
camera_target = target;
}
void
Camera::update_camera_gimbal_type()
{
// Auto detect the camera gimbal type depending on the functions assigned to the servos
if ((rc_function[CAM_YAW] == NULL) && (rc_function[CAM_PITCH] != NULL) && (rc_function[CAM_ROLL] != NULL))
{
gimbal_type = 0;
}
if ((rc_function[CAM_YAW] != NULL) && (rc_function[CAM_PITCH] != NULL) && (rc_function[CAM_ROLL] == NULL))
{
gimbal_type = 1;
}
if ((rc_function[CAM_YAW] != NULL) && (rc_function[CAM_PITCH] != NULL) && (rc_function[CAM_ROLL] != NULL))
{
gimbal_type = 2;
}
}
void
Camera::servo_pic() // Servo operated camera
{
if (rc_function[CAM_TRIGGER])
{
cam_trigger = rc_function[CAM_TRIGGER]->radio_max;
keep_cam_trigg_active_cycles = 2; // leave a message that it should be active for two event loop cycles
}
}
void
Camera::relay_pic() // basic relay activation
{
relay_on();
keep_cam_trigg_active_cycles = 2; // leave a message that it should be active for two event loop cycles
}
void
Camera::throttle_pic() // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
{
g.channel_throttle.radio_out = g.throttle_min;
if (thr_pic == 10){
servo_pic(); // triggering method
thr_pic = 0;
g.channel_throttle.radio_out = g.throttle_cruise;
}
thr_pic++;
}
void
Camera::distance_pic() // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
{
g.channel_throttle.radio_out = g.throttle_min;
if (wp_distance < 3){
servo_pic(); // triggering method
g.channel_throttle.radio_out = g.throttle_cruise;
}
}
void
Camera::NPN_pic() // hacked the circuit to run a transistor? use this trigger to send output.
{
// To Do: Assign pin spare pin for output
digitalWrite(camtrig, HIGH);
keep_cam_trigg_active_cycles = 1; // leave a message that it should be active for two event loop cycles
}
// single entry point to take pictures
void
Camera::trigger_pic()
{
switch (trigger_type)
{
case 0:
servo_pic(); // Servo operated camera
break;
case 1:
relay_pic(); // basic relay activation
break;
case 2:
throttle_pic(); // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
break;
case 3:
distance_pic(); // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
break;
case 4:
NPN_pic(); // hacked the circuit to run a transistor? use this trigger to send output.
break;
}
}
// de-activate the trigger after some delay, but without using a delay() function
void
Camera::trigger_pic_cleanup()
{
if (keep_cam_trigg_active_cycles)
{
keep_cam_trigg_active_cycles --;
}
else
{
switch (trigger_type)
{
case 0:
case 2:
case 3:
if (rc_function[CAM_TRIGGER])
{
cam_trigger = rc_function[CAM_TRIGGER]->radio_min;
}
break;
case 1:
relay_off();
break;
case 4:
digitalWrite(camtrig, LOW);
break;
}
}
}

View File

@ -1,71 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/// @file Camera.h
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
#ifndef CAMERA_H
#define CAMERA_H
#include <AP_Common.h>
/// @class Camera
/// @brief Object managing a Photo or video camera
class Camera{
protected:
AP_Var_group _group; // must be before all vars to keep ctor init order correct
public:
/// Constructor
///
/// @param key EEPROM storage key for the camera configuration parameters.
/// @param name Optional name for the group.
///
Camera(AP_Var::Key key, const prog_char_t *name) :
_group(key, name),
mode (&_group, 0, 0, name ? PSTR("MODE") : 0), // suppress name if group has no name
trigger_type(&_group, 1, 0, name ? PSTR("TRIGGER_MODE") : 0),
picture_time (0), // waypoint trigger variable
thr_pic (0), // timer variable for throttle_pic
camtrig (83), // PK6 chosen as it not near anything so safer for soldering
// camera_target (home), // use test target for now
gimbal_type (1),
keep_cam_trigg_active_cycles (0)
{}
// move the camera depending on the camera mode
void move();
// single entry point to take pictures
void trigger_pic();
// de-activate the trigger after some delay, but without using a delay() function
void trigger_pic_cleanup();
// call this from time to time to make sure the correct gimbal type gets choosen
void update_camera_gimbal_type();
// set camera orientation target
void set_target(struct Location target);
int picture_time; // waypoint trigger variable
private:
uint8_t keep_cam_trigg_active_cycles; // event loop cycles to keep trigger active
struct Location camera_target; // point of interest for the camera to track
// struct Location GPS_mark; // GPS POI for position based triggering
int thr_pic; // timer variable for throttle_pic
int camtrig; // PK6 chosen as it not near anything so safer for soldering
AP_Int8 mode; // 0=do nothing, 1=stabilize, 2=track target, 3=manual, 4=simple stabilize test
AP_Int8 trigger_type; // 0=Servo, 1=relay, 2=throttle_off time, 3=throttle_off waypoint 4=transistor
uint8_t gimbal_type; // 0=pitch & roll (tilt & roll), 1=yaw & pitch(pan & tilt), 2=pitch, roll & yaw (to be added)
void servo_pic(); // Servo operated camera
void relay_pic(); // basic relay activation
void throttle_pic(); // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
void distance_pic(); // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
void NPN_pic(); // hacked the circuit to run a transistor? use this trigger to send output.
};
#endif /* CAMERA_H */

View File

@ -1,184 +0,0 @@
#include "AP_Mount.h"
AP_Mount::AP_Mount(GPS *gps, AP_DCM *dcm, AP_Var::Key key, const prog_char_t *name):
_group(key, name),
_mountMode(&_group, 0, 0, name ? PSTR("MODE") : 0), // suppress name if group has no name
_mountType(&_group, 0, 0, name ? PSTR("TYPE") : 0),
_dcm(dcm);
_gps(gps);
{
}
void AP_Mount::SetPitchYaw(Location targetGPSLocation)
{
_targetGPSLocation=targetGPSLocation;
//set mode
_mountMode=gps;
//update mount position
UpDateMount();
}
void AP_Mount::SetGPSTarget(Location targetGPSLocation)
{
_targetGPSLocation=targetGPSLocation;
//set mode
_mountMode=gps;
//update mount position
UpDateMount();
}
void AP_Mount::SetAssisted(int roll, int pitch, int yaw)
{
_AssistAngles.x = roll;
_AssistAngles.y = pitch;
_AssistAngles.z = yaw;
//set mode
_mountMode=assisted;
//update mount position
UpDateMount();
}
//sets the servo angles for FPV, note angles are * 100
void AP_Mount::SetMountFreeRoam(int roll, int pitch, int yaw)
{
_RoamAngles.x=roll;
_RoamAngles.y=pitch;
_RoamAngles.z=yaw;
//set mode
_mountMode=roam;
//now update mount position
UpDateMount();
}
//sets the servo angles for landing, note angles are * 100
void AP_Mount::SetMountLanding(int roll, int pitch, int yaw)
{
_LandingAngles.x=roll;
_LandingAngles.y=pitch;
_LandingAngles.z=yaw;
//set mode
_mountMode=landing;
//now update mount position
UpDateMount();
}
void AP_Mount::SetNone()
{
//set mode
_mountMode=none;
//now update mount position
UpDateMount();
}
void AP_Mount::UpDateMount()
{
switch(_mountMode)
{
case gps:
{
if(_gps->fix)
{
CalcGPSTargetVector(&_targetGPSLocation);
}
m = _dcm->get_dcm_transposed();
targ = m*_GPSVector;
this->CalcMountAnglesFromVector(*targ)
break;
}
case stabilise:
{
//to do
break;
}
case roam:
{
pitchAngle=100*_RoamAngles.y;
rollAngle=100*_RoamAngles.x;
yawAngle=100*_RoamAngles.z;
break;
}
case assisted:
{
m = _dcm->get_dcm_transposed();
targ = m*_AssistVector;
this->CalcMountAnglesFromVector(*targ)
break;
}
case landing:
{
pitchAngle=100*_RoamAngles.y;
rollAngle=100*_RoamAngles.x;
yawAngle=100*_RoamAngles.z;
break;
}
case none:
{
//do nothing
break;
}
default:
{
//do nothing
break;
}
}
}
void AP_Mount::SetMode(MountMode mode)
{
_mountMode=mode;
}
void AP_Mount::CalcGPSTargetVector(struct Location *target)
{
_targetVector.x = (target->lng-_gps->longitude) * cos((_gps->latitude+target->lat)/2)*.01113195;
_targetVector.y = (target->lat-_gps->latitude)*.01113195;
_targetVector.z = (_gps->altitude-target->alt);
}
void AP_Mount::CalcMountAnglesFromVector(Vector3f *targ)
{
switch(_mountType)
{
case pitch_yaw:
{
//need to tidy up maths for below
pitchAngle = atan2((sqrt(sq(targ.y) + sq(targ.x)) * .01113195), targ.z) * -1;
yawAngle = 9000 + atan2(-targ.y, targ.x) * 5729.57795;
break;
}
case pitch_roll:
{
pitchAngle = degrees(atan2(-targ.x,targ.z))*100; //pitch
rollAngle = degrees(atan2(targ.y,targ.z))*100; //roll
break;
}
case pitch_roll_yaw:
{
//to do
break;
}
case none:
{
//do nothing
break;
}
default:
{
//do nothing
break;
}
}
}

View File

@ -1,99 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/************************************************************
* AP_mount -- library to control a 2 or 3 axis mount. *
* *
* Author: Joe Holdsworth; *
* Ritchie Wilson; *
* Amiclair Lucus; *
* *
* Purpose: Move a 2 or 3 axis mount attached to vehicle, *
* Used for mount to track targets or stabilise *
* camera plus other modes. *
* *
* Usage: Use in main code to control mounts attached to *
* vehicle. *
* 1. initialise class *
* 2. setMounttype * *
* *
*Comments: All angles in degrees * 100, distances in meters*
* unless otherwise stated. *
************************************************************/
#ifndef AP_Mount_H
#define AP_Mount_H
#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_GPS.h>
#include <AP_DCM.h>
class AP_Mount
{
protected:
AP_Var_group _group; // must be before all vars to keep ctor init order correct
public:
//Constructors
AP_Mount(GPS *gps, AP_DCM *dcm, AP_Var::Key key, const prog_char_t *name);
//enums
enum MountMode{
gps = 0,
stabilise = 1, //note the correct english spelling :)
roam = 2,
assisted = 3,
landing = 4,
none = 5
};
enum MountType{
pitch_yaw = 0,
pitch_roll = 1,
pitch_roll_yaw = 2,
none = 3;
};
//Accessors
//void SetPitchYaw(int pitchCh, int yawCh);
//void SetPitchRoll(int pitchCh, int rollCh);
//void SetPitchRollYaw(int pitchCh, int rollCh, int yawCh);
void SetGPSTarget(Location targetGPSLocation); //used to tell the mount to track GPS location
void SetAssisted(int roll, int pitch, int yaw);
void SetMountFreeRoam(int roll, int pitch, int yaw);//used in the FPV for example,
void SetMountLanding(int roll, int pitch, int yaw); //set mount landing position
void SetNone();
//methods
void UpDateMount();
void SetMode(MountMode mode);
int pitchAngle; //degrees*100
int rollAngle; //degrees*100
int yawAngle; //degrees*100
private:
//methods
void CalcGPSTargetVector(struct Location *target);
void CalcMountAnglesFromVector(Vector3f *targ);
//void CalculateDCM(int roll, int pitch, int yaw);
//members
AP_DCM *_dcm;
GPS *_gps;
MountMode _mountMode;
MountType _mountType;
struct Location _targetGPSLocation;
Vector3f _GPSVector; //target vector calculated stored in meters
Vector3i _RoamAngles; //used for roam mode vector.x = roll vector.y = pitch, vector.z=yaw
Vector3i _LandingAngles; //landing position for mount, vector.x = roll vector.y = pitch, vector.z=yaw
Vector3i _AssistAngles; //used to keep angles that user has supplied from assisted targetting
Vector3f _AssistVector; //used to keep vector calculated from _AssistAngles
Matrix3f _m; //holds 3 x 3 matrix, var is used as temp in calcs
Vector3f _targ; //holds target vector, var is used as temp in calcs
};
#endif

View File

@ -1,9 +0,0 @@
AP_Mount KEYWORD1
SetGPSTarget KEYWORD2
SetAssisted KEYWORD2
SetAntenna KEYWORD2
SetMountFPV KEYWORD2
SetMountLanding KEYWORD2
UpDateMount KEYWORD2
SetMode KEYWORD2