mirror of https://github.com/ArduPilot/ardupilot
firmware build
This commit is contained in:
parent
fa0711f9ba
commit
6cffcbe7c9
|
@ -3,11 +3,13 @@
|
||||||
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
|
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: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
|
/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
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
|
||||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
|
||||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
|
||||||
%% libraries/APM_BMP085/APM_BMP085.o
|
%% libraries/APM_BMP085/APM_BMP085.o
|
||||||
|
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||||
%% libraries/APM_RC/APM_RC.o
|
%% libraries/APM_RC/APM_RC.o
|
||||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||||
%% libraries/AP_ADC/AP_ADC.o
|
%% libraries/AP_ADC/AP_ADC.o
|
||||||
|
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
|
||||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||||
%% libraries/AP_GPS/GPS.o
|
%% libraries/AP_GPS/GPS.o
|
||||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||||
|
%% libraries/AP_Mount/AP_Mount.o
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||||
|
%% libraries/AP_Relay/AP_Relay.o
|
||||||
%% libraries/DataFlash/DataFlash.o
|
%% libraries/DataFlash/DataFlash.o
|
||||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
|
||||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
/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
|
/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/BetterStream.o
|
||||||
|
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
||||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||||
%% libraries/ModeFilter/ModeFilter.o
|
%% libraries/ModeFilter/ModeFilter.o
|
||||||
%% libraries/PID/PID.o
|
%% libraries/PID/PID.o
|
||||||
|
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||||
%% libraries/RC_Channel/RC_Channel.o
|
%% libraries/RC_Channel/RC_Channel.o
|
||||||
%% libraries/memcheck/memcheck.o
|
%% libraries/memcheck/memcheck.o
|
||||||
%% libraries/FastSerial/ftoa_engine.o
|
%% libraries/FastSerial/ftoa_engine.o
|
||||||
|
|
|
@ -3,20 +3,21 @@
|
||||||
00000001 b home_is_set
|
00000001 b home_is_set
|
||||||
00000001 b ch3_failsafe
|
00000001 b ch3_failsafe
|
||||||
00000001 b land_complete
|
00000001 b land_complete
|
||||||
00000001 b command_may_ID
|
00000001 b mavlink_active
|
||||||
00000001 b command_must_ID
|
00000001 b nav_command_ID
|
||||||
00000001 b failsafeCounter
|
00000001 b failsafeCounter
|
||||||
00000001 b counter_one_herz
|
00000001 b counter_one_herz
|
||||||
00000001 b in_mavlink_delay
|
00000001 b in_mavlink_delay
|
||||||
00000001 b slow_loopCounter
|
00000001 b slow_loopCounter
|
||||||
00000001 d takeoff_complete
|
00000001 d takeoff_complete
|
||||||
00000001 b command_may_index
|
00000001 b nav_command_index
|
||||||
00000001 b command_must_index
|
|
||||||
00000001 b delta_ms_fast_loop
|
00000001 b delta_ms_fast_loop
|
||||||
00000001 d ground_start_count
|
00000001 d ground_start_count
|
||||||
00000001 b medium_loopCounter
|
00000001 b medium_loopCounter
|
||||||
|
00000001 b non_nav_command_ID
|
||||||
00000001 b rc_override_active
|
00000001 b rc_override_active
|
||||||
00000001 b delta_ms_medium_loop
|
00000001 b delta_ms_medium_loop
|
||||||
|
00000001 b non_nav_command_index
|
||||||
00000001 b superslow_loopCounter
|
00000001 b superslow_loopCounter
|
||||||
00000001 b event_id
|
00000001 b event_id
|
||||||
00000001 b GPS_light
|
00000001 b GPS_light
|
||||||
|
@ -25,12 +26,10 @@
|
||||||
00000001 D control_mode
|
00000001 D control_mode
|
||||||
00000001 B hindex
|
00000001 B hindex
|
||||||
00000001 B inverted_flight
|
00000001 B inverted_flight
|
||||||
00000001 B mavdelay
|
|
||||||
00000001 B n
|
00000001 B n
|
||||||
00000001 B oldSwitchPosition
|
00000001 B oldSwitchPosition
|
||||||
|
00000001 B relay
|
||||||
00000002 T ReadSCP1000()
|
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 loiter_sum
|
||||||
00000002 b event_delay
|
00000002 b event_delay
|
||||||
00000002 b event_value
|
00000002 b event_value
|
||||||
|
@ -50,7 +49,6 @@
|
||||||
00000002 b event_undo_value
|
00000002 b event_undo_value
|
||||||
00000002 b ground_start_avg
|
00000002 b ground_start_avg
|
||||||
00000002 b airspeed_pressure
|
00000002 b airspeed_pressure
|
||||||
00000002 b adc
|
|
||||||
00000002 r comma
|
00000002 r comma
|
||||||
00000002 b g_gps
|
00000002 b g_gps
|
||||||
00000002 b pmTest1
|
00000002 b pmTest1
|
||||||
|
@ -60,7 +58,6 @@
|
||||||
00000002 d ch2_temp
|
00000002 d ch2_temp
|
||||||
00000002 b failsafe
|
00000002 b failsafe
|
||||||
00000002 b sonar_alt
|
00000002 b sonar_alt
|
||||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
|
||||||
00000002 r print_divider()::__c
|
00000002 r print_divider()::__c
|
||||||
00000002 d throttle_slew_limit()::last
|
00000002 d throttle_slew_limit()::last
|
||||||
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -72,6 +69,7 @@
|
||||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
00000003 r print_log_menu()::__c
|
00000003 r print_log_menu()::__c
|
||||||
00000003 r report_compass()::__c
|
00000003 r report_compass()::__c
|
||||||
|
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
00000004 b event_timer
|
00000004 b event_timer
|
||||||
00000004 d hold_course
|
00000004 d hold_course
|
||||||
00000004 b loiter_time
|
00000004 b loiter_time
|
||||||
|
@ -82,6 +80,7 @@
|
||||||
00000004 b airspeed_raw
|
00000004 b airspeed_raw
|
||||||
00000004 b current_amps
|
00000004 b current_amps
|
||||||
00000004 b energy_error
|
00000004 b energy_error
|
||||||
|
00000004 b airspeed_fbwB
|
||||||
00000004 b bearing_error
|
00000004 b bearing_error
|
||||||
00000004 b current_total
|
00000004 b current_total
|
||||||
00000004 b nav_loopTimer
|
00000004 b nav_loopTimer
|
||||||
|
@ -123,8 +122,6 @@
|
||||||
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_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 b mavlink_delay(unsigned long)::last_50hz
|
||||||
00000004 r print_enabled(bool)::__c
|
00000004 r print_enabled(bool)::__c
|
||||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -214,14 +211,14 @@
|
||||||
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
|
||||||
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
|
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
|
0000000a r init_home()::__c
|
||||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
|
0000000a r verify_nav_wp()::__c
|
||||||
0000000a r report_compass()::__c
|
0000000a r report_compass()::__c
|
||||||
0000000a r report_throttle()::__c
|
0000000a r report_throttle()::__c
|
||||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -232,31 +229,30 @@
|
||||||
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 RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a V Parameters::Parameters()::__c
|
0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a T setup
|
0000000a T setup
|
||||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
0000000b r report_gains()::__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 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
|
||||||
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 process_logs(unsigned char, Menu::arg const*)
|
||||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||||
0000000c V vtable for IMU
|
0000000c V vtable for IMU
|
||||||
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
||||||
0000000c r report_xtrack()::__c
|
0000000c r report_xtrack()::__c
|
||||||
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__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 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
|
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
|
||||||
|
0000000c V Parameters::Parameters()::__c
|
||||||
0000000d r init_home()::__c
|
0000000d r init_home()::__c
|
||||||
0000000d r verify_RTL()::__c
|
0000000d r verify_RTL()::__c
|
||||||
0000000d r demo_servos(unsigned char)::__c
|
0000000d r demo_servos(unsigned char)::__c
|
||||||
|
@ -267,6 +263,9 @@
|
||||||
0000000d r print_log_menu()::__c
|
0000000d r print_log_menu()::__c
|
||||||
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
||||||
0000000d r Log_Read_Startup()::__c
|
0000000d r Log_Read_Startup()::__c
|
||||||
|
0000000d r control_failsafe(unsigned int)::__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
|
||||||
|
@ -287,6 +286,7 @@
|
||||||
0000000d B sonar_mode_filter
|
0000000d B sonar_mode_filter
|
||||||
0000000e t global destructors keyed to Serial
|
0000000e t global destructors keyed to Serial
|
||||||
0000000e t global constructors keyed to Serial
|
0000000e t global constructors keyed to Serial
|
||||||
|
0000000e t send_statustext(mavlink_channel_t)
|
||||||
0000000e V vtable for AP_Float16
|
0000000e V vtable for AP_Float16
|
||||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||||
|
@ -296,10 +296,10 @@
|
||||||
0000000e V vtable for AP_VarT<int>
|
0000000e V vtable for AP_VarT<int>
|
||||||
0000000e V vtable for AP_VarT<long>
|
0000000e V vtable for AP_VarT<long>
|
||||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
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 select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_gains()::__c
|
0000000e r report_gains()::__c
|
||||||
0000000e r print_log_menu()::__c
|
0000000e r print_log_menu()::__c
|
||||||
|
0000000e r control_failsafe(unsigned int)::__c
|
||||||
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_batt_monitor()::__c
|
0000000e r report_batt_monitor()::__c
|
||||||
0000000e r report_flight_modes()::__c
|
0000000e r report_flight_modes()::__c
|
||||||
|
@ -325,23 +325,26 @@
|
||||||
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 current_loc
|
||||||
0000000f b next_command
|
0000000f b next_nav_command
|
||||||
|
0000000f b next_nonnav_command
|
||||||
0000000f b home
|
0000000f b home
|
||||||
0000000f b next_WP
|
0000000f b next_WP
|
||||||
0000000f b prev_WP
|
0000000f b prev_WP
|
||||||
0000000f b guided_WP
|
0000000f b guided_WP
|
||||||
0000000f r report_gains()::__c
|
0000000f r report_gains()::__c
|
||||||
0000000f r print_log_menu()::__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 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 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 Parameters::Parameters()::__c
|
||||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||||
00000010 b rc_override
|
00000010 b rc_override
|
||||||
00000010 r planner_menu_commands
|
00000010 r planner_menu_commands
|
||||||
|
00000010 r __menu_name__main_menu
|
||||||
|
00000010 T GCS_MAVLINK::send_message(ap_message)
|
||||||
00000010 W AP_VarT<float>::cast_to_float() const
|
00000010 W AP_VarT<float>::cast_to_float() const
|
||||||
00000010 W AP_VarT<long>::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 setup_radio(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -349,17 +352,17 @@
|
||||||
00000010 r Log_Read_Startup()::__c
|
00000010 r Log_Read_Startup()::__c
|
||||||
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000010 r dump_log(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 erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r set_next_WP(Location*)::__c
|
|
||||||
00000011 r zero_eeprom()::__c
|
00000011 r zero_eeprom()::__c
|
||||||
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r startup_ground()::__c
|
00000011 r startup_ground()::__c
|
||||||
00000011 r Log_Read_Attitude()::__c
|
00000011 r Log_Read_Attitude()::__c
|
||||||
00000011 r load_next_command_from_EEPROM()::__c
|
00000011 r process_next_command()::__c
|
||||||
|
00000011 r failsafe_short_on_event()::__c
|
||||||
00000012 B Serial
|
00000012 B Serial
|
||||||
00000012 B Serial1
|
00000012 B Serial1
|
||||||
00000012 B Serial3
|
00000012 B Serial3
|
||||||
|
00000012 t gcs_update()
|
||||||
00000012 W AP_Float16::~AP_Float16()
|
00000012 W AP_Float16::~AP_Float16()
|
||||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
|
@ -372,6 +375,7 @@
|
||||||
00000012 r print_done()::__c
|
00000012 r print_done()::__c
|
||||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000012 r init_barometer()::__c
|
00000012 r init_barometer()::__c
|
||||||
|
00000012 r handle_no_commands()::__c
|
||||||
00000012 r startup_IMU_ground()::__c
|
00000012 r startup_IMU_ground()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
|
@ -391,11 +395,11 @@
|
||||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||||
00000014 W AP_VarT<int>::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_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000014 r test_imu(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 map_baudrate(signed char, unsigned long)::__c
|
||||||
00000015 r report_gains()::__c
|
00000015 r report_gains()::__c
|
||||||
|
00000015 r verify_nav_wp()::__c
|
||||||
00000015 r init_ardupilot()::__c
|
00000015 r init_ardupilot()::__c
|
||||||
00000015 r print_hit_enter()::__c
|
00000015 r print_hit_enter()::__c
|
||||||
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -403,20 +407,18 @@
|
||||||
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r report_batt_monitor()::__c
|
00000016 r report_batt_monitor()::__c
|
||||||
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r GCS_MAVLINK::update()::__c
|
|
||||||
00000016 B sonar
|
00000016 B sonar
|
||||||
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000017 r test_pressure(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
|
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
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 report_compass()::__c
|
||||||
00000018 r Log_Read_Startup()::__c
|
00000018 r Log_Read_Startup()::__c
|
||||||
00000019 r report_batt_monitor()::__c
|
00000019 r report_batt_monitor()::__c
|
||||||
00000019 r failsafe_long_on_event()::__c
|
00000019 r failsafe_long_on_event()::__c
|
||||||
00000019 r GCS_MAVLINK::update()::__c
|
00000019 r handle_process_nav_cmd()::__c
|
||||||
0000001a r reset_control_switch()::__c
|
00000019 r handle_process_do_command()::__c
|
||||||
|
00000019 r handle_process_condition_command()::__c
|
||||||
0000001a r failsafe_short_on_event()::__c
|
0000001a r failsafe_short_on_event()::__c
|
||||||
0000001a r Log_Read(int, int)::__c
|
0000001a r Log_Read(int, int)::__c
|
||||||
0000001b r failsafe_short_off_event()::__c
|
0000001b r failsafe_short_off_event()::__c
|
||||||
|
@ -434,20 +436,23 @@
|
||||||
0000001d r startup_ground()::__c
|
0000001d r startup_ground()::__c
|
||||||
0000001d r report_batt_monitor()::__c
|
0000001d r report_batt_monitor()::__c
|
||||||
0000001e r flight_mode_strings
|
0000001e r flight_mode_strings
|
||||||
0000001e t failsafe_short_off_event()
|
|
||||||
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
0000001e r startup_ground()::__c
|
0000001e r startup_ground()::__c
|
||||||
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
0000001f r init_ardupilot()::__c
|
0000001f r init_ardupilot()::__c
|
||||||
|
0000001f r Log_Read(int, int)::__c
|
||||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000020 t gcs_send_message(ap_message)
|
||||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||||
00000020 r report_xtrack()::__c
|
00000020 r report_xtrack()::__c
|
||||||
00000020 r init_barometer()::__c
|
00000020 r init_barometer()::__c
|
||||||
00000020 r Log_Read(int, int)::__c
|
|
||||||
00000020 t byte_swap_4
|
00000020 t byte_swap_4
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
|
00000021 r verify_loiter_time()::__c
|
||||||
|
00000021 r process_next_command()::__c
|
||||||
00000022 t print_blanks(int)
|
00000022 t print_blanks(int)
|
||||||
|
00000022 t failsafe_short_off_event()
|
||||||
00000022 t reset_I()
|
00000022 t reset_I()
|
||||||
00000022 W AP_Float16::~AP_Float16()
|
00000022 W AP_Float16::~AP_Float16()
|
||||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
|
@ -459,23 +464,22 @@
|
||||||
00000022 W AP_VarT<long>::~AP_VarT()
|
00000022 W AP_VarT<long>::~AP_VarT()
|
||||||
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000022 r report_compass()::__c
|
00000022 r report_compass()::__c
|
||||||
00000022 r increment_WP_index()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000022 r verify_loiter_time()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
||||||
00000023 r print_gyro_offsets()::__c
|
00000023 r print_gyro_offsets()::__c
|
||||||
|
00000023 r verify_loiter_turns()::__c
|
||||||
00000023 r navigate()::__c
|
00000023 r navigate()::__c
|
||||||
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
00000024 r print_accel_offsets()::__c
|
00000024 r print_accel_offsets()::__c
|
||||||
00000024 r verify_loiter_turns()::__c
|
|
||||||
00000026 t print_done()
|
00000026 t print_done()
|
||||||
00000026 b mavlink_queue
|
|
||||||
00000026 t print_hit_enter()
|
00000026 t print_hit_enter()
|
||||||
00000026 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
|
00000026 r init_ardupilot()::__c
|
||||||
00000026 r print_PID(PID*)::__c
|
00000026 r print_PID(PID*)::__c
|
||||||
00000027 r init_ardupilot()::__c
|
00000027 r change_command(unsigned char)::__c
|
||||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
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 t help_log(unsigned char, Menu::arg const*)
|
||||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||||
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
||||||
|
@ -485,71 +489,75 @@
|
||||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||||
0000002a r init_ardupilot()::__c
|
0000002a r init_ardupilot()::__c
|
||||||
0000002a r startup_ground()::__c
|
0000002a r startup_ground()::__c
|
||||||
0000002b r verify_must()::__c
|
0000002a r verify_nav_command()::__c
|
||||||
|
0000002a t _mav_put_int8_t_array
|
||||||
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
||||||
0000002b r change_command(unsigned char)::__c
|
0000002b r change_command(unsigned char)::__c
|
||||||
0000002c t freeRAM()
|
|
||||||
0000002d r startup_IMU_ground()::__c
|
0000002d r startup_IMU_ground()::__c
|
||||||
0000002e t reset_control_switch()
|
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
|
||||||
0000002e t send_rate(unsigned int, unsigned int)
|
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
|
||||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
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 setup_mode(unsigned char, Menu::arg const*)
|
||||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||||
|
00000030 t send_heartbeat(mavlink_channel_t)
|
||||||
00000030 t test_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
|
00000030 r print_log_menu()::__c
|
||||||
00000031 r start_new_log(unsigned char)::__c
|
00000031 r start_new_log(unsigned char)::__c
|
||||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||||
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000033 b pending_status
|
||||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||||
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
||||||
00000034 t _mav_put_int8_t_array
|
00000034 t mavlink_msg_statustext_send
|
||||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||||
00000035 r Log_Read_Nav_Tuning()::__c
|
00000035 r Log_Read_Nav_Tuning()::__c
|
||||||
|
00000035 r verify_condition_command()::__c
|
||||||
00000036 t report_radio()
|
00000036 t report_radio()
|
||||||
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000038 t send_current_waypoint(mavlink_channel_t)
|
||||||
|
00000038 b barometer
|
||||||
00000038 r test_dipswitches(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
|
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r setup_radio(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 planner_mode(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r init_ardupilot()::__c
|
00000039 r init_ardupilot()::__c
|
||||||
0000003a t report_imu()
|
0000003a t report_imu()
|
||||||
|
0000003a t verify_loiter_turns()
|
||||||
0000003a W PID::~PID()
|
0000003a W PID::~PID()
|
||||||
|
0000003c t verify_RTL()
|
||||||
0000003c t Log_Write_Mode(unsigned char)
|
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_wp_print(Location*, unsigned char)::__c
|
||||||
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
0000003d B g_gps_driver
|
0000003d B g_gps_driver
|
||||||
0000003e t verify_RTL()
|
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
|
||||||
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)
|
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
00000040 b adc
|
||||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||||
00000040 t byte_swap_8
|
00000040 t byte_swap_8
|
||||||
00000040 t crc_accumulate
|
|
||||||
00000040 B history
|
00000040 B history
|
||||||
00000043 r Log_Read_GPS()::__c
|
00000043 r Log_Read_GPS()::__c
|
||||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||||
00000044 r report_throttle()::__c
|
00000044 r report_throttle()::__c
|
||||||
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000046 W RC_Channel::~RC_Channel()
|
||||||
|
00000048 t failsafe_long_on_event()
|
||||||
|
0000004a t send_meminfo(mavlink_channel_t)
|
||||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, 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)
|
||||||
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
||||||
0000004c t Log_Read_Mode()
|
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*)
|
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||||
|
00000050 b mavlink_queue
|
||||||
00000050 r log_menu_commands
|
00000050 r log_menu_commands
|
||||||
00000050 r main_menu_commands
|
00000050 r main_menu_commands
|
||||||
00000050 t failsafe_long_on_event()
|
|
||||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||||
|
00000050 B imu
|
||||||
00000054 t print_divider()
|
00000054 t print_divider()
|
||||||
00000054 t print_enabled(bool)
|
00000054 t print_enabled(bool)
|
||||||
00000054 t report_flight_modes()
|
00000054 t report_flight_modes()
|
||||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||||
00000056 t change_command(unsigned char)
|
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||||
00000058 t radio_input_switch()
|
00000058 t radio_input_switch()
|
||||||
0000005a t update_GPS_light()
|
0000005a t update_GPS_light()
|
||||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
@ -557,143 +565,157 @@
|
||||||
0000005c t readSwitch()
|
0000005c t readSwitch()
|
||||||
0000005c t get_num_logs()
|
0000005c t get_num_logs()
|
||||||
0000005e T GCS_MAVLINK::_count_parameters()
|
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 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)
|
00000062 t print_switch(unsigned char, unsigned char)
|
||||||
00000064 t Log_Write_Attitude(int, int, unsigned int)
|
00000064 t Log_Write_Attitude(int, int, unsigned int)
|
||||||
|
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
|
||||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||||
00000064 t mavlink_msg_param_value_send
|
00000064 W RC_Channel_aux::~RC_Channel_aux()
|
||||||
00000068 t zero_eeprom()
|
00000068 t zero_eeprom()
|
||||||
00000068 t find_last_log_page(int)
|
00000068 t find_last_log_page(int)
|
||||||
|
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
|
||||||
|
0000006a t demo_servos(unsigned char)
|
||||||
|
0000006a t startup_IMU_ground()
|
||||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||||
0000006c t setup_show(unsigned char, Menu::arg const*)
|
0000006c t setup_show(unsigned char, Menu::arg const*)
|
||||||
0000006c t demo_servos(unsigned char)
|
|
||||||
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
||||||
00000070 r init_ardupilot()::__c
|
00000070 r init_ardupilot()::__c
|
||||||
00000074 t verify_loiter_time()
|
00000072 t verify_loiter_time()
|
||||||
00000076 t startup_IMU_ground()
|
00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
|
||||||
00000078 t read_control_switch()
|
00000078 t read_control_switch()
|
||||||
0000007c t failsafe_short_on_event()
|
0000007c t send_gps_status(mavlink_channel_t)
|
||||||
|
0000007c t do_RTL()
|
||||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||||
00000080 r setup_menu_commands
|
00000080 r setup_menu_commands
|
||||||
00000080 T __vector_25
|
00000080 T __vector_25
|
||||||
00000080 T __vector_36
|
00000080 T __vector_36
|
||||||
00000080 T __vector_54
|
00000080 T __vector_54
|
||||||
|
00000084 t change_command(unsigned char)
|
||||||
00000086 t Log_Read_Attitude()
|
00000086 t Log_Read_Attitude()
|
||||||
00000088 t Log_Read_Raw()
|
00000088 t Log_Read_Raw()
|
||||||
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
||||||
0000008c t print_gyro_offsets()
|
0000008c t print_gyro_offsets()
|
||||||
0000008c t print_accel_offsets()
|
0000008c t print_accel_offsets()
|
||||||
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||||
00000090 t do_RTL()
|
0000008e t handle_no_commands()
|
||||||
|
0000008e t failsafe_short_on_event()
|
||||||
|
00000092 T GCS_MAVLINK::queued_param_send()
|
||||||
00000096 t map_baudrate(signed char, unsigned long)
|
00000096 t map_baudrate(signed char, unsigned long)
|
||||||
00000096 t test_wp_print(Location*, unsigned char)
|
00000096 t test_wp_print(Location*, unsigned char)
|
||||||
0000009c t update_servo_switches()
|
0000009c t update_servo_switches()
|
||||||
0000009c t print_PID(PID*)
|
0000009c t print_PID(PID*)
|
||||||
0000009d B gcs
|
0000009c B gcs0
|
||||||
0000009d B hil
|
0000009c B gcs3
|
||||||
000000a0 t report_xtrack()
|
000000a0 t report_xtrack()
|
||||||
|
000000a2 t verify_nav_wp()
|
||||||
000000a4 t Log_Read_Cmd()
|
000000a4 t Log_Read_Cmd()
|
||||||
000000a4 T __vector_26
|
000000a4 T __vector_26
|
||||||
000000a4 T __vector_37
|
000000a4 T __vector_37
|
||||||
000000a4 T __vector_55
|
000000a4 T __vector_55
|
||||||
|
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
|
||||||
000000ac t Log_Read_Performance()
|
000000ac t Log_Read_Performance()
|
||||||
|
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||||
000000b2 t Log_Read_Startup()
|
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&)
|
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||||
000000b7 b compass
|
000000b7 b compass
|
||||||
000000bc t Log_Read_Control_Tuning()
|
000000bc t Log_Read_Control_Tuning()
|
||||||
|
000000be t update_events()
|
||||||
000000c0 t report_throttle()
|
000000c0 t report_throttle()
|
||||||
000000c0 t calc_bearing_error()
|
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*)
|
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||||
|
000000c6 t zero_airspeed()
|
||||||
|
000000c6 t startup_ground()
|
||||||
000000c7 B dcm
|
000000c7 B dcm
|
||||||
|
000000ca t send_radio_out(mavlink_channel_t)
|
||||||
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
|
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
|
||||||
000000ca t control_failsafe(unsigned int)
|
000000ca t control_failsafe(unsigned int)
|
||||||
000000ce t zero_airspeed()
|
000000ce t send_radio_in(mavlink_channel_t)
|
||||||
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
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 setup_mode(unsigned char, Menu::arg const*)::__c
|
||||||
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
||||||
000000d0 t get_bearing(Location*, Location*)
|
000000d0 t get_bearing(Location*, Location*)
|
||||||
000000da t verify_nav_wp()
|
000000d4 t trim_radio()
|
||||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
|
||||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||||
000000e7 r init_ardupilot()::__c
|
000000e7 r init_ardupilot()::__c
|
||||||
000000ec t dump_log(unsigned char, Menu::arg const*)
|
000000ec t dump_log(unsigned char, Menu::arg const*)
|
||||||
000000f0 t throttle_slew_limit()
|
000000f0 t throttle_slew_limit()
|
||||||
000000f2 t test_adc(unsigned char, Menu::arg const*)
|
000000f2 t test_adc(unsigned char, Menu::arg const*)
|
||||||
000000f4 t _mav_finalize_message_chan_send
|
|
||||||
000000fa t Log_Read_Current()
|
000000fa t Log_Read_Current()
|
||||||
00000100 t trim_radio()
|
|
||||||
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
||||||
00000106 t test_current(unsigned char, Menu::arg const*)
|
00000106 t test_current(unsigned char, Menu::arg const*)
|
||||||
00000106 t calc_nav_pitch()
|
00000106 t calc_nav_pitch()
|
||||||
00000106 t get_wp_with_index(int)
|
|
||||||
00000108 t test_battery(unsigned char, Menu::arg const*)
|
00000108 t test_battery(unsigned char, Menu::arg const*)
|
||||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
0000010a t mavlink_delay(unsigned long)
|
||||||
|
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||||
00000110 t test_radio(unsigned char, Menu::arg const*)
|
00000110 t test_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000110 t get_cmd_with_index(int)
|
||||||
00000112 t get_distance(Location*, Location*)
|
00000112 t get_distance(Location*, Location*)
|
||||||
00000112 t startup_ground()
|
00000112 t send_servo_out(mavlink_channel_t)
|
||||||
00000112 t report_batt_monitor()
|
00000112 t report_batt_monitor()
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000114 t read_barometer()
|
00000114 t read_barometer()
|
||||||
00000116 t erase_logs(unsigned char, Menu::arg const*)
|
00000116 t erase_logs(unsigned char, Menu::arg const*)
|
||||||
00000118 t test_gps(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*)
|
00000120 t test_pressure(unsigned char, Menu::arg const*)
|
||||||
00000130 t test_dipswitches(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 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||||
|
00000130 t set_cmd_with_index(Location, int)
|
||||||
00000130 r test_menu_commands
|
00000130 r test_menu_commands
|
||||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||||
0000013e t process_may()
|
|
||||||
0000013e t calc_nav_roll()
|
0000013e t calc_nav_roll()
|
||||||
|
0000013e t handle_process_condition_command()
|
||||||
00000146 t select_logs(unsigned char, Menu::arg const*)
|
00000146 t select_logs(unsigned char, Menu::arg const*)
|
||||||
0000014e t verify_may()
|
00000146 t send_vfr_hud(mavlink_channel_t)
|
||||||
0000014e T GCS_MAVLINK::update()
|
|
||||||
00000152 t report_gains()
|
00000152 t report_gains()
|
||||||
|
00000152 t verify_condition_command()
|
||||||
0000015a t test_airspeed(unsigned char, Menu::arg const*)
|
0000015a t test_airspeed(unsigned char, Menu::arg const*)
|
||||||
|
0000015e t set_guided_WP()
|
||||||
|
0000015e t handle_process_nav_cmd()
|
||||||
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
||||||
0000016a t process_must()
|
0000016c t navigate()
|
||||||
0000016a t set_guided_WP()
|
0000016e t send_attitude(mavlink_channel_t)
|
||||||
00000172 t navigate()
|
|
||||||
00000174 t report_compass()
|
00000174 t report_compass()
|
||||||
|
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
0000017c t send_location(mavlink_channel_t)
|
||||||
0000017e t Log_Read_Nav_Tuning()
|
0000017e t Log_Read_Nav_Tuning()
|
||||||
000001a2 t test_imu(unsigned char, Menu::arg const*)
|
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||||
000001ae T init_home()
|
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||||
|
00000192 T init_home()
|
||||||
|
00000192 t test_imu(unsigned char, Menu::arg const*)
|
||||||
|
000001ae t start_new_log(unsigned char)
|
||||||
000001b2 t update_crosstrack()
|
000001b2 t update_crosstrack()
|
||||||
|
000001b2 t set_mode(unsigned char)
|
||||||
|
000001bc t set_next_WP(Location*)
|
||||||
|
000001bc t send_nav_controller_output(mavlink_channel_t)
|
||||||
000001be t Log_Read_GPS()
|
000001be t Log_Read_GPS()
|
||||||
000001c8 t read_airspeed()
|
000001c0 t read_airspeed()
|
||||||
000001ca t mavlink_delay(unsigned long)
|
000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
000001ca t start_new_log(unsigned char)
|
000001d2 T GCS_MAVLINK::update()
|
||||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
|
||||||
000001ec t init_barometer()
|
000001ea t init_barometer()
|
||||||
00000202 t test_failsafe(unsigned char, Menu::arg const*)
|
00000202 t test_failsafe(unsigned char, Menu::arg const*)
|
||||||
00000206 t set_next_WP(Location*)
|
|
||||||
00000208 t calc_throttle()
|
00000208 t calc_throttle()
|
||||||
00000226 t Log_Read(int, int)
|
00000216 t Log_Read(int, int)
|
||||||
|
0000021a t send_raw_imu1(mavlink_channel_t)
|
||||||
|
0000022a t send_gps_raw(mavlink_channel_t)
|
||||||
|
0000022c t process_next_command()
|
||||||
0000022c t test_wp(unsigned char, Menu::arg const*)
|
0000022c t test_wp(unsigned char, Menu::arg const*)
|
||||||
0000022c t set_mode(unsigned char)
|
00000230 t verify_nav_command()
|
||||||
00000232 t verify_must()
|
|
||||||
0000023e t print_radio_values()
|
0000023e t print_radio_values()
|
||||||
0000024c t update_loiter()
|
0000024c t update_loiter()
|
||||||
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000268 t send_raw_imu3(mavlink_channel_t)
|
||||||
000002e4 t read_radio()
|
000002e4 t read_radio()
|
||||||
0000031e t read_battery()
|
0000031e t test_mag(unsigned char, Menu::arg const*)
|
||||||
0000032e t test_mag(unsigned char, Menu::arg const*)
|
|
||||||
0000033a W Parameters::~Parameters()
|
0000033a W Parameters::~Parameters()
|
||||||
00000404 t process_next_command()
|
00000382 t handle_process_do_command()
|
||||||
0000041c t set_servos()
|
000003e6 t read_battery()
|
||||||
0000044c t print_log_menu()
|
0000044c t print_log_menu()
|
||||||
000004b2 t mavlink_parse_char
|
000004de t set_servos()
|
||||||
0000059c t __static_initialization_and_destruction_0(int, int)
|
0000059c t __static_initialization_and_destruction_0(int, int)
|
||||||
000006da t init_ardupilot()
|
0000064a t init_ardupilot()
|
||||||
00000831 b g
|
00000920 W Parameters::Parameters()
|
||||||
0000090a W Parameters::Parameters()
|
0000092b b g
|
||||||
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||||
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
00001be4 T loop
|
||||||
00001ae8 T loop
|
|
||||||
|
|
|
@ -3,11 +3,13 @@
|
||||||
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
|
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: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
|
/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
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
|
||||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
|
||||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
|
||||||
%% libraries/APM_BMP085/APM_BMP085.o
|
%% libraries/APM_BMP085/APM_BMP085.o
|
||||||
|
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||||
%% libraries/APM_RC/APM_RC.o
|
%% libraries/APM_RC/APM_RC.o
|
||||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||||
%% libraries/AP_ADC/AP_ADC.o
|
%% libraries/AP_ADC/AP_ADC.o
|
||||||
|
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
|
||||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||||
%% libraries/AP_GPS/GPS.o
|
%% libraries/AP_GPS/GPS.o
|
||||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||||
|
%% libraries/AP_Mount/AP_Mount.o
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||||
|
%% libraries/AP_Relay/AP_Relay.o
|
||||||
%% libraries/DataFlash/DataFlash.o
|
%% libraries/DataFlash/DataFlash.o
|
||||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
|
||||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
/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
|
/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/BetterStream.o
|
||||||
|
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
||||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||||
%% libraries/ModeFilter/ModeFilter.o
|
%% libraries/ModeFilter/ModeFilter.o
|
||||||
%% libraries/PID/PID.o
|
%% libraries/PID/PID.o
|
||||||
|
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||||
%% libraries/RC_Channel/RC_Channel.o
|
%% libraries/RC_Channel/RC_Channel.o
|
||||||
%% libraries/memcheck/memcheck.o
|
%% libraries/memcheck/memcheck.o
|
||||||
%% libraries/FastSerial/ftoa_engine.o
|
%% libraries/FastSerial/ftoa_engine.o
|
||||||
|
|
|
@ -3,20 +3,21 @@
|
||||||
00000001 b home_is_set
|
00000001 b home_is_set
|
||||||
00000001 b ch3_failsafe
|
00000001 b ch3_failsafe
|
||||||
00000001 b land_complete
|
00000001 b land_complete
|
||||||
00000001 b command_may_ID
|
00000001 b mavlink_active
|
||||||
00000001 b command_must_ID
|
00000001 b nav_command_ID
|
||||||
00000001 b failsafeCounter
|
00000001 b failsafeCounter
|
||||||
00000001 b counter_one_herz
|
00000001 b counter_one_herz
|
||||||
00000001 b in_mavlink_delay
|
00000001 b in_mavlink_delay
|
||||||
00000001 b slow_loopCounter
|
00000001 b slow_loopCounter
|
||||||
00000001 d takeoff_complete
|
00000001 d takeoff_complete
|
||||||
00000001 b command_may_index
|
00000001 b nav_command_index
|
||||||
00000001 b command_must_index
|
|
||||||
00000001 b delta_ms_fast_loop
|
00000001 b delta_ms_fast_loop
|
||||||
00000001 d ground_start_count
|
00000001 d ground_start_count
|
||||||
00000001 b medium_loopCounter
|
00000001 b medium_loopCounter
|
||||||
|
00000001 b non_nav_command_ID
|
||||||
00000001 b rc_override_active
|
00000001 b rc_override_active
|
||||||
00000001 b delta_ms_medium_loop
|
00000001 b delta_ms_medium_loop
|
||||||
|
00000001 b non_nav_command_index
|
||||||
00000001 b superslow_loopCounter
|
00000001 b superslow_loopCounter
|
||||||
00000001 b event_id
|
00000001 b event_id
|
||||||
00000001 b GPS_light
|
00000001 b GPS_light
|
||||||
|
@ -25,12 +26,10 @@
|
||||||
00000001 D control_mode
|
00000001 D control_mode
|
||||||
00000001 B hindex
|
00000001 B hindex
|
||||||
00000001 B inverted_flight
|
00000001 B inverted_flight
|
||||||
00000001 B mavdelay
|
|
||||||
00000001 B n
|
00000001 B n
|
||||||
00000001 B oldSwitchPosition
|
00000001 B oldSwitchPosition
|
||||||
|
00000001 B relay
|
||||||
00000002 T ReadSCP1000()
|
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 loiter_sum
|
||||||
00000002 b event_delay
|
00000002 b event_delay
|
||||||
00000002 b event_value
|
00000002 b event_value
|
||||||
|
@ -50,7 +49,6 @@
|
||||||
00000002 b event_undo_value
|
00000002 b event_undo_value
|
||||||
00000002 b ground_start_avg
|
00000002 b ground_start_avg
|
||||||
00000002 b airspeed_pressure
|
00000002 b airspeed_pressure
|
||||||
00000002 b adc
|
|
||||||
00000002 r comma
|
00000002 r comma
|
||||||
00000002 b g_gps
|
00000002 b g_gps
|
||||||
00000002 b pmTest1
|
00000002 b pmTest1
|
||||||
|
@ -60,7 +58,6 @@
|
||||||
00000002 d ch2_temp
|
00000002 d ch2_temp
|
||||||
00000002 b failsafe
|
00000002 b failsafe
|
||||||
00000002 b sonar_alt
|
00000002 b sonar_alt
|
||||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
|
||||||
00000002 r print_divider()::__c
|
00000002 r print_divider()::__c
|
||||||
00000002 d throttle_slew_limit()::last
|
00000002 d throttle_slew_limit()::last
|
||||||
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -72,6 +69,7 @@
|
||||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
00000003 r print_log_menu()::__c
|
00000003 r print_log_menu()::__c
|
||||||
00000003 r report_compass()::__c
|
00000003 r report_compass()::__c
|
||||||
|
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
00000004 b event_timer
|
00000004 b event_timer
|
||||||
00000004 d hold_course
|
00000004 d hold_course
|
||||||
00000004 b loiter_time
|
00000004 b loiter_time
|
||||||
|
@ -82,6 +80,7 @@
|
||||||
00000004 b airspeed_raw
|
00000004 b airspeed_raw
|
||||||
00000004 b current_amps
|
00000004 b current_amps
|
||||||
00000004 b energy_error
|
00000004 b energy_error
|
||||||
|
00000004 b airspeed_fbwB
|
||||||
00000004 b bearing_error
|
00000004 b bearing_error
|
||||||
00000004 b current_total
|
00000004 b current_total
|
||||||
00000004 b nav_loopTimer
|
00000004 b nav_loopTimer
|
||||||
|
@ -123,8 +122,6 @@
|
||||||
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_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 b mavlink_delay(unsigned long)::last_50hz
|
||||||
00000004 r print_enabled(bool)::__c
|
00000004 r print_enabled(bool)::__c
|
||||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -214,14 +211,14 @@
|
||||||
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
|
||||||
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
|
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
|
0000000a r init_home()::__c
|
||||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
|
0000000a r verify_nav_wp()::__c
|
||||||
0000000a r report_compass()::__c
|
0000000a r report_compass()::__c
|
||||||
0000000a r report_throttle()::__c
|
0000000a r report_throttle()::__c
|
||||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -232,31 +229,30 @@
|
||||||
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 RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a V Parameters::Parameters()::__c
|
0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a T setup
|
0000000a T setup
|
||||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
0000000b r report_gains()::__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 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
|
||||||
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 process_logs(unsigned char, Menu::arg const*)
|
||||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||||
0000000c V vtable for IMU
|
0000000c V vtable for IMU
|
||||||
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
||||||
0000000c r report_xtrack()::__c
|
0000000c r report_xtrack()::__c
|
||||||
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__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 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
|
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
|
||||||
|
0000000c V Parameters::Parameters()::__c
|
||||||
0000000d r init_home()::__c
|
0000000d r init_home()::__c
|
||||||
0000000d r verify_RTL()::__c
|
0000000d r verify_RTL()::__c
|
||||||
0000000d r demo_servos(unsigned char)::__c
|
0000000d r demo_servos(unsigned char)::__c
|
||||||
|
@ -267,6 +263,9 @@
|
||||||
0000000d r print_log_menu()::__c
|
0000000d r print_log_menu()::__c
|
||||||
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
||||||
0000000d r Log_Read_Startup()::__c
|
0000000d r Log_Read_Startup()::__c
|
||||||
|
0000000d r control_failsafe(unsigned int)::__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
|
||||||
|
@ -287,6 +286,7 @@
|
||||||
0000000d B sonar_mode_filter
|
0000000d B sonar_mode_filter
|
||||||
0000000e t global destructors keyed to Serial
|
0000000e t global destructors keyed to Serial
|
||||||
0000000e t global constructors keyed to Serial
|
0000000e t global constructors keyed to Serial
|
||||||
|
0000000e t send_statustext(mavlink_channel_t)
|
||||||
0000000e V vtable for AP_Float16
|
0000000e V vtable for AP_Float16
|
||||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||||
|
@ -296,10 +296,10 @@
|
||||||
0000000e V vtable for AP_VarT<int>
|
0000000e V vtable for AP_VarT<int>
|
||||||
0000000e V vtable for AP_VarT<long>
|
0000000e V vtable for AP_VarT<long>
|
||||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
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 select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_gains()::__c
|
0000000e r report_gains()::__c
|
||||||
0000000e r print_log_menu()::__c
|
0000000e r print_log_menu()::__c
|
||||||
|
0000000e r control_failsafe(unsigned int)::__c
|
||||||
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_batt_monitor()::__c
|
0000000e r report_batt_monitor()::__c
|
||||||
0000000e r report_flight_modes()::__c
|
0000000e r report_flight_modes()::__c
|
||||||
|
@ -325,23 +325,26 @@
|
||||||
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 current_loc
|
||||||
0000000f b next_command
|
0000000f b next_nav_command
|
||||||
|
0000000f b next_nonnav_command
|
||||||
0000000f b home
|
0000000f b home
|
||||||
0000000f b next_WP
|
0000000f b next_WP
|
||||||
0000000f b prev_WP
|
0000000f b prev_WP
|
||||||
0000000f b guided_WP
|
0000000f b guided_WP
|
||||||
0000000f r report_gains()::__c
|
0000000f r report_gains()::__c
|
||||||
0000000f r print_log_menu()::__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 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 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 Parameters::Parameters()::__c
|
||||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||||
00000010 b rc_override
|
00000010 b rc_override
|
||||||
00000010 r planner_menu_commands
|
00000010 r planner_menu_commands
|
||||||
|
00000010 r __menu_name__main_menu
|
||||||
|
00000010 T GCS_MAVLINK::send_message(ap_message)
|
||||||
00000010 W AP_VarT<float>::cast_to_float() const
|
00000010 W AP_VarT<float>::cast_to_float() const
|
||||||
00000010 W AP_VarT<long>::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 setup_radio(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -349,17 +352,17 @@
|
||||||
00000010 r Log_Read_Startup()::__c
|
00000010 r Log_Read_Startup()::__c
|
||||||
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000010 r dump_log(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 erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r set_next_WP(Location*)::__c
|
|
||||||
00000011 r zero_eeprom()::__c
|
00000011 r zero_eeprom()::__c
|
||||||
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r startup_ground()::__c
|
00000011 r startup_ground()::__c
|
||||||
00000011 r Log_Read_Attitude()::__c
|
00000011 r Log_Read_Attitude()::__c
|
||||||
00000011 r load_next_command_from_EEPROM()::__c
|
00000011 r process_next_command()::__c
|
||||||
|
00000011 r failsafe_short_on_event()::__c
|
||||||
00000012 B Serial
|
00000012 B Serial
|
||||||
00000012 B Serial1
|
00000012 B Serial1
|
||||||
00000012 B Serial3
|
00000012 B Serial3
|
||||||
|
00000012 t gcs_update()
|
||||||
00000012 W AP_Float16::~AP_Float16()
|
00000012 W AP_Float16::~AP_Float16()
|
||||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
|
@ -372,6 +375,7 @@
|
||||||
00000012 r print_done()::__c
|
00000012 r print_done()::__c
|
||||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000012 r init_barometer()::__c
|
00000012 r init_barometer()::__c
|
||||||
|
00000012 r handle_no_commands()::__c
|
||||||
00000012 r startup_IMU_ground()::__c
|
00000012 r startup_IMU_ground()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
|
@ -391,11 +395,11 @@
|
||||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||||
00000014 W AP_VarT<int>::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_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000014 r test_imu(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 map_baudrate(signed char, unsigned long)::__c
|
||||||
00000015 r report_gains()::__c
|
00000015 r report_gains()::__c
|
||||||
|
00000015 r verify_nav_wp()::__c
|
||||||
00000015 r init_ardupilot()::__c
|
00000015 r init_ardupilot()::__c
|
||||||
00000015 r print_hit_enter()::__c
|
00000015 r print_hit_enter()::__c
|
||||||
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -403,20 +407,18 @@
|
||||||
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r report_batt_monitor()::__c
|
00000016 r report_batt_monitor()::__c
|
||||||
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r GCS_MAVLINK::update()::__c
|
|
||||||
00000016 B sonar
|
00000016 B sonar
|
||||||
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000017 r test_pressure(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
|
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
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 report_compass()::__c
|
||||||
00000018 r Log_Read_Startup()::__c
|
00000018 r Log_Read_Startup()::__c
|
||||||
00000019 r report_batt_monitor()::__c
|
00000019 r report_batt_monitor()::__c
|
||||||
00000019 r failsafe_long_on_event()::__c
|
00000019 r failsafe_long_on_event()::__c
|
||||||
00000019 r GCS_MAVLINK::update()::__c
|
00000019 r handle_process_nav_cmd()::__c
|
||||||
0000001a r reset_control_switch()::__c
|
00000019 r handle_process_do_command()::__c
|
||||||
|
00000019 r handle_process_condition_command()::__c
|
||||||
0000001a r failsafe_short_on_event()::__c
|
0000001a r failsafe_short_on_event()::__c
|
||||||
0000001a r Log_Read(int, int)::__c
|
0000001a r Log_Read(int, int)::__c
|
||||||
0000001b r failsafe_short_off_event()::__c
|
0000001b r failsafe_short_off_event()::__c
|
||||||
|
@ -434,20 +436,23 @@
|
||||||
0000001d r startup_ground()::__c
|
0000001d r startup_ground()::__c
|
||||||
0000001d r report_batt_monitor()::__c
|
0000001d r report_batt_monitor()::__c
|
||||||
0000001e r flight_mode_strings
|
0000001e r flight_mode_strings
|
||||||
0000001e t failsafe_short_off_event()
|
|
||||||
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
0000001e r startup_ground()::__c
|
0000001e r startup_ground()::__c
|
||||||
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
0000001f r init_ardupilot()::__c
|
0000001f r init_ardupilot()::__c
|
||||||
|
0000001f r Log_Read(int, int)::__c
|
||||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000020 t gcs_send_message(ap_message)
|
||||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||||
00000020 r report_xtrack()::__c
|
00000020 r report_xtrack()::__c
|
||||||
00000020 r init_barometer()::__c
|
00000020 r init_barometer()::__c
|
||||||
00000020 r Log_Read(int, int)::__c
|
|
||||||
00000020 t byte_swap_4
|
00000020 t byte_swap_4
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
|
00000021 r verify_loiter_time()::__c
|
||||||
|
00000021 r process_next_command()::__c
|
||||||
00000022 t print_blanks(int)
|
00000022 t print_blanks(int)
|
||||||
|
00000022 t failsafe_short_off_event()
|
||||||
00000022 t reset_I()
|
00000022 t reset_I()
|
||||||
00000022 W AP_Float16::~AP_Float16()
|
00000022 W AP_Float16::~AP_Float16()
|
||||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
|
@ -459,23 +464,22 @@
|
||||||
00000022 W AP_VarT<long>::~AP_VarT()
|
00000022 W AP_VarT<long>::~AP_VarT()
|
||||||
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000022 r report_compass()::__c
|
00000022 r report_compass()::__c
|
||||||
00000022 r increment_WP_index()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000022 r verify_loiter_time()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
||||||
00000023 r print_gyro_offsets()::__c
|
00000023 r print_gyro_offsets()::__c
|
||||||
|
00000023 r verify_loiter_turns()::__c
|
||||||
00000023 r navigate()::__c
|
00000023 r navigate()::__c
|
||||||
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
00000024 r print_accel_offsets()::__c
|
00000024 r print_accel_offsets()::__c
|
||||||
00000024 r verify_loiter_turns()::__c
|
|
||||||
00000026 t print_done()
|
00000026 t print_done()
|
||||||
00000026 b mavlink_queue
|
|
||||||
00000026 t print_hit_enter()
|
00000026 t print_hit_enter()
|
||||||
00000026 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
|
00000026 r init_ardupilot()::__c
|
||||||
00000026 r print_PID(PID*)::__c
|
00000026 r print_PID(PID*)::__c
|
||||||
00000027 r init_ardupilot()::__c
|
00000027 r change_command(unsigned char)::__c
|
||||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
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 t help_log(unsigned char, Menu::arg const*)
|
||||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||||
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
||||||
|
@ -485,71 +489,75 @@
|
||||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||||
0000002a r init_ardupilot()::__c
|
0000002a r init_ardupilot()::__c
|
||||||
0000002a r startup_ground()::__c
|
0000002a r startup_ground()::__c
|
||||||
0000002b r verify_must()::__c
|
0000002a r verify_nav_command()::__c
|
||||||
|
0000002a t _mav_put_int8_t_array
|
||||||
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
||||||
0000002b r change_command(unsigned char)::__c
|
0000002b r change_command(unsigned char)::__c
|
||||||
0000002c t freeRAM()
|
|
||||||
0000002d r startup_IMU_ground()::__c
|
0000002d r startup_IMU_ground()::__c
|
||||||
0000002e t reset_control_switch()
|
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
|
||||||
0000002e t send_rate(unsigned int, unsigned int)
|
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
|
||||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
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 setup_mode(unsigned char, Menu::arg const*)
|
||||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||||
|
00000030 t send_heartbeat(mavlink_channel_t)
|
||||||
00000030 t test_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
|
00000030 r print_log_menu()::__c
|
||||||
00000031 r start_new_log(unsigned char)::__c
|
00000031 r start_new_log(unsigned char)::__c
|
||||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||||
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000033 b pending_status
|
||||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||||
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
||||||
00000034 t _mav_put_int8_t_array
|
00000034 t mavlink_msg_statustext_send
|
||||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||||
00000035 r Log_Read_Nav_Tuning()::__c
|
00000035 r Log_Read_Nav_Tuning()::__c
|
||||||
|
00000035 r verify_condition_command()::__c
|
||||||
00000036 t report_radio()
|
00000036 t report_radio()
|
||||||
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000038 t send_current_waypoint(mavlink_channel_t)
|
||||||
|
00000038 b barometer
|
||||||
00000038 r test_dipswitches(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
|
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r setup_radio(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 planner_mode(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r init_ardupilot()::__c
|
00000039 r init_ardupilot()::__c
|
||||||
0000003a t report_imu()
|
0000003a t report_imu()
|
||||||
|
0000003a t verify_loiter_turns()
|
||||||
0000003a W PID::~PID()
|
0000003a W PID::~PID()
|
||||||
|
0000003c t verify_RTL()
|
||||||
0000003c t Log_Write_Mode(unsigned char)
|
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_wp_print(Location*, unsigned char)::__c
|
||||||
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
0000003d B g_gps_driver
|
0000003d B g_gps_driver
|
||||||
0000003e t verify_RTL()
|
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
|
||||||
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)
|
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
00000040 b adc
|
||||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||||
00000040 t byte_swap_8
|
00000040 t byte_swap_8
|
||||||
00000040 t crc_accumulate
|
|
||||||
00000040 B history
|
00000040 B history
|
||||||
00000043 r Log_Read_GPS()::__c
|
00000043 r Log_Read_GPS()::__c
|
||||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||||
00000044 r report_throttle()::__c
|
00000044 r report_throttle()::__c
|
||||||
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000046 W RC_Channel::~RC_Channel()
|
||||||
|
00000048 t failsafe_long_on_event()
|
||||||
|
0000004a t send_meminfo(mavlink_channel_t)
|
||||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, 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)
|
||||||
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
||||||
0000004c t Log_Read_Mode()
|
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*)
|
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||||
|
00000050 b mavlink_queue
|
||||||
00000050 r log_menu_commands
|
00000050 r log_menu_commands
|
||||||
00000050 r main_menu_commands
|
00000050 r main_menu_commands
|
||||||
00000050 t failsafe_long_on_event()
|
|
||||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||||
|
00000050 B imu
|
||||||
00000054 t print_divider()
|
00000054 t print_divider()
|
||||||
00000054 t print_enabled(bool)
|
00000054 t print_enabled(bool)
|
||||||
00000054 t report_flight_modes()
|
00000054 t report_flight_modes()
|
||||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||||
00000056 t change_command(unsigned char)
|
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||||
00000058 t radio_input_switch()
|
00000058 t radio_input_switch()
|
||||||
0000005a t update_GPS_light()
|
0000005a t update_GPS_light()
|
||||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
@ -558,142 +566,156 @@
|
||||||
0000005c t get_num_logs()
|
0000005c t get_num_logs()
|
||||||
0000005e T GCS_MAVLINK::_count_parameters()
|
0000005e T GCS_MAVLINK::_count_parameters()
|
||||||
00000060 t print_switch(unsigned char, unsigned char)
|
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 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 Log_Write_Attitude(int, int, unsigned int)
|
||||||
|
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
|
||||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||||
00000064 t mavlink_msg_param_value_send
|
00000064 W RC_Channel_aux::~RC_Channel_aux()
|
||||||
00000068 t zero_eeprom()
|
00000068 t zero_eeprom()
|
||||||
00000068 t find_last_log_page(int)
|
00000068 t find_last_log_page(int)
|
||||||
|
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
|
||||||
|
0000006a t demo_servos(unsigned char)
|
||||||
|
0000006a t startup_IMU_ground()
|
||||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||||
0000006c t setup_show(unsigned char, Menu::arg const*)
|
0000006c t setup_show(unsigned char, Menu::arg const*)
|
||||||
0000006c t demo_servos(unsigned char)
|
|
||||||
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
||||||
00000070 r init_ardupilot()::__c
|
00000070 r init_ardupilot()::__c
|
||||||
00000074 t verify_loiter_time()
|
00000072 t verify_loiter_time()
|
||||||
00000076 t startup_IMU_ground()
|
00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
|
||||||
00000078 t read_control_switch()
|
00000078 t read_control_switch()
|
||||||
0000007c t failsafe_short_on_event()
|
0000007c t send_gps_status(mavlink_channel_t)
|
||||||
|
0000007c t do_RTL()
|
||||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||||
00000080 r setup_menu_commands
|
00000080 r setup_menu_commands
|
||||||
00000080 T __vector_25
|
00000080 T __vector_25
|
||||||
00000080 T __vector_36
|
00000080 T __vector_36
|
||||||
00000080 T __vector_54
|
00000080 T __vector_54
|
||||||
|
00000084 t change_command(unsigned char)
|
||||||
00000086 t Log_Read_Attitude()
|
00000086 t Log_Read_Attitude()
|
||||||
00000088 t Log_Read_Raw()
|
00000088 t Log_Read_Raw()
|
||||||
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
||||||
0000008c t print_gyro_offsets()
|
0000008c t print_gyro_offsets()
|
||||||
0000008c t print_accel_offsets()
|
0000008c t print_accel_offsets()
|
||||||
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||||
00000090 t do_RTL()
|
0000008e t failsafe_short_on_event()
|
||||||
|
00000090 t handle_no_commands()
|
||||||
|
00000092 T GCS_MAVLINK::queued_param_send()
|
||||||
00000096 t map_baudrate(signed char, unsigned long)
|
00000096 t map_baudrate(signed char, unsigned long)
|
||||||
00000096 t test_wp_print(Location*, unsigned char)
|
00000096 t test_wp_print(Location*, unsigned char)
|
||||||
0000009c t update_servo_switches()
|
0000009c t update_servo_switches()
|
||||||
0000009c t print_PID(PID*)
|
0000009c t print_PID(PID*)
|
||||||
0000009d B gcs
|
0000009c B gcs0
|
||||||
0000009d B hil
|
0000009c B gcs3
|
||||||
000000a0 t report_xtrack()
|
000000a0 t report_xtrack()
|
||||||
|
000000a2 t verify_nav_wp()
|
||||||
000000a4 t Log_Read_Cmd()
|
000000a4 t Log_Read_Cmd()
|
||||||
000000a4 T __vector_26
|
000000a4 T __vector_26
|
||||||
000000a4 T __vector_37
|
000000a4 T __vector_37
|
||||||
000000a4 T __vector_55
|
000000a4 T __vector_55
|
||||||
|
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
|
||||||
000000ac t Log_Read_Performance()
|
000000ac t Log_Read_Performance()
|
||||||
|
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||||
000000b0 t Log_Read_Startup()
|
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&)
|
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||||
000000b7 b compass
|
000000b7 b compass
|
||||||
000000bc t Log_Read_Control_Tuning()
|
000000bc t Log_Read_Control_Tuning()
|
||||||
|
000000be t update_events()
|
||||||
000000c0 t report_throttle()
|
000000c0 t report_throttle()
|
||||||
000000c0 t calc_bearing_error()
|
000000c0 t calc_bearing_error()
|
||||||
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
||||||
000000c4 t update_events()
|
000000c6 t zero_airspeed()
|
||||||
000000c4 t load_next_command_from_EEPROM()
|
000000c6 t startup_ground()
|
||||||
000000c7 B dcm
|
000000c7 B dcm
|
||||||
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
|
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
|
||||||
|
000000ca t send_radio_out(mavlink_channel_t)
|
||||||
000000ca t control_failsafe(unsigned int)
|
000000ca t control_failsafe(unsigned int)
|
||||||
000000ce t zero_airspeed()
|
000000ce t send_radio_in(mavlink_channel_t)
|
||||||
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
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 setup_mode(unsigned char, Menu::arg const*)::__c
|
||||||
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
||||||
000000d0 t get_bearing(Location*, Location*)
|
000000d0 t get_bearing(Location*, Location*)
|
||||||
000000d8 t verify_nav_wp()
|
000000d4 t trim_radio()
|
||||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
|
||||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||||
000000e7 r init_ardupilot()::__c
|
000000e7 r init_ardupilot()::__c
|
||||||
000000ec t dump_log(unsigned char, Menu::arg const*)
|
000000ec t dump_log(unsigned char, Menu::arg const*)
|
||||||
000000f0 t throttle_slew_limit()
|
000000f0 t throttle_slew_limit()
|
||||||
000000f0 t test_adc(unsigned char, Menu::arg const*)
|
000000f0 t test_adc(unsigned char, Menu::arg const*)
|
||||||
000000f4 t _mav_finalize_message_chan_send
|
|
||||||
000000fa t Log_Read_Current()
|
000000fa t Log_Read_Current()
|
||||||
00000100 t trim_radio()
|
|
||||||
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
||||||
00000106 t test_current(unsigned char, Menu::arg const*)
|
00000106 t test_current(unsigned char, Menu::arg const*)
|
||||||
00000106 t calc_nav_pitch()
|
00000106 t calc_nav_pitch()
|
||||||
00000106 t get_wp_with_index(int)
|
|
||||||
00000108 t test_battery(unsigned char, Menu::arg const*)
|
00000108 t test_battery(unsigned char, Menu::arg const*)
|
||||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
0000010a t mavlink_delay(unsigned long)
|
||||||
|
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||||
00000110 t test_radio(unsigned char, Menu::arg const*)
|
00000110 t test_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000110 t get_cmd_with_index(int)
|
||||||
00000112 t get_distance(Location*, Location*)
|
00000112 t get_distance(Location*, Location*)
|
||||||
00000112 t startup_ground()
|
00000112 t send_servo_out(mavlink_channel_t)
|
||||||
00000112 t report_batt_monitor()
|
00000112 t report_batt_monitor()
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
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 erase_logs(unsigned char, Menu::arg const*)
|
||||||
00000114 t read_barometer()
|
00000114 t read_barometer()
|
||||||
00000118 t test_gps(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*)
|
00000120 t test_pressure(unsigned char, Menu::arg const*)
|
||||||
00000130 t test_dipswitches(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 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||||
|
00000130 t set_cmd_with_index(Location, int)
|
||||||
00000130 r test_menu_commands
|
00000130 r test_menu_commands
|
||||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||||
0000013e t process_may()
|
|
||||||
0000013e t calc_nav_roll()
|
0000013e t calc_nav_roll()
|
||||||
|
0000013e t handle_process_condition_command()
|
||||||
00000146 t select_logs(unsigned char, Menu::arg const*)
|
00000146 t select_logs(unsigned char, Menu::arg const*)
|
||||||
0000014e t verify_may()
|
00000146 t send_vfr_hud(mavlink_channel_t)
|
||||||
0000014e T GCS_MAVLINK::update()
|
|
||||||
00000152 t report_gains()
|
00000152 t report_gains()
|
||||||
|
00000152 t verify_condition_command()
|
||||||
00000158 t test_airspeed(unsigned char, Menu::arg const*)
|
00000158 t test_airspeed(unsigned char, Menu::arg const*)
|
||||||
|
0000015e t set_guided_WP()
|
||||||
|
0000015e t handle_process_nav_cmd()
|
||||||
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
||||||
0000016a t process_must()
|
0000016c t navigate()
|
||||||
0000016a t set_guided_WP()
|
0000016e t send_attitude(mavlink_channel_t)
|
||||||
00000172 t navigate()
|
|
||||||
00000174 t report_compass()
|
00000174 t report_compass()
|
||||||
|
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
0000017c t send_location(mavlink_channel_t)
|
||||||
0000017e t Log_Read_Nav_Tuning()
|
0000017e t Log_Read_Nav_Tuning()
|
||||||
000001a2 t test_imu(unsigned char, Menu::arg const*)
|
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||||
000001ae T init_home()
|
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||||
|
00000190 T init_home()
|
||||||
|
00000192 t test_imu(unsigned char, Menu::arg const*)
|
||||||
|
000001ae t start_new_log(unsigned char)
|
||||||
000001b2 t update_crosstrack()
|
000001b2 t update_crosstrack()
|
||||||
|
000001b2 t set_mode(unsigned char)
|
||||||
|
000001bc t set_next_WP(Location*)
|
||||||
|
000001bc t send_nav_controller_output(mavlink_channel_t)
|
||||||
000001be t Log_Read_GPS()
|
000001be t Log_Read_GPS()
|
||||||
000001c8 t read_airspeed()
|
000001c0 t read_airspeed()
|
||||||
000001ca t mavlink_delay(unsigned long)
|
000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
000001ca t start_new_log(unsigned char)
|
000001d2 T GCS_MAVLINK::update()
|
||||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
|
||||||
000001ec t init_barometer()
|
000001ea t init_barometer()
|
||||||
000001fe t test_failsafe(unsigned char, Menu::arg const*)
|
000001fe t test_failsafe(unsigned char, Menu::arg const*)
|
||||||
00000206 t set_next_WP(Location*)
|
|
||||||
00000208 t calc_throttle()
|
00000208 t calc_throttle()
|
||||||
00000222 t Log_Read(int, int)
|
00000210 t Log_Read(int, int)
|
||||||
|
0000021a t send_raw_imu1(mavlink_channel_t)
|
||||||
00000228 t test_wp(unsigned char, Menu::arg const*)
|
00000228 t test_wp(unsigned char, Menu::arg const*)
|
||||||
0000022c t set_mode(unsigned char)
|
0000022a t send_gps_raw(mavlink_channel_t)
|
||||||
00000232 t verify_must()
|
0000022c t process_next_command()
|
||||||
|
00000230 t verify_nav_command()
|
||||||
0000023e t print_radio_values()
|
0000023e t print_radio_values()
|
||||||
0000024c t update_loiter()
|
0000024c t update_loiter()
|
||||||
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000268 t send_raw_imu3(mavlink_channel_t)
|
||||||
000002e4 t read_radio()
|
000002e4 t read_radio()
|
||||||
0000031e t read_battery()
|
0000031e t test_mag(unsigned char, Menu::arg const*)
|
||||||
0000032e t test_mag(unsigned char, Menu::arg const*)
|
|
||||||
0000033a W Parameters::~Parameters()
|
0000033a W Parameters::~Parameters()
|
||||||
00000404 t process_next_command()
|
00000382 t handle_process_do_command()
|
||||||
0000041c t set_servos()
|
000003e6 t read_battery()
|
||||||
00000436 t print_log_menu()
|
00000436 t print_log_menu()
|
||||||
000004b2 t mavlink_parse_char
|
000004de t set_servos()
|
||||||
0000059c t __static_initialization_and_destruction_0(int, int)
|
0000059c t __static_initialization_and_destruction_0(int, int)
|
||||||
000006da t init_ardupilot()
|
00000648 t init_ardupilot()
|
||||||
00000831 b g
|
00000920 W Parameters::Parameters()
|
||||||
0000090a W Parameters::Parameters()
|
0000092b b g
|
||||||
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||||
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
00001be4 T loop
|
||||||
00001ae8 T loop
|
|
||||||
|
|
|
@ -3,11 +3,13 @@
|
||||||
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
|
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: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
|
/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
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
|
||||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
|
||||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
|
||||||
%% libraries/APM_BMP085/APM_BMP085.o
|
%% libraries/APM_BMP085/APM_BMP085.o
|
||||||
|
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||||
%% libraries/APM_RC/APM_RC.o
|
%% libraries/APM_RC/APM_RC.o
|
||||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||||
%% libraries/AP_ADC/AP_ADC.o
|
%% libraries/AP_ADC/AP_ADC.o
|
||||||
|
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
|
||||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||||
%% libraries/AP_GPS/GPS.o
|
%% libraries/AP_GPS/GPS.o
|
||||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||||
|
%% libraries/AP_Mount/AP_Mount.o
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||||
|
%% libraries/AP_Relay/AP_Relay.o
|
||||||
%% libraries/DataFlash/DataFlash.o
|
%% libraries/DataFlash/DataFlash.o
|
||||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
|
||||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
/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
|
/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/BetterStream.o
|
||||||
|
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
||||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||||
%% libraries/ModeFilter/ModeFilter.o
|
%% libraries/ModeFilter/ModeFilter.o
|
||||||
%% libraries/PID/PID.o
|
%% libraries/PID/PID.o
|
||||||
|
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||||
%% libraries/RC_Channel/RC_Channel.o
|
%% libraries/RC_Channel/RC_Channel.o
|
||||||
%% libraries/memcheck/memcheck.o
|
%% libraries/memcheck/memcheck.o
|
||||||
%% libraries/FastSerial/ftoa_engine.o
|
%% libraries/FastSerial/ftoa_engine.o
|
||||||
|
|
|
@ -3,20 +3,21 @@
|
||||||
00000001 b home_is_set
|
00000001 b home_is_set
|
||||||
00000001 b ch3_failsafe
|
00000001 b ch3_failsafe
|
||||||
00000001 b land_complete
|
00000001 b land_complete
|
||||||
00000001 b command_may_ID
|
00000001 b mavlink_active
|
||||||
00000001 b command_must_ID
|
00000001 b nav_command_ID
|
||||||
00000001 b failsafeCounter
|
00000001 b failsafeCounter
|
||||||
00000001 b counter_one_herz
|
00000001 b counter_one_herz
|
||||||
00000001 b in_mavlink_delay
|
00000001 b in_mavlink_delay
|
||||||
00000001 b slow_loopCounter
|
00000001 b slow_loopCounter
|
||||||
00000001 d takeoff_complete
|
00000001 d takeoff_complete
|
||||||
00000001 b command_may_index
|
00000001 b nav_command_index
|
||||||
00000001 b command_must_index
|
|
||||||
00000001 b delta_ms_fast_loop
|
00000001 b delta_ms_fast_loop
|
||||||
00000001 d ground_start_count
|
00000001 d ground_start_count
|
||||||
00000001 b medium_loopCounter
|
00000001 b medium_loopCounter
|
||||||
|
00000001 b non_nav_command_ID
|
||||||
00000001 b rc_override_active
|
00000001 b rc_override_active
|
||||||
00000001 b delta_ms_medium_loop
|
00000001 b delta_ms_medium_loop
|
||||||
|
00000001 b non_nav_command_index
|
||||||
00000001 b superslow_loopCounter
|
00000001 b superslow_loopCounter
|
||||||
00000001 b event_id
|
00000001 b event_id
|
||||||
00000001 b GPS_light
|
00000001 b GPS_light
|
||||||
|
@ -25,12 +26,10 @@
|
||||||
00000001 D control_mode
|
00000001 D control_mode
|
||||||
00000001 B hindex
|
00000001 B hindex
|
||||||
00000001 B inverted_flight
|
00000001 B inverted_flight
|
||||||
00000001 B mavdelay
|
|
||||||
00000001 B n
|
00000001 B n
|
||||||
00000001 B oldSwitchPosition
|
00000001 B oldSwitchPosition
|
||||||
|
00000001 B relay
|
||||||
00000002 T ReadSCP1000()
|
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 loiter_sum
|
||||||
00000002 b event_delay
|
00000002 b event_delay
|
||||||
00000002 b event_value
|
00000002 b event_value
|
||||||
|
@ -50,7 +49,6 @@
|
||||||
00000002 b event_undo_value
|
00000002 b event_undo_value
|
||||||
00000002 b ground_start_avg
|
00000002 b ground_start_avg
|
||||||
00000002 b airspeed_pressure
|
00000002 b airspeed_pressure
|
||||||
00000002 b adc
|
|
||||||
00000002 r comma
|
00000002 r comma
|
||||||
00000002 b g_gps
|
00000002 b g_gps
|
||||||
00000002 b pmTest1
|
00000002 b pmTest1
|
||||||
|
@ -60,7 +58,6 @@
|
||||||
00000002 d ch2_temp
|
00000002 d ch2_temp
|
||||||
00000002 b failsafe
|
00000002 b failsafe
|
||||||
00000002 b sonar_alt
|
00000002 b sonar_alt
|
||||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
|
||||||
00000002 r print_divider()::__c
|
00000002 r print_divider()::__c
|
||||||
00000002 d throttle_slew_limit()::last
|
00000002 d throttle_slew_limit()::last
|
||||||
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -72,6 +69,7 @@
|
||||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
00000003 r print_log_menu()::__c
|
00000003 r print_log_menu()::__c
|
||||||
00000003 r report_compass()::__c
|
00000003 r report_compass()::__c
|
||||||
|
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
00000004 b event_timer
|
00000004 b event_timer
|
||||||
00000004 d hold_course
|
00000004 d hold_course
|
||||||
00000004 b loiter_time
|
00000004 b loiter_time
|
||||||
|
@ -82,6 +80,7 @@
|
||||||
00000004 b airspeed_raw
|
00000004 b airspeed_raw
|
||||||
00000004 b current_amps
|
00000004 b current_amps
|
||||||
00000004 b energy_error
|
00000004 b energy_error
|
||||||
|
00000004 b airspeed_fbwB
|
||||||
00000004 b bearing_error
|
00000004 b bearing_error
|
||||||
00000004 b current_total
|
00000004 b current_total
|
||||||
00000004 b nav_loopTimer
|
00000004 b nav_loopTimer
|
||||||
|
@ -123,8 +122,6 @@
|
||||||
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_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 b mavlink_delay(unsigned long)::last_50hz
|
||||||
00000004 r print_enabled(bool)::__c
|
00000004 r print_enabled(bool)::__c
|
||||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -214,14 +211,14 @@
|
||||||
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
|
||||||
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
|
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
|
0000000a r init_home()::__c
|
||||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
|
0000000a r verify_nav_wp()::__c
|
||||||
0000000a r report_compass()::__c
|
0000000a r report_compass()::__c
|
||||||
0000000a r report_throttle()::__c
|
0000000a r report_throttle()::__c
|
||||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -232,31 +229,30 @@
|
||||||
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 RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a V Parameters::Parameters()::__c
|
0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a T setup
|
0000000a T setup
|
||||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
0000000b r report_gains()::__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 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
|
||||||
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 process_logs(unsigned char, Menu::arg const*)
|
||||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||||
0000000c V vtable for IMU
|
0000000c V vtable for IMU
|
||||||
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
||||||
0000000c r report_xtrack()::__c
|
0000000c r report_xtrack()::__c
|
||||||
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__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 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
|
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
|
||||||
|
0000000c V Parameters::Parameters()::__c
|
||||||
0000000d r init_home()::__c
|
0000000d r init_home()::__c
|
||||||
0000000d r verify_RTL()::__c
|
0000000d r verify_RTL()::__c
|
||||||
0000000d r demo_servos(unsigned char)::__c
|
0000000d r demo_servos(unsigned char)::__c
|
||||||
|
@ -267,6 +263,9 @@
|
||||||
0000000d r print_log_menu()::__c
|
0000000d r print_log_menu()::__c
|
||||||
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
||||||
0000000d r Log_Read_Startup()::__c
|
0000000d r Log_Read_Startup()::__c
|
||||||
|
0000000d r control_failsafe(unsigned int)::__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
|
||||||
|
@ -287,6 +286,7 @@
|
||||||
0000000d B sonar_mode_filter
|
0000000d B sonar_mode_filter
|
||||||
0000000e t global destructors keyed to Serial
|
0000000e t global destructors keyed to Serial
|
||||||
0000000e t global constructors keyed to Serial
|
0000000e t global constructors keyed to Serial
|
||||||
|
0000000e t send_statustext(mavlink_channel_t)
|
||||||
0000000e V vtable for AP_Float16
|
0000000e V vtable for AP_Float16
|
||||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||||
|
@ -296,10 +296,10 @@
|
||||||
0000000e V vtable for AP_VarT<int>
|
0000000e V vtable for AP_VarT<int>
|
||||||
0000000e V vtable for AP_VarT<long>
|
0000000e V vtable for AP_VarT<long>
|
||||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
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 select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_gains()::__c
|
0000000e r report_gains()::__c
|
||||||
0000000e r print_log_menu()::__c
|
0000000e r print_log_menu()::__c
|
||||||
|
0000000e r control_failsafe(unsigned int)::__c
|
||||||
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_batt_monitor()::__c
|
0000000e r report_batt_monitor()::__c
|
||||||
0000000e r report_flight_modes()::__c
|
0000000e r report_flight_modes()::__c
|
||||||
|
@ -325,23 +325,26 @@
|
||||||
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 current_loc
|
||||||
0000000f b next_command
|
0000000f b next_nav_command
|
||||||
|
0000000f b next_nonnav_command
|
||||||
0000000f b home
|
0000000f b home
|
||||||
0000000f b next_WP
|
0000000f b next_WP
|
||||||
0000000f b prev_WP
|
0000000f b prev_WP
|
||||||
0000000f b guided_WP
|
0000000f b guided_WP
|
||||||
0000000f r report_gains()::__c
|
0000000f r report_gains()::__c
|
||||||
0000000f r print_log_menu()::__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 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 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 Parameters::Parameters()::__c
|
||||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||||
00000010 b rc_override
|
00000010 b rc_override
|
||||||
00000010 r planner_menu_commands
|
00000010 r planner_menu_commands
|
||||||
|
00000010 r __menu_name__main_menu
|
||||||
|
00000010 T GCS_MAVLINK::send_message(ap_message)
|
||||||
00000010 W AP_VarT<float>::cast_to_float() const
|
00000010 W AP_VarT<float>::cast_to_float() const
|
||||||
00000010 W AP_VarT<long>::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 setup_radio(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -349,17 +352,17 @@
|
||||||
00000010 r Log_Read_Startup()::__c
|
00000010 r Log_Read_Startup()::__c
|
||||||
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000010 r dump_log(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 erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r set_next_WP(Location*)::__c
|
|
||||||
00000011 r zero_eeprom()::__c
|
00000011 r zero_eeprom()::__c
|
||||||
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r startup_ground()::__c
|
00000011 r startup_ground()::__c
|
||||||
00000011 r Log_Read_Attitude()::__c
|
00000011 r Log_Read_Attitude()::__c
|
||||||
00000011 r load_next_command_from_EEPROM()::__c
|
00000011 r process_next_command()::__c
|
||||||
|
00000011 r failsafe_short_on_event()::__c
|
||||||
00000012 B Serial
|
00000012 B Serial
|
||||||
00000012 B Serial1
|
00000012 B Serial1
|
||||||
00000012 B Serial3
|
00000012 B Serial3
|
||||||
|
00000012 t gcs_update()
|
||||||
00000012 W AP_Float16::~AP_Float16()
|
00000012 W AP_Float16::~AP_Float16()
|
||||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
|
@ -372,6 +375,7 @@
|
||||||
00000012 r print_done()::__c
|
00000012 r print_done()::__c
|
||||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000012 r init_barometer()::__c
|
00000012 r init_barometer()::__c
|
||||||
|
00000012 r handle_no_commands()::__c
|
||||||
00000012 r startup_IMU_ground()::__c
|
00000012 r startup_IMU_ground()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
|
@ -391,11 +395,11 @@
|
||||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||||
00000014 W AP_VarT<int>::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_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000014 r test_imu(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 map_baudrate(signed char, unsigned long)::__c
|
||||||
00000015 r report_gains()::__c
|
00000015 r report_gains()::__c
|
||||||
|
00000015 r verify_nav_wp()::__c
|
||||||
00000015 r init_ardupilot()::__c
|
00000015 r init_ardupilot()::__c
|
||||||
00000015 r print_hit_enter()::__c
|
00000015 r print_hit_enter()::__c
|
||||||
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -403,20 +407,18 @@
|
||||||
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r report_batt_monitor()::__c
|
00000016 r report_batt_monitor()::__c
|
||||||
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r GCS_MAVLINK::update()::__c
|
|
||||||
00000016 B sonar
|
00000016 B sonar
|
||||||
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000017 r test_pressure(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
|
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
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 report_compass()::__c
|
||||||
00000018 r Log_Read_Startup()::__c
|
00000018 r Log_Read_Startup()::__c
|
||||||
00000019 r report_batt_monitor()::__c
|
00000019 r report_batt_monitor()::__c
|
||||||
00000019 r failsafe_long_on_event()::__c
|
00000019 r failsafe_long_on_event()::__c
|
||||||
00000019 r GCS_MAVLINK::update()::__c
|
00000019 r handle_process_nav_cmd()::__c
|
||||||
0000001a r reset_control_switch()::__c
|
00000019 r handle_process_do_command()::__c
|
||||||
|
00000019 r handle_process_condition_command()::__c
|
||||||
0000001a r failsafe_short_on_event()::__c
|
0000001a r failsafe_short_on_event()::__c
|
||||||
0000001a r Log_Read(int, int)::__c
|
0000001a r Log_Read(int, int)::__c
|
||||||
0000001b r failsafe_short_off_event()::__c
|
0000001b r failsafe_short_off_event()::__c
|
||||||
|
@ -434,20 +436,23 @@
|
||||||
0000001d r startup_ground()::__c
|
0000001d r startup_ground()::__c
|
||||||
0000001d r report_batt_monitor()::__c
|
0000001d r report_batt_monitor()::__c
|
||||||
0000001e r flight_mode_strings
|
0000001e r flight_mode_strings
|
||||||
0000001e t failsafe_short_off_event()
|
|
||||||
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
0000001e r startup_ground()::__c
|
0000001e r startup_ground()::__c
|
||||||
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
0000001f r init_ardupilot()::__c
|
0000001f r init_ardupilot()::__c
|
||||||
|
0000001f r Log_Read(int, int)::__c
|
||||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000020 t gcs_send_message(ap_message)
|
||||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||||
00000020 r report_xtrack()::__c
|
00000020 r report_xtrack()::__c
|
||||||
00000020 r init_barometer()::__c
|
00000020 r init_barometer()::__c
|
||||||
00000020 r Log_Read(int, int)::__c
|
|
||||||
00000020 t byte_swap_4
|
00000020 t byte_swap_4
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
|
00000021 r verify_loiter_time()::__c
|
||||||
|
00000021 r process_next_command()::__c
|
||||||
00000022 t print_blanks(int)
|
00000022 t print_blanks(int)
|
||||||
|
00000022 t failsafe_short_off_event()
|
||||||
00000022 t reset_I()
|
00000022 t reset_I()
|
||||||
00000022 W AP_Float16::~AP_Float16()
|
00000022 W AP_Float16::~AP_Float16()
|
||||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
|
@ -459,23 +464,22 @@
|
||||||
00000022 W AP_VarT<long>::~AP_VarT()
|
00000022 W AP_VarT<long>::~AP_VarT()
|
||||||
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000022 r report_compass()::__c
|
00000022 r report_compass()::__c
|
||||||
00000022 r increment_WP_index()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000022 r verify_loiter_time()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
||||||
00000023 r print_gyro_offsets()::__c
|
00000023 r print_gyro_offsets()::__c
|
||||||
|
00000023 r verify_loiter_turns()::__c
|
||||||
00000023 r navigate()::__c
|
00000023 r navigate()::__c
|
||||||
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
00000024 r print_accel_offsets()::__c
|
00000024 r print_accel_offsets()::__c
|
||||||
00000024 r verify_loiter_turns()::__c
|
|
||||||
00000026 t print_done()
|
00000026 t print_done()
|
||||||
00000026 b mavlink_queue
|
|
||||||
00000026 t print_hit_enter()
|
00000026 t print_hit_enter()
|
||||||
00000026 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
|
00000026 r init_ardupilot()::__c
|
||||||
00000026 r print_PID(PID*)::__c
|
00000026 r print_PID(PID*)::__c
|
||||||
00000027 r init_ardupilot()::__c
|
00000027 r change_command(unsigned char)::__c
|
||||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
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 t help_log(unsigned char, Menu::arg const*)
|
||||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||||
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
||||||
|
@ -485,71 +489,75 @@
|
||||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||||
0000002a r init_ardupilot()::__c
|
0000002a r init_ardupilot()::__c
|
||||||
0000002a r startup_ground()::__c
|
0000002a r startup_ground()::__c
|
||||||
0000002b r verify_must()::__c
|
0000002a r verify_nav_command()::__c
|
||||||
|
0000002a t _mav_put_int8_t_array
|
||||||
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
||||||
0000002b r change_command(unsigned char)::__c
|
0000002b r change_command(unsigned char)::__c
|
||||||
0000002c t freeRAM()
|
|
||||||
0000002d r startup_IMU_ground()::__c
|
0000002d r startup_IMU_ground()::__c
|
||||||
0000002e t reset_control_switch()
|
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
|
||||||
0000002e t send_rate(unsigned int, unsigned int)
|
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
|
||||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
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 setup_mode(unsigned char, Menu::arg const*)
|
||||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||||
|
00000030 t send_heartbeat(mavlink_channel_t)
|
||||||
00000030 t test_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
|
00000030 r print_log_menu()::__c
|
||||||
00000031 r start_new_log(unsigned char)::__c
|
00000031 r start_new_log(unsigned char)::__c
|
||||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||||
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000033 b pending_status
|
||||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||||
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
||||||
00000034 t _mav_put_int8_t_array
|
00000034 t mavlink_msg_statustext_send
|
||||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||||
00000035 r Log_Read_Nav_Tuning()::__c
|
00000035 r Log_Read_Nav_Tuning()::__c
|
||||||
|
00000035 r verify_condition_command()::__c
|
||||||
00000036 t report_radio()
|
00000036 t report_radio()
|
||||||
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000038 t send_current_waypoint(mavlink_channel_t)
|
||||||
|
00000038 b barometer
|
||||||
00000038 r test_dipswitches(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
|
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r setup_radio(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 planner_mode(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r init_ardupilot()::__c
|
00000039 r init_ardupilot()::__c
|
||||||
0000003a t report_imu()
|
0000003a t report_imu()
|
||||||
|
0000003a t verify_loiter_turns()
|
||||||
0000003a W PID::~PID()
|
0000003a W PID::~PID()
|
||||||
|
0000003c t verify_RTL()
|
||||||
0000003c t Log_Write_Mode(unsigned char)
|
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_wp_print(Location*, unsigned char)::__c
|
||||||
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
0000003d B g_gps_driver
|
0000003d B g_gps_driver
|
||||||
0000003e t verify_RTL()
|
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
|
||||||
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)
|
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
00000040 b adc
|
||||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||||
00000040 t byte_swap_8
|
00000040 t byte_swap_8
|
||||||
00000040 t crc_accumulate
|
|
||||||
00000040 B history
|
00000040 B history
|
||||||
00000043 r Log_Read_GPS()::__c
|
00000043 r Log_Read_GPS()::__c
|
||||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||||
00000044 r report_throttle()::__c
|
00000044 r report_throttle()::__c
|
||||||
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000046 W RC_Channel::~RC_Channel()
|
||||||
|
00000048 t failsafe_long_on_event()
|
||||||
|
0000004a t send_meminfo(mavlink_channel_t)
|
||||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, 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)
|
||||||
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
||||||
0000004c t Log_Read_Mode()
|
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*)
|
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||||
|
00000050 b mavlink_queue
|
||||||
00000050 r log_menu_commands
|
00000050 r log_menu_commands
|
||||||
00000050 r main_menu_commands
|
00000050 r main_menu_commands
|
||||||
00000050 t failsafe_long_on_event()
|
|
||||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||||
|
00000050 B imu
|
||||||
00000054 t print_divider()
|
00000054 t print_divider()
|
||||||
00000054 t print_enabled(bool)
|
00000054 t print_enabled(bool)
|
||||||
00000054 t report_flight_modes()
|
00000054 t report_flight_modes()
|
||||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||||
00000056 t change_command(unsigned char)
|
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||||
00000058 t radio_input_switch()
|
00000058 t radio_input_switch()
|
||||||
0000005a t update_GPS_light()
|
0000005a t update_GPS_light()
|
||||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
@ -557,143 +565,157 @@
|
||||||
0000005c t readSwitch()
|
0000005c t readSwitch()
|
||||||
0000005c t get_num_logs()
|
0000005c t get_num_logs()
|
||||||
0000005e T GCS_MAVLINK::_count_parameters()
|
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 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)
|
00000062 t print_switch(unsigned char, unsigned char)
|
||||||
00000064 t Log_Write_Attitude(int, int, unsigned int)
|
00000064 t Log_Write_Attitude(int, int, unsigned int)
|
||||||
|
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
|
||||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||||
00000064 t mavlink_msg_param_value_send
|
00000064 W RC_Channel_aux::~RC_Channel_aux()
|
||||||
00000068 t zero_eeprom()
|
00000068 t zero_eeprom()
|
||||||
00000068 t find_last_log_page(int)
|
00000068 t find_last_log_page(int)
|
||||||
|
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
|
||||||
|
0000006a t demo_servos(unsigned char)
|
||||||
|
0000006a t startup_IMU_ground()
|
||||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||||
0000006c t setup_show(unsigned char, Menu::arg const*)
|
0000006c t setup_show(unsigned char, Menu::arg const*)
|
||||||
0000006c t demo_servos(unsigned char)
|
|
||||||
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
||||||
00000070 r init_ardupilot()::__c
|
00000070 r init_ardupilot()::__c
|
||||||
00000074 t verify_loiter_time()
|
00000072 t verify_loiter_time()
|
||||||
00000076 t startup_IMU_ground()
|
00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
|
||||||
00000078 t read_control_switch()
|
00000078 t read_control_switch()
|
||||||
0000007c t failsafe_short_on_event()
|
0000007c t send_gps_status(mavlink_channel_t)
|
||||||
|
0000007c t do_RTL()
|
||||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||||
00000080 r setup_menu_commands
|
00000080 r setup_menu_commands
|
||||||
00000080 T __vector_25
|
00000080 T __vector_25
|
||||||
00000080 T __vector_36
|
00000080 T __vector_36
|
||||||
00000080 T __vector_54
|
00000080 T __vector_54
|
||||||
|
00000084 t change_command(unsigned char)
|
||||||
00000086 t Log_Read_Attitude()
|
00000086 t Log_Read_Attitude()
|
||||||
00000088 t Log_Read_Raw()
|
00000088 t Log_Read_Raw()
|
||||||
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
||||||
0000008c t print_gyro_offsets()
|
0000008c t print_gyro_offsets()
|
||||||
0000008c t print_accel_offsets()
|
0000008c t print_accel_offsets()
|
||||||
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||||
00000090 t do_RTL()
|
0000008e t handle_no_commands()
|
||||||
|
0000008e t failsafe_short_on_event()
|
||||||
|
00000092 T GCS_MAVLINK::queued_param_send()
|
||||||
00000096 t map_baudrate(signed char, unsigned long)
|
00000096 t map_baudrate(signed char, unsigned long)
|
||||||
00000096 t test_wp_print(Location*, unsigned char)
|
00000096 t test_wp_print(Location*, unsigned char)
|
||||||
0000009c t update_servo_switches()
|
0000009c t update_servo_switches()
|
||||||
0000009c t print_PID(PID*)
|
0000009c t print_PID(PID*)
|
||||||
0000009d B gcs
|
0000009c B gcs0
|
||||||
0000009d B hil
|
0000009c B gcs3
|
||||||
000000a0 t report_xtrack()
|
000000a0 t report_xtrack()
|
||||||
|
000000a2 t verify_nav_wp()
|
||||||
000000a4 t Log_Read_Cmd()
|
000000a4 t Log_Read_Cmd()
|
||||||
000000a4 T __vector_26
|
000000a4 T __vector_26
|
||||||
000000a4 T __vector_37
|
000000a4 T __vector_37
|
||||||
000000a4 T __vector_55
|
000000a4 T __vector_55
|
||||||
|
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
|
||||||
000000ac t Log_Read_Performance()
|
000000ac t Log_Read_Performance()
|
||||||
|
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||||
000000b2 t Log_Read_Startup()
|
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&)
|
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||||
000000b7 b compass
|
000000b7 b compass
|
||||||
000000bc t Log_Read_Control_Tuning()
|
000000bc t Log_Read_Control_Tuning()
|
||||||
|
000000be t update_events()
|
||||||
000000c0 t report_throttle()
|
000000c0 t report_throttle()
|
||||||
000000c0 t calc_bearing_error()
|
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*)
|
000000c6 t test_eedump(unsigned char, Menu::arg const*)
|
||||||
|
000000c6 t zero_airspeed()
|
||||||
|
000000c6 t startup_ground()
|
||||||
000000c7 B dcm
|
000000c7 B dcm
|
||||||
|
000000ca t send_radio_out(mavlink_channel_t)
|
||||||
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
|
000000ca t test_modeswitch(unsigned char, Menu::arg const*)
|
||||||
000000ca t control_failsafe(unsigned int)
|
000000ca t control_failsafe(unsigned int)
|
||||||
000000ce t zero_airspeed()
|
000000ce t send_radio_in(mavlink_channel_t)
|
||||||
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
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 setup_mode(unsigned char, Menu::arg const*)::__c
|
||||||
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
||||||
000000d0 t get_bearing(Location*, Location*)
|
000000d0 t get_bearing(Location*, Location*)
|
||||||
000000da t verify_nav_wp()
|
000000d4 t trim_radio()
|
||||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
|
||||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||||
000000e7 r init_ardupilot()::__c
|
000000e7 r init_ardupilot()::__c
|
||||||
000000ec t dump_log(unsigned char, Menu::arg const*)
|
000000ec t dump_log(unsigned char, Menu::arg const*)
|
||||||
000000f0 t throttle_slew_limit()
|
000000f0 t throttle_slew_limit()
|
||||||
000000f2 t test_adc(unsigned char, Menu::arg const*)
|
000000f2 t test_adc(unsigned char, Menu::arg const*)
|
||||||
000000f4 t _mav_finalize_message_chan_send
|
|
||||||
000000fa t Log_Read_Current()
|
000000fa t Log_Read_Current()
|
||||||
00000100 t trim_radio()
|
|
||||||
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
||||||
00000106 t test_current(unsigned char, Menu::arg const*)
|
00000106 t test_current(unsigned char, Menu::arg const*)
|
||||||
00000106 t calc_nav_pitch()
|
00000106 t calc_nav_pitch()
|
||||||
00000106 t get_wp_with_index(int)
|
|
||||||
00000108 t test_battery(unsigned char, Menu::arg const*)
|
00000108 t test_battery(unsigned char, Menu::arg const*)
|
||||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
0000010a t mavlink_delay(unsigned long)
|
||||||
|
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||||
00000110 t test_radio(unsigned char, Menu::arg const*)
|
00000110 t test_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000110 t get_cmd_with_index(int)
|
||||||
00000112 t get_distance(Location*, Location*)
|
00000112 t get_distance(Location*, Location*)
|
||||||
00000112 t startup_ground()
|
00000112 t send_servo_out(mavlink_channel_t)
|
||||||
00000112 t report_batt_monitor()
|
00000112 t report_batt_monitor()
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000114 t read_barometer()
|
00000114 t read_barometer()
|
||||||
00000116 t erase_logs(unsigned char, Menu::arg const*)
|
00000116 t erase_logs(unsigned char, Menu::arg const*)
|
||||||
00000118 t test_gps(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*)
|
00000120 t test_pressure(unsigned char, Menu::arg const*)
|
||||||
00000130 t test_dipswitches(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 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||||
|
00000130 t set_cmd_with_index(Location, int)
|
||||||
00000130 r test_menu_commands
|
00000130 r test_menu_commands
|
||||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||||
0000013e t process_may()
|
|
||||||
0000013e t calc_nav_roll()
|
0000013e t calc_nav_roll()
|
||||||
|
0000013e t handle_process_condition_command()
|
||||||
00000146 t select_logs(unsigned char, Menu::arg const*)
|
00000146 t select_logs(unsigned char, Menu::arg const*)
|
||||||
0000014e t verify_may()
|
00000146 t send_vfr_hud(mavlink_channel_t)
|
||||||
0000014e T GCS_MAVLINK::update()
|
|
||||||
00000152 t report_gains()
|
00000152 t report_gains()
|
||||||
|
00000152 t verify_condition_command()
|
||||||
0000015a t test_airspeed(unsigned char, Menu::arg const*)
|
0000015a t test_airspeed(unsigned char, Menu::arg const*)
|
||||||
|
0000015e t set_guided_WP()
|
||||||
|
0000015e t handle_process_nav_cmd()
|
||||||
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
||||||
0000016a t process_must()
|
0000016c t navigate()
|
||||||
0000016a t set_guided_WP()
|
0000016e t send_attitude(mavlink_channel_t)
|
||||||
00000172 t navigate()
|
|
||||||
00000174 t report_compass()
|
00000174 t report_compass()
|
||||||
|
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
0000017c t send_location(mavlink_channel_t)
|
||||||
0000017e t Log_Read_Nav_Tuning()
|
0000017e t Log_Read_Nav_Tuning()
|
||||||
000001a2 t test_imu(unsigned char, Menu::arg const*)
|
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||||
000001ae T init_home()
|
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||||
|
00000192 T init_home()
|
||||||
|
00000192 t test_imu(unsigned char, Menu::arg const*)
|
||||||
|
000001ae t start_new_log(unsigned char)
|
||||||
000001b2 t update_crosstrack()
|
000001b2 t update_crosstrack()
|
||||||
|
000001b2 t set_mode(unsigned char)
|
||||||
|
000001bc t set_next_WP(Location*)
|
||||||
|
000001bc t send_nav_controller_output(mavlink_channel_t)
|
||||||
000001be t Log_Read_GPS()
|
000001be t Log_Read_GPS()
|
||||||
000001c8 t read_airspeed()
|
000001c0 t read_airspeed()
|
||||||
000001ca t mavlink_delay(unsigned long)
|
000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
000001ca t start_new_log(unsigned char)
|
000001d2 T GCS_MAVLINK::update()
|
||||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
|
||||||
000001ec t init_barometer()
|
000001ea t init_barometer()
|
||||||
00000202 t test_failsafe(unsigned char, Menu::arg const*)
|
00000202 t test_failsafe(unsigned char, Menu::arg const*)
|
||||||
00000206 t set_next_WP(Location*)
|
|
||||||
00000208 t calc_throttle()
|
00000208 t calc_throttle()
|
||||||
00000226 t Log_Read(int, int)
|
00000216 t Log_Read(int, int)
|
||||||
|
0000021a t send_raw_imu1(mavlink_channel_t)
|
||||||
|
0000022a t send_gps_raw(mavlink_channel_t)
|
||||||
|
0000022c t process_next_command()
|
||||||
0000022c t test_wp(unsigned char, Menu::arg const*)
|
0000022c t test_wp(unsigned char, Menu::arg const*)
|
||||||
0000022c t set_mode(unsigned char)
|
00000230 t verify_nav_command()
|
||||||
00000232 t verify_must()
|
|
||||||
0000023e t print_radio_values()
|
0000023e t print_radio_values()
|
||||||
0000024c t update_loiter()
|
0000024c t update_loiter()
|
||||||
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000268 t send_raw_imu3(mavlink_channel_t)
|
||||||
000002e4 t read_radio()
|
000002e4 t read_radio()
|
||||||
0000031e t read_battery()
|
0000031e t test_mag(unsigned char, Menu::arg const*)
|
||||||
0000032e t test_mag(unsigned char, Menu::arg const*)
|
|
||||||
0000033a W Parameters::~Parameters()
|
0000033a W Parameters::~Parameters()
|
||||||
00000404 t process_next_command()
|
00000382 t handle_process_do_command()
|
||||||
0000041c t set_servos()
|
000003e6 t read_battery()
|
||||||
0000044c t print_log_menu()
|
0000044c t print_log_menu()
|
||||||
000004b2 t mavlink_parse_char
|
000004de t set_servos()
|
||||||
0000059c t __static_initialization_and_destruction_0(int, int)
|
0000059c t __static_initialization_and_destruction_0(int, int)
|
||||||
000006da t init_ardupilot()
|
0000064a t init_ardupilot()
|
||||||
00000831 b g
|
00000920 W Parameters::Parameters()
|
||||||
0000090a W Parameters::Parameters()
|
0000092b b g
|
||||||
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||||
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
00001be4 T loop
|
||||||
00001ae8 T loop
|
|
||||||
|
|
|
@ -3,11 +3,13 @@
|
||||||
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
|
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: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
|
/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
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
|
||||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
|
||||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
|
||||||
%% libraries/APM_BMP085/APM_BMP085.o
|
%% libraries/APM_BMP085/APM_BMP085.o
|
||||||
|
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||||
%% libraries/APM_RC/APM_RC.o
|
%% libraries/APM_RC/APM_RC.o
|
||||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||||
%% libraries/AP_ADC/AP_ADC.o
|
%% libraries/AP_ADC/AP_ADC.o
|
||||||
|
@ -35,11 +37,17 @@ autogenerated:126: warning: 'void low_battery_event()' declared 'static' but nev
|
||||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||||
%% libraries/AP_GPS/GPS.o
|
%% libraries/AP_GPS/GPS.o
|
||||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||||
|
%% libraries/AP_Mount/AP_Mount.o
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||||
|
%% libraries/AP_Relay/AP_Relay.o
|
||||||
%% libraries/DataFlash/DataFlash.o
|
%% libraries/DataFlash/DataFlash.o
|
||||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
|
||||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
/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
|
/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/BetterStream.o
|
||||||
|
@ -48,6 +56,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
||||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||||
%% libraries/ModeFilter/ModeFilter.o
|
%% libraries/ModeFilter/ModeFilter.o
|
||||||
%% libraries/PID/PID.o
|
%% libraries/PID/PID.o
|
||||||
|
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||||
%% libraries/RC_Channel/RC_Channel.o
|
%% libraries/RC_Channel/RC_Channel.o
|
||||||
%% libraries/memcheck/memcheck.o
|
%% libraries/memcheck/memcheck.o
|
||||||
%% libraries/FastSerial/ftoa_engine.o
|
%% libraries/FastSerial/ftoa_engine.o
|
||||||
|
|
|
@ -3,20 +3,21 @@
|
||||||
00000001 b home_is_set
|
00000001 b home_is_set
|
||||||
00000001 b ch3_failsafe
|
00000001 b ch3_failsafe
|
||||||
00000001 b land_complete
|
00000001 b land_complete
|
||||||
00000001 b command_may_ID
|
00000001 b mavlink_active
|
||||||
00000001 b command_must_ID
|
00000001 b nav_command_ID
|
||||||
00000001 b failsafeCounter
|
00000001 b failsafeCounter
|
||||||
00000001 b counter_one_herz
|
00000001 b counter_one_herz
|
||||||
00000001 b in_mavlink_delay
|
00000001 b in_mavlink_delay
|
||||||
00000001 b slow_loopCounter
|
00000001 b slow_loopCounter
|
||||||
00000001 d takeoff_complete
|
00000001 d takeoff_complete
|
||||||
00000001 b command_may_index
|
00000001 b nav_command_index
|
||||||
00000001 b command_must_index
|
|
||||||
00000001 b delta_ms_fast_loop
|
00000001 b delta_ms_fast_loop
|
||||||
00000001 d ground_start_count
|
00000001 d ground_start_count
|
||||||
00000001 b medium_loopCounter
|
00000001 b medium_loopCounter
|
||||||
|
00000001 b non_nav_command_ID
|
||||||
00000001 b rc_override_active
|
00000001 b rc_override_active
|
||||||
00000001 b delta_ms_medium_loop
|
00000001 b delta_ms_medium_loop
|
||||||
|
00000001 b non_nav_command_index
|
||||||
00000001 b superslow_loopCounter
|
00000001 b superslow_loopCounter
|
||||||
00000001 b event_id
|
00000001 b event_id
|
||||||
00000001 b GPS_light
|
00000001 b GPS_light
|
||||||
|
@ -25,12 +26,10 @@
|
||||||
00000001 D control_mode
|
00000001 D control_mode
|
||||||
00000001 B hindex
|
00000001 B hindex
|
||||||
00000001 B inverted_flight
|
00000001 B inverted_flight
|
||||||
00000001 B mavdelay
|
|
||||||
00000001 B n
|
00000001 B n
|
||||||
00000001 B oldSwitchPosition
|
00000001 B oldSwitchPosition
|
||||||
|
00000001 B relay
|
||||||
00000002 T ReadSCP1000()
|
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 loiter_sum
|
||||||
00000002 b event_delay
|
00000002 b event_delay
|
||||||
00000002 b event_value
|
00000002 b event_value
|
||||||
|
@ -50,7 +49,6 @@
|
||||||
00000002 b event_undo_value
|
00000002 b event_undo_value
|
||||||
00000002 b ground_start_avg
|
00000002 b ground_start_avg
|
||||||
00000002 b airspeed_pressure
|
00000002 b airspeed_pressure
|
||||||
00000002 b adc
|
|
||||||
00000002 r comma
|
00000002 r comma
|
||||||
00000002 b g_gps
|
00000002 b g_gps
|
||||||
00000002 b pmTest1
|
00000002 b pmTest1
|
||||||
|
@ -60,7 +58,6 @@
|
||||||
00000002 d ch2_temp
|
00000002 d ch2_temp
|
||||||
00000002 b failsafe
|
00000002 b failsafe
|
||||||
00000002 b sonar_alt
|
00000002 b sonar_alt
|
||||||
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
|
|
||||||
00000002 r print_divider()::__c
|
00000002 r print_divider()::__c
|
||||||
00000002 d throttle_slew_limit()::last
|
00000002 d throttle_slew_limit()::last
|
||||||
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
00000002 r test_gps(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -72,6 +69,7 @@
|
||||||
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
00000003 r print_log_menu()::__c
|
00000003 r print_log_menu()::__c
|
||||||
00000003 r report_compass()::__c
|
00000003 r report_compass()::__c
|
||||||
|
00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
00000004 b event_timer
|
00000004 b event_timer
|
||||||
00000004 d hold_course
|
00000004 d hold_course
|
||||||
00000004 b loiter_time
|
00000004 b loiter_time
|
||||||
|
@ -82,6 +80,7 @@
|
||||||
00000004 b airspeed_raw
|
00000004 b airspeed_raw
|
||||||
00000004 b current_amps
|
00000004 b current_amps
|
||||||
00000004 b energy_error
|
00000004 b energy_error
|
||||||
|
00000004 b airspeed_fbwB
|
||||||
00000004 b bearing_error
|
00000004 b bearing_error
|
||||||
00000004 b current_total
|
00000004 b current_total
|
||||||
00000004 b nav_loopTimer
|
00000004 b nav_loopTimer
|
||||||
|
@ -123,8 +122,6 @@
|
||||||
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_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 b mavlink_delay(unsigned long)::last_50hz
|
||||||
00000004 r print_enabled(bool)::__c
|
00000004 r print_enabled(bool)::__c
|
||||||
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -214,14 +211,14 @@
|
||||||
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
|
||||||
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
|
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
|
0000000a r init_home()::__c
|
||||||
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000a r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
|
0000000a r verify_nav_wp()::__c
|
||||||
0000000a r report_compass()::__c
|
0000000a r report_compass()::__c
|
||||||
0000000a r report_throttle()::__c
|
0000000a r report_throttle()::__c
|
||||||
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
0000000a r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -232,31 +229,30 @@
|
||||||
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 RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a V Parameters::Parameters()::__c
|
0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a T setup
|
0000000a T setup
|
||||||
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
|
||||||
0000000b r report_gains()::__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 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
|
||||||
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 process_logs(unsigned char, Menu::arg const*)
|
||||||
0000000c T GCS_MAVLINK::send_text(unsigned char, char const*)
|
0000000c T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||||
0000000c V vtable for IMU
|
0000000c V vtable for IMU
|
||||||
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
0000000c r setup_show(unsigned char, Menu::arg const*)::__c
|
||||||
0000000c r report_xtrack()::__c
|
0000000c r report_xtrack()::__c
|
||||||
0000000c r test_modeswitch(unsigned char, Menu::arg const*)::__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 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
|
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
|
||||||
|
0000000c V Parameters::Parameters()::__c
|
||||||
0000000d r init_home()::__c
|
0000000d r init_home()::__c
|
||||||
0000000d r verify_RTL()::__c
|
0000000d r verify_RTL()::__c
|
||||||
0000000d r demo_servos(unsigned char)::__c
|
0000000d r demo_servos(unsigned char)::__c
|
||||||
|
@ -267,6 +263,9 @@
|
||||||
0000000d r print_log_menu()::__c
|
0000000d r print_log_menu()::__c
|
||||||
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
0000000d r test_modeswitch(unsigned char, Menu::arg const*)::__c
|
||||||
0000000d r Log_Read_Startup()::__c
|
0000000d r Log_Read_Startup()::__c
|
||||||
|
0000000d r control_failsafe(unsigned int)::__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
|
||||||
|
@ -287,6 +286,7 @@
|
||||||
0000000d B sonar_mode_filter
|
0000000d B sonar_mode_filter
|
||||||
0000000e t global destructors keyed to Serial
|
0000000e t global destructors keyed to Serial
|
||||||
0000000e t global constructors keyed to Serial
|
0000000e t global constructors keyed to Serial
|
||||||
|
0000000e t send_statustext(mavlink_channel_t)
|
||||||
0000000e V vtable for AP_Float16
|
0000000e V vtable for AP_Float16
|
||||||
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
0000000e V vtable for AP_VarA<float, (unsigned char)6>
|
||||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||||
|
@ -296,10 +296,10 @@
|
||||||
0000000e V vtable for AP_VarT<int>
|
0000000e V vtable for AP_VarT<int>
|
||||||
0000000e V vtable for AP_VarT<long>
|
0000000e V vtable for AP_VarT<long>
|
||||||
0000000e r erase_logs(unsigned char, Menu::arg const*)::__c
|
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 select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_gains()::__c
|
0000000e r report_gains()::__c
|
||||||
0000000e r print_log_menu()::__c
|
0000000e r print_log_menu()::__c
|
||||||
|
0000000e r control_failsafe(unsigned int)::__c
|
||||||
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
|
||||||
0000000e r report_batt_monitor()::__c
|
0000000e r report_batt_monitor()::__c
|
||||||
0000000e r report_flight_modes()::__c
|
0000000e r report_flight_modes()::__c
|
||||||
|
@ -325,23 +325,26 @@
|
||||||
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 current_loc
|
||||||
0000000f b next_command
|
0000000f b next_nav_command
|
||||||
|
0000000f b next_nonnav_command
|
||||||
0000000f b home
|
0000000f b home
|
||||||
0000000f b next_WP
|
0000000f b next_WP
|
||||||
0000000f b prev_WP
|
0000000f b prev_WP
|
||||||
0000000f b guided_WP
|
0000000f b guided_WP
|
||||||
0000000f r report_gains()::__c
|
0000000f r report_gains()::__c
|
||||||
0000000f r print_log_menu()::__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 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 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 Parameters::Parameters()::__c
|
||||||
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c
|
||||||
00000010 b rc_override
|
00000010 b rc_override
|
||||||
00000010 r planner_menu_commands
|
00000010 r planner_menu_commands
|
||||||
|
00000010 r __menu_name__main_menu
|
||||||
|
00000010 T GCS_MAVLINK::send_message(ap_message)
|
||||||
00000010 W AP_VarT<float>::cast_to_float() const
|
00000010 W AP_VarT<float>::cast_to_float() const
|
||||||
00000010 W AP_VarT<long>::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 setup_radio(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -349,17 +352,17 @@
|
||||||
00000010 r Log_Read_Startup()::__c
|
00000010 r Log_Read_Startup()::__c
|
||||||
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000010 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000010 r dump_log(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 erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r set_next_WP(Location*)::__c
|
|
||||||
00000011 r zero_eeprom()::__c
|
00000011 r zero_eeprom()::__c
|
||||||
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c
|
||||||
00000011 r startup_ground()::__c
|
00000011 r startup_ground()::__c
|
||||||
00000011 r Log_Read_Attitude()::__c
|
00000011 r Log_Read_Attitude()::__c
|
||||||
00000011 r load_next_command_from_EEPROM()::__c
|
00000011 r process_next_command()::__c
|
||||||
|
00000011 r failsafe_short_on_event()::__c
|
||||||
00000012 B Serial
|
00000012 B Serial
|
||||||
00000012 B Serial1
|
00000012 B Serial1
|
||||||
00000012 B Serial3
|
00000012 B Serial3
|
||||||
|
00000012 t gcs_update()
|
||||||
00000012 W AP_Float16::~AP_Float16()
|
00000012 W AP_Float16::~AP_Float16()
|
||||||
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000012 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
|
@ -372,6 +375,7 @@
|
||||||
00000012 r print_done()::__c
|
00000012 r print_done()::__c
|
||||||
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
00000012 r select_logs(unsigned char, Menu::arg const*)::__c
|
||||||
00000012 r init_barometer()::__c
|
00000012 r init_barometer()::__c
|
||||||
|
00000012 r handle_no_commands()::__c
|
||||||
00000012 r startup_IMU_ground()::__c
|
00000012 r startup_IMU_ground()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
00000012 r report_batt_monitor()::__c
|
00000012 r report_batt_monitor()::__c
|
||||||
|
@ -391,11 +395,11 @@
|
||||||
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int)
|
||||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||||
00000014 W AP_VarT<int>::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_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000014 r test_imu(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 map_baudrate(signed char, unsigned long)::__c
|
||||||
00000015 r report_gains()::__c
|
00000015 r report_gains()::__c
|
||||||
|
00000015 r verify_nav_wp()::__c
|
||||||
00000015 r init_ardupilot()::__c
|
00000015 r init_ardupilot()::__c
|
||||||
00000015 r print_hit_enter()::__c
|
00000015 r print_hit_enter()::__c
|
||||||
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
00000015 r test_gyro(unsigned char, Menu::arg const*)::__c
|
||||||
|
@ -403,20 +407,18 @@
|
||||||
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000016 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r report_batt_monitor()::__c
|
00000016 r report_batt_monitor()::__c
|
||||||
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
00000016 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000016 r GCS_MAVLINK::update()::__c
|
|
||||||
00000016 B sonar
|
00000016 B sonar
|
||||||
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000017 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000017 r test_pressure(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
|
00000017 r test_wp(unsigned char, Menu::arg const*)::__c
|
||||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
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 report_compass()::__c
|
||||||
00000018 r Log_Read_Startup()::__c
|
00000018 r Log_Read_Startup()::__c
|
||||||
00000019 r report_batt_monitor()::__c
|
00000019 r report_batt_monitor()::__c
|
||||||
00000019 r failsafe_long_on_event()::__c
|
00000019 r failsafe_long_on_event()::__c
|
||||||
00000019 r GCS_MAVLINK::update()::__c
|
00000019 r handle_process_nav_cmd()::__c
|
||||||
0000001a r reset_control_switch()::__c
|
00000019 r handle_process_do_command()::__c
|
||||||
|
00000019 r handle_process_condition_command()::__c
|
||||||
0000001a r failsafe_short_on_event()::__c
|
0000001a r failsafe_short_on_event()::__c
|
||||||
0000001a r Log_Read(int, int)::__c
|
0000001a r Log_Read(int, int)::__c
|
||||||
0000001b r failsafe_short_off_event()::__c
|
0000001b r failsafe_short_off_event()::__c
|
||||||
|
@ -434,20 +436,23 @@
|
||||||
0000001d r startup_ground()::__c
|
0000001d r startup_ground()::__c
|
||||||
0000001d r report_batt_monitor()::__c
|
0000001d r report_batt_monitor()::__c
|
||||||
0000001e r flight_mode_strings
|
0000001e r flight_mode_strings
|
||||||
0000001e t failsafe_short_off_event()
|
|
||||||
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
0000001e r startup_ground()::__c
|
0000001e r startup_ground()::__c
|
||||||
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
0000001f r setup_compass(unsigned char, Menu::arg const*)::__c
|
||||||
0000001f r init_ardupilot()::__c
|
0000001f r init_ardupilot()::__c
|
||||||
|
0000001f r Log_Read(int, int)::__c
|
||||||
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
0000001f r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000020 t gcs_send_message(ap_message)
|
||||||
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
00000020 r test_current(unsigned char, Menu::arg const*)::__c
|
||||||
00000020 r report_xtrack()::__c
|
00000020 r report_xtrack()::__c
|
||||||
00000020 r init_barometer()::__c
|
00000020 r init_barometer()::__c
|
||||||
00000020 r Log_Read(int, int)::__c
|
|
||||||
00000020 t byte_swap_4
|
00000020 t byte_swap_4
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
00000021 r print_log_menu()::__c
|
00000021 r print_log_menu()::__c
|
||||||
|
00000021 r verify_loiter_time()::__c
|
||||||
|
00000021 r process_next_command()::__c
|
||||||
00000022 t print_blanks(int)
|
00000022 t print_blanks(int)
|
||||||
|
00000022 t failsafe_short_off_event()
|
||||||
00000022 t reset_I()
|
00000022 t reset_I()
|
||||||
00000022 W AP_Float16::~AP_Float16()
|
00000022 W AP_Float16::~AP_Float16()
|
||||||
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
00000022 W AP_VarA<float, (unsigned char)6>::~AP_VarA()
|
||||||
|
@ -459,23 +464,22 @@
|
||||||
00000022 W AP_VarT<long>::~AP_VarT()
|
00000022 W AP_VarT<long>::~AP_VarT()
|
||||||
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000022 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000022 r report_compass()::__c
|
00000022 r report_compass()::__c
|
||||||
00000022 r increment_WP_index()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000022 r verify_loiter_time()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
00000023 r test_pressure(unsigned char, Menu::arg const*)::__c
|
||||||
00000023 r print_gyro_offsets()::__c
|
00000023 r print_gyro_offsets()::__c
|
||||||
|
00000023 r verify_loiter_turns()::__c
|
||||||
00000023 r navigate()::__c
|
00000023 r navigate()::__c
|
||||||
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000024 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
00000024 r print_accel_offsets()::__c
|
00000024 r print_accel_offsets()::__c
|
||||||
00000024 r verify_loiter_turns()::__c
|
|
||||||
00000026 t print_done()
|
00000026 t print_done()
|
||||||
00000026 b mavlink_queue
|
|
||||||
00000026 t print_hit_enter()
|
00000026 t print_hit_enter()
|
||||||
00000026 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
|
00000026 r init_ardupilot()::__c
|
||||||
00000026 r print_PID(PID*)::__c
|
00000026 r print_PID(PID*)::__c
|
||||||
00000027 r init_ardupilot()::__c
|
00000027 r change_command(unsigned char)::__c
|
||||||
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
00000027 r test_xbee(unsigned char, Menu::arg const*)::__c
|
||||||
00000028 t main_menu_help(unsigned char, Menu::arg const*)
|
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 t help_log(unsigned char, Menu::arg const*)
|
||||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||||
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<long>::unserialize(void*, unsigned int)
|
||||||
|
@ -485,71 +489,75 @@
|
||||||
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
0000002a t setup_declination(unsigned char, Menu::arg const*)
|
||||||
0000002a r init_ardupilot()::__c
|
0000002a r init_ardupilot()::__c
|
||||||
0000002a r startup_ground()::__c
|
0000002a r startup_ground()::__c
|
||||||
0000002b r verify_must()::__c
|
0000002a r verify_nav_command()::__c
|
||||||
|
0000002a t _mav_put_int8_t_array
|
||||||
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
0000002b r test_battery(unsigned char, Menu::arg const*)::__c
|
||||||
0000002b r change_command(unsigned char)::__c
|
0000002b r change_command(unsigned char)::__c
|
||||||
0000002c t freeRAM()
|
|
||||||
0000002d r startup_IMU_ground()::__c
|
0000002d r startup_IMU_ground()::__c
|
||||||
0000002e t reset_control_switch()
|
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
|
||||||
0000002e t send_rate(unsigned int, unsigned int)
|
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
|
||||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
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 setup_mode(unsigned char, Menu::arg const*)
|
||||||
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
00000030 t planner_mode(unsigned char, Menu::arg const*)
|
||||||
|
00000030 t send_heartbeat(mavlink_channel_t)
|
||||||
00000030 t test_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
|
00000030 r print_log_menu()::__c
|
||||||
00000031 r start_new_log(unsigned char)::__c
|
00000031 r start_new_log(unsigned char)::__c
|
||||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||||
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000033 b pending_status
|
||||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||||
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
00000034 r test_radio(unsigned char, Menu::arg const*)::__c
|
||||||
00000034 t _mav_put_int8_t_array
|
00000034 t mavlink_msg_statustext_send
|
||||||
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
|
||||||
00000035 r Log_Read_Nav_Tuning()::__c
|
00000035 r Log_Read_Nav_Tuning()::__c
|
||||||
|
00000035 r verify_condition_command()::__c
|
||||||
00000036 t report_radio()
|
00000036 t report_radio()
|
||||||
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c
|
||||||
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
00000037 r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000038 t send_current_waypoint(mavlink_channel_t)
|
||||||
|
00000038 b barometer
|
||||||
00000038 r test_dipswitches(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
|
00000038 r dump_log(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r setup_radio(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 planner_mode(unsigned char, Menu::arg const*)::__c
|
||||||
00000039 r init_ardupilot()::__c
|
00000039 r init_ardupilot()::__c
|
||||||
0000003a t report_imu()
|
0000003a t report_imu()
|
||||||
|
0000003a t verify_loiter_turns()
|
||||||
0000003a W PID::~PID()
|
0000003a W PID::~PID()
|
||||||
|
0000003c t verify_RTL()
|
||||||
0000003c t Log_Write_Mode(unsigned char)
|
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_wp_print(Location*, unsigned char)::__c
|
||||||
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
0000003c r test_mag(unsigned char, Menu::arg const*)::__c
|
||||||
0000003d B g_gps_driver
|
0000003d B g_gps_driver
|
||||||
0000003e t verify_RTL()
|
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
|
||||||
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)
|
0000003e W AP_VarT<signed char>::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
00000040 b adc
|
||||||
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
00000040 W AP_Float16::unserialize(void*, unsigned int)
|
||||||
00000040 t byte_swap_8
|
00000040 t byte_swap_8
|
||||||
00000040 t crc_accumulate
|
|
||||||
00000040 B history
|
00000040 B history
|
||||||
00000043 r Log_Read_GPS()::__c
|
00000043 r Log_Read_GPS()::__c
|
||||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||||
00000044 r report_throttle()::__c
|
00000044 r report_throttle()::__c
|
||||||
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
00000045 r erase_logs(unsigned char, Menu::arg const*)::__c
|
||||||
|
00000046 W RC_Channel::~RC_Channel()
|
||||||
|
00000048 t failsafe_long_on_event()
|
||||||
|
0000004a t send_meminfo(mavlink_channel_t)
|
||||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, 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)
|
||||||
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
0000004b r setup_factory(unsigned char, Menu::arg const*)::__c
|
||||||
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
0000004c t setup_erase(unsigned char, Menu::arg const*)
|
||||||
0000004c t Log_Read_Mode()
|
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*)
|
0000004e t setup_batt_monitor(unsigned char, Menu::arg const*)
|
||||||
|
00000050 b mavlink_queue
|
||||||
00000050 r log_menu_commands
|
00000050 r log_menu_commands
|
||||||
00000050 r main_menu_commands
|
00000050 r main_menu_commands
|
||||||
00000050 t failsafe_long_on_event()
|
|
||||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||||
|
00000050 B imu
|
||||||
00000054 t print_divider()
|
00000054 t print_divider()
|
||||||
00000054 t print_enabled(bool)
|
00000054 t print_enabled(bool)
|
||||||
00000054 t report_flight_modes()
|
00000054 t report_flight_modes()
|
||||||
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
|
||||||
00000056 t change_command(unsigned char)
|
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||||
00000058 t radio_input_switch()
|
00000058 t radio_input_switch()
|
||||||
0000005a t update_GPS_light()
|
0000005a t update_GPS_light()
|
||||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
@ -558,142 +566,156 @@
|
||||||
0000005c t get_num_logs()
|
0000005c t get_num_logs()
|
||||||
0000005e T GCS_MAVLINK::_count_parameters()
|
0000005e T GCS_MAVLINK::_count_parameters()
|
||||||
00000060 t print_switch(unsigned char, unsigned char)
|
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 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 Log_Write_Attitude(int, int, unsigned int)
|
||||||
|
00000064 t mavlink_msg_param_value_send(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
|
||||||
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
00000064 t test_xbee(unsigned char, Menu::arg const*)
|
||||||
00000064 t mavlink_msg_param_value_send
|
00000064 W RC_Channel_aux::~RC_Channel_aux()
|
||||||
00000068 t zero_eeprom()
|
00000068 t zero_eeprom()
|
||||||
00000068 t find_last_log_page(int)
|
00000068 t find_last_log_page(int)
|
||||||
|
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
|
||||||
|
0000006a t demo_servos(unsigned char)
|
||||||
|
0000006a t startup_IMU_ground()
|
||||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||||
0000006c t setup_show(unsigned char, Menu::arg const*)
|
0000006c t setup_show(unsigned char, Menu::arg const*)
|
||||||
0000006c t demo_servos(unsigned char)
|
|
||||||
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
0000006e t setup_factory(unsigned char, Menu::arg const*)
|
||||||
00000070 r init_ardupilot()::__c
|
00000070 r init_ardupilot()::__c
|
||||||
00000074 t verify_loiter_time()
|
00000072 t verify_loiter_time()
|
||||||
00000076 t startup_IMU_ground()
|
00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
|
||||||
00000078 t read_control_switch()
|
00000078 t read_control_switch()
|
||||||
0000007c t failsafe_short_on_event()
|
0000007c t send_gps_status(mavlink_channel_t)
|
||||||
|
0000007c t do_RTL()
|
||||||
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
0000007e t test_rawgps(unsigned char, Menu::arg const*)
|
||||||
00000080 r setup_menu_commands
|
00000080 r setup_menu_commands
|
||||||
00000080 T __vector_25
|
00000080 T __vector_25
|
||||||
00000080 T __vector_36
|
00000080 T __vector_36
|
||||||
00000080 T __vector_54
|
00000080 T __vector_54
|
||||||
|
00000084 t change_command(unsigned char)
|
||||||
00000086 t Log_Read_Attitude()
|
00000086 t Log_Read_Attitude()
|
||||||
00000088 t Log_Read_Raw()
|
00000088 t Log_Read_Raw()
|
||||||
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
0000008a t Log_Write_Cmd(unsigned char, Location*)
|
||||||
0000008c t print_gyro_offsets()
|
0000008c t print_gyro_offsets()
|
||||||
0000008c t print_accel_offsets()
|
0000008c t print_accel_offsets()
|
||||||
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
0000008c r main_menu_help(unsigned char, Menu::arg const*)::__c
|
||||||
00000090 t do_RTL()
|
0000008e t failsafe_short_on_event()
|
||||||
|
00000090 t handle_no_commands()
|
||||||
|
00000092 T GCS_MAVLINK::queued_param_send()
|
||||||
00000096 t map_baudrate(signed char, unsigned long)
|
00000096 t map_baudrate(signed char, unsigned long)
|
||||||
00000096 t test_wp_print(Location*, unsigned char)
|
00000096 t test_wp_print(Location*, unsigned char)
|
||||||
0000009c t update_servo_switches()
|
0000009c t update_servo_switches()
|
||||||
0000009c t print_PID(PID*)
|
0000009c t print_PID(PID*)
|
||||||
0000009d B gcs
|
0000009c B gcs0
|
||||||
0000009d B hil
|
0000009c B gcs3
|
||||||
000000a0 t report_xtrack()
|
000000a0 t report_xtrack()
|
||||||
|
000000a2 t verify_nav_wp()
|
||||||
000000a4 t Log_Read_Cmd()
|
000000a4 t Log_Read_Cmd()
|
||||||
000000a4 T __vector_26
|
000000a4 T __vector_26
|
||||||
000000a4 T __vector_37
|
000000a4 T __vector_37
|
||||||
000000a4 T __vector_55
|
000000a4 T __vector_55
|
||||||
|
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
|
||||||
000000ac t Log_Read_Performance()
|
000000ac t Log_Read_Performance()
|
||||||
|
000000b0 t test_relay(unsigned char, Menu::arg const*)
|
||||||
000000b0 t Log_Read_Startup()
|
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&)
|
000000b6 t get_log_boundaries(unsigned char, int&, int&)
|
||||||
000000b7 b compass
|
000000b7 b compass
|
||||||
000000bc t Log_Read_Control_Tuning()
|
000000bc t Log_Read_Control_Tuning()
|
||||||
|
000000be t update_events()
|
||||||
000000c0 t report_throttle()
|
000000c0 t report_throttle()
|
||||||
000000c0 t calc_bearing_error()
|
000000c0 t calc_bearing_error()
|
||||||
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
000000c2 t test_eedump(unsigned char, Menu::arg const*)
|
||||||
000000c4 t update_events()
|
000000c6 t zero_airspeed()
|
||||||
000000c4 t load_next_command_from_EEPROM()
|
000000c6 t startup_ground()
|
||||||
000000c7 B dcm
|
000000c7 B dcm
|
||||||
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
|
000000c8 t test_modeswitch(unsigned char, Menu::arg const*)
|
||||||
|
000000ca t send_radio_out(mavlink_channel_t)
|
||||||
000000ca t control_failsafe(unsigned int)
|
000000ca t control_failsafe(unsigned int)
|
||||||
000000ce t zero_airspeed()
|
000000ce t send_radio_in(mavlink_channel_t)
|
||||||
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
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 setup_mode(unsigned char, Menu::arg const*)::__c
|
||||||
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
000000ce r help_log(unsigned char, Menu::arg const*)::__c
|
||||||
000000d0 t get_bearing(Location*, Location*)
|
000000d0 t get_bearing(Location*, Location*)
|
||||||
000000d8 t verify_nav_wp()
|
000000d4 t trim_radio()
|
||||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
|
||||||
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
|
||||||
000000e7 r init_ardupilot()::__c
|
000000e7 r init_ardupilot()::__c
|
||||||
000000ec t dump_log(unsigned char, Menu::arg const*)
|
000000ec t dump_log(unsigned char, Menu::arg const*)
|
||||||
000000f0 t throttle_slew_limit()
|
000000f0 t throttle_slew_limit()
|
||||||
000000f0 t test_adc(unsigned char, Menu::arg const*)
|
000000f0 t test_adc(unsigned char, Menu::arg const*)
|
||||||
000000f4 t _mav_finalize_message_chan_send
|
|
||||||
000000fa t Log_Read_Current()
|
000000fa t Log_Read_Current()
|
||||||
00000100 t trim_radio()
|
|
||||||
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
00000102 t setup_compass(unsigned char, Menu::arg const*)
|
||||||
00000106 t test_current(unsigned char, Menu::arg const*)
|
00000106 t test_current(unsigned char, Menu::arg const*)
|
||||||
00000106 t calc_nav_pitch()
|
00000106 t calc_nav_pitch()
|
||||||
00000106 t get_wp_with_index(int)
|
|
||||||
00000108 t test_battery(unsigned char, Menu::arg const*)
|
00000108 t test_battery(unsigned char, Menu::arg const*)
|
||||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
0000010a t mavlink_delay(unsigned long)
|
||||||
|
0000010a t send_raw_imu2(mavlink_channel_t)
|
||||||
00000110 t test_radio(unsigned char, Menu::arg const*)
|
00000110 t test_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000110 t get_cmd_with_index(int)
|
||||||
00000112 t get_distance(Location*, Location*)
|
00000112 t get_distance(Location*, Location*)
|
||||||
00000112 t startup_ground()
|
00000112 t send_servo_out(mavlink_channel_t)
|
||||||
00000112 t report_batt_monitor()
|
00000112 t report_batt_monitor()
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
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 erase_logs(unsigned char, Menu::arg const*)
|
||||||
00000114 t read_barometer()
|
00000114 t read_barometer()
|
||||||
00000118 t test_gps(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*)
|
00000120 t test_pressure(unsigned char, Menu::arg const*)
|
||||||
00000130 t test_dipswitches(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 t setup_flightmodes(unsigned char, Menu::arg const*)
|
||||||
|
00000130 t set_cmd_with_index(Location, int)
|
||||||
00000130 r test_menu_commands
|
00000130 r test_menu_commands
|
||||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||||
0000013e t process_may()
|
|
||||||
0000013e t calc_nav_roll()
|
0000013e t calc_nav_roll()
|
||||||
|
0000013e t handle_process_condition_command()
|
||||||
00000146 t select_logs(unsigned char, Menu::arg const*)
|
00000146 t select_logs(unsigned char, Menu::arg const*)
|
||||||
0000014e t verify_may()
|
00000146 t send_vfr_hud(mavlink_channel_t)
|
||||||
0000014e T GCS_MAVLINK::update()
|
|
||||||
00000152 t report_gains()
|
00000152 t report_gains()
|
||||||
|
00000152 t verify_condition_command()
|
||||||
00000158 t test_airspeed(unsigned char, Menu::arg const*)
|
00000158 t test_airspeed(unsigned char, Menu::arg const*)
|
||||||
|
0000015e t set_guided_WP()
|
||||||
|
0000015e t handle_process_nav_cmd()
|
||||||
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
0000015e t test_gyro(unsigned char, Menu::arg const*)
|
||||||
0000016a t process_must()
|
0000016c t navigate()
|
||||||
0000016a t set_guided_WP()
|
0000016e t send_attitude(mavlink_channel_t)
|
||||||
00000172 t navigate()
|
|
||||||
00000174 t report_compass()
|
00000174 t report_compass()
|
||||||
|
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
0000017c t send_location(mavlink_channel_t)
|
||||||
0000017e t Log_Read_Nav_Tuning()
|
0000017e t Log_Read_Nav_Tuning()
|
||||||
000001a2 t test_imu(unsigned char, Menu::arg const*)
|
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||||
000001ae T init_home()
|
0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||||
|
00000190 T init_home()
|
||||||
|
00000192 t test_imu(unsigned char, Menu::arg const*)
|
||||||
|
000001ae t start_new_log(unsigned char)
|
||||||
000001b2 t update_crosstrack()
|
000001b2 t update_crosstrack()
|
||||||
|
000001b2 t set_mode(unsigned char)
|
||||||
|
000001bc t set_next_WP(Location*)
|
||||||
|
000001bc t send_nav_controller_output(mavlink_channel_t)
|
||||||
000001be t Log_Read_GPS()
|
000001be t Log_Read_GPS()
|
||||||
000001c8 t read_airspeed()
|
000001c0 t read_airspeed()
|
||||||
000001ca t mavlink_delay(unsigned long)
|
000001d2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
000001ca t start_new_log(unsigned char)
|
000001d2 T GCS_MAVLINK::update()
|
||||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
|
||||||
000001ec t init_barometer()
|
000001ea t init_barometer()
|
||||||
000001fe t test_failsafe(unsigned char, Menu::arg const*)
|
000001fe t test_failsafe(unsigned char, Menu::arg const*)
|
||||||
00000206 t set_next_WP(Location*)
|
|
||||||
00000208 t calc_throttle()
|
00000208 t calc_throttle()
|
||||||
00000222 t Log_Read(int, int)
|
00000210 t Log_Read(int, int)
|
||||||
|
0000021a t send_raw_imu1(mavlink_channel_t)
|
||||||
00000228 t test_wp(unsigned char, Menu::arg const*)
|
00000228 t test_wp(unsigned char, Menu::arg const*)
|
||||||
0000022c t set_mode(unsigned char)
|
0000022a t send_gps_raw(mavlink_channel_t)
|
||||||
00000232 t verify_must()
|
0000022c t process_next_command()
|
||||||
|
00000230 t verify_nav_command()
|
||||||
0000023e t print_radio_values()
|
0000023e t print_radio_values()
|
||||||
0000024c t update_loiter()
|
0000024c t update_loiter()
|
||||||
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
0000025c t setup_radio(unsigned char, Menu::arg const*)
|
||||||
|
00000268 t send_raw_imu3(mavlink_channel_t)
|
||||||
000002e4 t read_radio()
|
000002e4 t read_radio()
|
||||||
0000031e t read_battery()
|
0000031e t test_mag(unsigned char, Menu::arg const*)
|
||||||
0000032e t test_mag(unsigned char, Menu::arg const*)
|
|
||||||
0000033a W Parameters::~Parameters()
|
0000033a W Parameters::~Parameters()
|
||||||
00000404 t process_next_command()
|
00000382 t handle_process_do_command()
|
||||||
0000041c t set_servos()
|
000003e6 t read_battery()
|
||||||
00000436 t print_log_menu()
|
00000436 t print_log_menu()
|
||||||
000004b2 t mavlink_parse_char
|
000004de t set_servos()
|
||||||
0000059c t __static_initialization_and_destruction_0(int, int)
|
0000059c t __static_initialization_and_destruction_0(int, int)
|
||||||
000006da t init_ardupilot()
|
00000648 t init_ardupilot()
|
||||||
00000831 b g
|
00000920 W Parameters::Parameters()
|
||||||
0000090a W Parameters::Parameters()
|
0000092b b g
|
||||||
0000156a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||||
000018ea t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
00001be4 T loop
|
||||||
00001ae8 T loop
|
|
||||||
|
|
|
@ -3,59 +3,71 @@
|
||||||
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
|
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: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
|
/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
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
|
||||||
autogenerated:28: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
|
||||||
autogenerated:29: warning: 'int find_last_log_page(int)' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
|
||||||
/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/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
|
||||||
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Control_Tuning()' defined but not used
|
autogenerated: At global scope:
|
||||||
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Raw()' defined but not used
|
autogenerated:34: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
|
||||||
autogenerated:40: warning: 'void Log_Read_Current()' declared 'static' but never defined
|
autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
|
||||||
autogenerated:41: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
|
autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
|
||||||
autogenerated:42: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
|
||||||
autogenerated:43: warning: 'void Log_Read_Performance()' declared 'static' but never defined
|
autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined
|
||||||
autogenerated:44: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
|
autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
|
||||||
autogenerated:45: warning: 'void Log_Read_Startup()' declared 'static' but never defined
|
autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined
|
||||||
autogenerated:46: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
|
||||||
autogenerated:47: warning: 'void Log_Read_Mode()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Control_Tuning()' defined but not used
|
||||||
autogenerated:48: warning: 'void Log_Read_GPS()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:748: warning: 'void Log_Write_Raw()' defined but not used
|
||||||
autogenerated:49: warning: 'void Log_Read_Raw()' declared 'static' but never defined
|
autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined
|
||||||
autogenerated:50: warning: 'void Log_Read(int, int)' declared 'static' but never defined
|
autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
|
||||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
|
||||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined
|
||||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
|
||||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined
|
||||||
autogenerated:149: warning: 'void init_barometer()' declared 'static' but never defined
|
autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
|
||||||
autogenerated:150: warning: 'long int read_barometer()' declared 'static' but never defined
|
autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined
|
||||||
autogenerated:152: warning: 'void zero_airspeed()' declared 'static' but never defined
|
autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined
|
||||||
autogenerated:154: warning: 'void report_batt_monitor()' declared 'static' but never defined
|
autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined
|
||||||
autogenerated:155: warning: 'void report_radio()' declared 'static' but never defined
|
autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined
|
||||||
autogenerated:156: warning: 'void report_gains()' declared 'static' but never defined
|
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||||
autogenerated:157: warning: 'void report_xtrack()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
|
||||||
autogenerated:158: warning: 'void report_throttle()' declared 'static' but never defined
|
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||||
autogenerated:159: warning: 'void report_imu()' declared 'static' but never defined
|
autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined
|
||||||
autogenerated:160: warning: 'void report_compass()' declared 'static' but never defined
|
autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||||
autogenerated:161: warning: 'void report_flight_modes()' declared 'static' but never defined
|
autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||||
autogenerated:162: warning: 'void print_PID(PID*)' declared 'static' but never defined
|
autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||||
autogenerated:163: warning: 'void print_radio_values()' declared 'static' but never defined
|
autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined
|
||||||
autogenerated:164: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
|
autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined
|
||||||
autogenerated:165: warning: 'void print_done()' declared 'static' but never defined
|
autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined
|
||||||
autogenerated:166: warning: 'void print_blanks(int)' declared 'static' but never defined
|
autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined
|
||||||
autogenerated:167: warning: 'void print_divider()' declared 'static' but never defined
|
autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined
|
||||||
autogenerated:168: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
|
autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined
|
||||||
autogenerated:169: warning: 'void zero_eeprom()' declared 'static' but never defined
|
autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined
|
||||||
autogenerated:170: warning: 'void print_enabled(bool)' declared 'static' but never defined
|
autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined
|
||||||
autogenerated:171: warning: 'void print_accel_offsets()' declared 'static' but never defined
|
autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined
|
||||||
autogenerated:172: warning: 'void print_gyro_offsets()' declared 'static' but never defined
|
autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined
|
||||||
autogenerated:183: warning: 'void print_hit_enter()' declared 'static' but never defined
|
autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
|
||||||
autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
|
autogenerated:180: warning: 'void print_done()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:210: warning: 'comma' defined but not used
|
autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:212: warning: 'flight_mode_strings' defined but not used
|
autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:317: warning: 'airspeed_raw' defined but not used
|
autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:318: warning: 'airspeed_pressure' defined but not used
|
autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:322: warning: 'abs_pressure' defined but not used
|
autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/Log.pde:742: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
|
autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined
|
||||||
|
autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined
|
||||||
|
autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined
|
||||||
|
autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined
|
||||||
|
autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:743: 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
|
/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_BMP085/APM_BMP085.o
|
||||||
|
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||||
%% libraries/APM_RC/APM_RC.o
|
%% libraries/APM_RC/APM_RC.o
|
||||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||||
%% libraries/AP_ADC/AP_ADC.o
|
%% libraries/AP_ADC/AP_ADC.o
|
||||||
|
@ -83,11 +95,17 @@ autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'stat
|
||||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||||
%% libraries/AP_GPS/GPS.o
|
%% libraries/AP_GPS/GPS.o
|
||||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||||
|
%% libraries/AP_Mount/AP_Mount.o
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||||
|
%% libraries/AP_Relay/AP_Relay.o
|
||||||
%% libraries/DataFlash/DataFlash.o
|
%% libraries/DataFlash/DataFlash.o
|
||||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
|
||||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
/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
|
/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/BetterStream.o
|
||||||
|
@ -96,6 +114,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
||||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||||
%% libraries/ModeFilter/ModeFilter.o
|
%% libraries/ModeFilter/ModeFilter.o
|
||||||
%% libraries/PID/PID.o
|
%% libraries/PID/PID.o
|
||||||
|
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||||
%% libraries/RC_Channel/RC_Channel.o
|
%% libraries/RC_Channel/RC_Channel.o
|
||||||
%% libraries/memcheck/memcheck.o
|
%% libraries/memcheck/memcheck.o
|
||||||
%% libraries/FastSerial/ftoa_engine.o
|
%% libraries/FastSerial/ftoa_engine.o
|
||||||
|
|
|
@ -3,20 +3,21 @@
|
||||||
00000001 b home_is_set
|
00000001 b home_is_set
|
||||||
00000001 b ch3_failsafe
|
00000001 b ch3_failsafe
|
||||||
00000001 b land_complete
|
00000001 b land_complete
|
||||||
00000001 b command_may_ID
|
00000001 b mavlink_active
|
||||||
00000001 b command_must_ID
|
00000001 b nav_command_ID
|
||||||
00000001 b failsafeCounter
|
00000001 b failsafeCounter
|
||||||
00000001 b counter_one_herz
|
00000001 b counter_one_herz
|
||||||
00000001 b in_mavlink_delay
|
00000001 b in_mavlink_delay
|
||||||
00000001 b slow_loopCounter
|
00000001 b slow_loopCounter
|
||||||
00000001 d takeoff_complete
|
00000001 d takeoff_complete
|
||||||
00000001 b command_may_index
|
00000001 b nav_command_index
|
||||||
00000001 b command_must_index
|
|
||||||
00000001 b delta_ms_fast_loop
|
00000001 b delta_ms_fast_loop
|
||||||
00000001 d ground_start_count
|
00000001 d ground_start_count
|
||||||
00000001 b medium_loopCounter
|
00000001 b medium_loopCounter
|
||||||
|
00000001 b non_nav_command_ID
|
||||||
00000001 b rc_override_active
|
00000001 b rc_override_active
|
||||||
00000001 b delta_ms_medium_loop
|
00000001 b delta_ms_medium_loop
|
||||||
|
00000001 b non_nav_command_index
|
||||||
00000001 b superslow_loopCounter
|
00000001 b superslow_loopCounter
|
||||||
00000001 b event_id
|
00000001 b event_id
|
||||||
00000001 b GPS_light
|
00000001 b GPS_light
|
||||||
|
@ -24,11 +25,9 @@
|
||||||
00000001 D control_mode
|
00000001 D control_mode
|
||||||
00000001 B hindex
|
00000001 B hindex
|
||||||
00000001 B inverted_flight
|
00000001 B inverted_flight
|
||||||
00000001 B mavdelay
|
|
||||||
00000001 B n
|
00000001 B n
|
||||||
00000001 B oldSwitchPosition
|
00000001 B oldSwitchPosition
|
||||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
00000001 B relay
|
||||||
00000002 b climb_rate
|
|
||||||
00000002 b loiter_sum
|
00000002 b loiter_sum
|
||||||
00000002 b event_delay
|
00000002 b event_delay
|
||||||
00000002 b event_value
|
00000002 b event_value
|
||||||
|
@ -58,11 +57,11 @@
|
||||||
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
|
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(IMU::Start_style, void (*)(unsigned long))
|
||||||
00000002 W AP_IMU_Shim::init_gyro(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 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
|
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 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
00000004 b event_timer
|
00000004 b event_timer
|
||||||
00000004 d hold_course
|
00000004 d hold_course
|
||||||
00000004 b loiter_time
|
00000004 b loiter_time
|
||||||
|
@ -71,6 +70,7 @@
|
||||||
00000004 b wp_distance
|
00000004 b wp_distance
|
||||||
00000004 b current_amps
|
00000004 b current_amps
|
||||||
00000004 b energy_error
|
00000004 b energy_error
|
||||||
|
00000004 b airspeed_fbwB
|
||||||
00000004 b bearing_error
|
00000004 b bearing_error
|
||||||
00000004 b current_total
|
00000004 b current_total
|
||||||
00000004 b nav_loopTimer
|
00000004 b nav_loopTimer
|
||||||
|
@ -106,8 +106,6 @@
|
||||||
00000004 b nav_roll
|
00000004 b nav_roll
|
||||||
00000004 b nav_pitch
|
00000004 b nav_pitch
|
||||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
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 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 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
|
@ -135,7 +133,6 @@
|
||||||
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
|
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||||
00000008 r __menu_name__planner_menu
|
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 V Parameters::Parameters()::__c
|
00000008 V Parameters::Parameters()::__c
|
||||||
|
@ -149,12 +146,13 @@
|
||||||
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
|
||||||
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
|
||||||
|
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
|
0000000a r init_home()::__c
|
||||||
|
0000000a r verify_nav_wp()::__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
|
||||||
|
@ -162,18 +160,17 @@
|
||||||
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 RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a V Parameters::Parameters()::__c
|
0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a T setup
|
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
|
||||||
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 T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||||
0000000c V vtable for AP_IMU_Shim
|
0000000c V vtable for AP_IMU_Shim
|
||||||
0000000c V vtable for IMU
|
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
|
||||||
0000000c V Parameters::Parameters()::__c
|
0000000c V Parameters::Parameters()::__c
|
||||||
|
@ -182,6 +179,9 @@
|
||||||
0000000d r init_home()::__c
|
0000000d r init_home()::__c
|
||||||
0000000d r verify_RTL()::__c
|
0000000d r verify_RTL()::__c
|
||||||
0000000d r demo_servos(unsigned char)::__c
|
0000000d r demo_servos(unsigned char)::__c
|
||||||
|
0000000d r control_failsafe(unsigned int)::__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
|
||||||
|
@ -202,6 +202,7 @@
|
||||||
0000000d B sonar_mode_filter
|
0000000d B sonar_mode_filter
|
||||||
0000000e t global destructors keyed to Serial
|
0000000e t global destructors keyed to Serial
|
||||||
0000000e t global constructors keyed to Serial
|
0000000e t global constructors keyed to Serial
|
||||||
|
0000000e t send_statustext(mavlink_channel_t)
|
||||||
0000000e V vtable for AP_Float16
|
0000000e V vtable for AP_Float16
|
||||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||||
|
@ -209,7 +210,7 @@
|
||||||
0000000e V vtable for AP_VarT<float>
|
0000000e V vtable for AP_VarT<float>
|
||||||
0000000e V vtable for AP_VarT<int>
|
0000000e V vtable for AP_VarT<int>
|
||||||
0000000e V vtable for AP_VarT<long>
|
0000000e V vtable for AP_VarT<long>
|
||||||
0000000e r process_may()::__c
|
0000000e r control_failsafe(unsigned int)::__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
|
||||||
|
@ -230,12 +231,13 @@
|
||||||
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 current_loc
|
||||||
0000000f b next_command
|
0000000f b next_nav_command
|
||||||
|
0000000f b next_nonnav_command
|
||||||
0000000f b home
|
0000000f b home
|
||||||
0000000f b next_WP
|
0000000f b next_WP
|
||||||
0000000f b prev_WP
|
0000000f b prev_WP
|
||||||
0000000f b guided_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
|
||||||
0000000f V Parameters::Parameters()::__c
|
0000000f V Parameters::Parameters()::__c
|
||||||
|
@ -243,15 +245,16 @@
|
||||||
0000000f V Parameters::Parameters()::__c
|
0000000f V Parameters::Parameters()::__c
|
||||||
00000010 b rc_override
|
00000010 b rc_override
|
||||||
00000010 r planner_menu_commands
|
00000010 r planner_menu_commands
|
||||||
|
00000010 T GCS_MAVLINK::send_message(ap_message)
|
||||||
00000010 W AP_VarT<float>::cast_to_float() const
|
00000010 W AP_VarT<float>::cast_to_float() const
|
||||||
00000010 W AP_VarT<long>::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 startup_ground()::__c
|
||||||
00000011 r load_next_command_from_EEPROM()::__c
|
00000011 r process_next_command()::__c
|
||||||
|
00000011 r failsafe_short_on_event()::__c
|
||||||
00000012 B Serial
|
00000012 B Serial
|
||||||
00000012 B Serial1
|
00000012 B Serial1
|
||||||
00000012 B Serial3
|
00000012 B Serial3
|
||||||
|
00000012 t gcs_update()
|
||||||
00000012 W AP_Float16::~AP_Float16()
|
00000012 W AP_Float16::~AP_Float16()
|
||||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||||
|
@ -260,24 +263,23 @@
|
||||||
00000012 W AP_VarT<int>::~AP_VarT()
|
00000012 W AP_VarT<int>::~AP_VarT()
|
||||||
00000012 W AP_VarT<long>::~AP_VarT()
|
00000012 W AP_VarT<long>::~AP_VarT()
|
||||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||||
|
00000012 r handle_no_commands()::__c
|
||||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
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>::unserialize(void*, unsigned int)
|
||||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||||
00000014 W AP_VarT<int>::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 map_baudrate(signed char, unsigned long)::__c
|
||||||
|
00000015 r verify_nav_wp()::__c
|
||||||
00000015 r init_ardupilot()::__c
|
00000015 r init_ardupilot()::__c
|
||||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||||
00000016 r GCS_MAVLINK::update()::__c
|
00000016 B adc
|
||||||
00000016 B sonar
|
00000016 B sonar
|
||||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
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 failsafe_long_on_event()::__c
|
||||||
00000019 r GCS_MAVLINK::update()::__c
|
00000019 r handle_process_nav_cmd()::__c
|
||||||
|
00000019 r handle_process_do_command()::__c
|
||||||
|
00000019 r handle_process_condition_command()::__c
|
||||||
0000001a t startup_IMU_ground()
|
0000001a t startup_IMU_ground()
|
||||||
0000001a r reset_control_switch()::__c
|
|
||||||
0000001a r failsafe_short_on_event()::__c
|
0000001a r failsafe_short_on_event()::__c
|
||||||
0000001b r failsafe_short_off_event()::__c
|
0000001b r failsafe_short_off_event()::__c
|
||||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||||
|
@ -285,9 +287,12 @@
|
||||||
0000001c W AP_VarT<int>::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<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||||
0000001c W AP_VarS<Vector3<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
|
0000001e r startup_ground()::__c
|
||||||
|
00000020 t gcs_send_message(ap_message)
|
||||||
00000020 t byte_swap_4
|
00000020 t byte_swap_4
|
||||||
|
00000021 r verify_loiter_time()::__c
|
||||||
|
00000021 r process_next_command()::__c
|
||||||
|
00000022 t failsafe_short_off_event()
|
||||||
00000022 t reset_I()
|
00000022 t reset_I()
|
||||||
00000022 W AP_Float16::~AP_Float16()
|
00000022 W AP_Float16::~AP_Float16()
|
||||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
|
@ -296,117 +301,133 @@
|
||||||
00000022 W AP_VarT<float>::~AP_VarT()
|
00000022 W AP_VarT<float>::~AP_VarT()
|
||||||
00000022 W AP_VarT<int>::~AP_VarT()
|
00000022 W AP_VarT<int>::~AP_VarT()
|
||||||
00000022 W AP_VarT<long>::~AP_VarT()
|
00000022 W AP_VarT<long>::~AP_VarT()
|
||||||
00000022 r increment_WP_index()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000022 r verify_loiter_time()::__c
|
00000022 r process_next_command()::__c
|
||||||
|
00000023 r verify_loiter_turns()::__c
|
||||||
00000023 r navigate()::__c
|
00000023 r navigate()::__c
|
||||||
00000024 r verify_loiter_turns()::__c
|
|
||||||
00000026 b mavlink_queue
|
|
||||||
00000026 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
00000027 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
00000028 t increment_WP_index()
|
00000027 r change_command(unsigned char)::__c
|
||||||
|
00000028 t demo_servos(unsigned char)
|
||||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||||
00000028 W AP_VarT<long>::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<float>::serialize(void*, unsigned int) const
|
||||||
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
|
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
|
||||||
00000028 B imu
|
0000002a r verify_nav_command()::__c
|
||||||
0000002a t demo_servos(unsigned char)
|
0000002a t _mav_put_int8_t_array
|
||||||
0000002b r verify_must()::__c
|
|
||||||
0000002b r change_command(unsigned char)::__c
|
0000002b r change_command(unsigned char)::__c
|
||||||
0000002e t reset_control_switch()
|
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
|
||||||
0000002e t send_rate(unsigned int, unsigned int)
|
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
|
||||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||||
0000002e r verify_nav_wp()::__c
|
00000030 t send_heartbeat(mavlink_channel_t)
|
||||||
00000030 r verify_may()::__c
|
00000030 B imu
|
||||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||||
|
00000032 r init_ardupilot()::__c
|
||||||
|
00000033 b pending_status
|
||||||
00000034 t _MAV_RETURN_float
|
00000034 t _MAV_RETURN_float
|
||||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||||
00000034 t _mav_put_int8_t_array
|
00000034 t mavlink_msg_statustext_send
|
||||||
|
00000035 r verify_condition_command()::__c
|
||||||
|
00000038 t send_current_waypoint(mavlink_channel_t)
|
||||||
00000039 r init_ardupilot()::__c
|
00000039 r init_ardupilot()::__c
|
||||||
|
0000003a t verify_loiter_turns()
|
||||||
0000003a W PID::~PID()
|
0000003a W PID::~PID()
|
||||||
0000003a B g_gps_driver
|
0000003a B g_gps_driver
|
||||||
0000003c t verify_loiter_turns()
|
0000003c t verify_RTL()
|
||||||
0000003c W RC_Channel::~RC_Channel()
|
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
|
||||||
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)
|
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 W AP_Float16::unserialize(void*, unsigned int)
|
||||||
00000040 t byte_swap_8
|
00000040 t byte_swap_8
|
||||||
00000040 t crc_accumulate
|
|
||||||
00000040 B history
|
00000040 B history
|
||||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
00000046 W RC_Channel::~RC_Channel()
|
||||||
|
00000048 t failsafe_long_on_event()
|
||||||
|
0000004a t send_meminfo(mavlink_channel_t)
|
||||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, 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 b mavlink_queue
|
||||||
00000050 t failsafe_long_on_event()
|
|
||||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||||
00000056 t change_command(unsigned char)
|
00000052 W AP_IMU_Shim::update()
|
||||||
|
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||||
00000057 B dcm
|
00000057 B dcm
|
||||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||||
0000005e T GCS_MAVLINK::_count_parameters()
|
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 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(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
|
||||||
00000064 t mavlink_msg_param_value_send
|
00000064 W RC_Channel_aux::~RC_Channel_aux()
|
||||||
|
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
|
||||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||||
|
0000006e t do_RTL()
|
||||||
00000070 r init_ardupilot()::__c
|
00000070 r init_ardupilot()::__c
|
||||||
00000074 t verify_loiter_time()
|
00000072 t verify_loiter_time()
|
||||||
0000007c t failsafe_short_on_event()
|
00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
|
||||||
00000080 t do_RTL()
|
0000007c t send_gps_status(mavlink_channel_t)
|
||||||
00000080 T __vector_25
|
00000080 T __vector_25
|
||||||
00000080 T __vector_36
|
00000080 T __vector_36
|
||||||
00000080 T __vector_54
|
00000080 T __vector_54
|
||||||
|
00000084 t change_command(unsigned char)
|
||||||
|
0000008e t handle_no_commands()
|
||||||
|
0000008e t failsafe_short_on_event()
|
||||||
|
00000092 T GCS_MAVLINK::queued_param_send()
|
||||||
00000096 t map_baudrate(signed char, unsigned long)
|
00000096 t map_baudrate(signed char, unsigned long)
|
||||||
|
0000009b B gcs0
|
||||||
|
0000009b B gcs3
|
||||||
0000009c t update_servo_switches()
|
0000009c t update_servo_switches()
|
||||||
0000009d B gcs
|
000000a2 t verify_nav_wp()
|
||||||
0000009d B hil
|
|
||||||
000000a4 T __vector_26
|
000000a4 T __vector_26
|
||||||
000000a4 T __vector_37
|
000000a4 T __vector_37
|
||||||
000000a4 T __vector_55
|
000000a4 T __vector_55
|
||||||
|
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
|
||||||
000000ab B compass
|
000000ab B compass
|
||||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
000000be t update_events()
|
||||||
000000c0 t calc_bearing_error()
|
000000c0 t calc_bearing_error()
|
||||||
000000c4 t update_events()
|
000000ca t send_radio_out(mavlink_channel_t)
|
||||||
000000c4 t load_next_command_from_EEPROM()
|
|
||||||
000000ca t control_failsafe(unsigned int)
|
000000ca t control_failsafe(unsigned int)
|
||||||
000000cc t read_control_switch()
|
000000cc t read_control_switch()
|
||||||
|
000000ce t send_radio_in(mavlink_channel_t)
|
||||||
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
||||||
000000d0 t get_bearing(Location*, Location*)
|
000000d0 t get_bearing(Location*, Location*)
|
||||||
000000da t verify_nav_wp()
|
|
||||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
|
||||||
000000f0 t throttle_slew_limit()
|
000000f0 t throttle_slew_limit()
|
||||||
000000f4 t _mav_finalize_message_chan_send
|
|
||||||
00000106 t calc_nav_pitch()
|
00000106 t calc_nav_pitch()
|
||||||
00000106 t get_wp_with_index(int)
|
0000010a t mavlink_delay(unsigned long)
|
||||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
00000110 t get_cmd_with_index(int)
|
||||||
00000112 t get_distance(Location*, Location*)
|
00000112 t get_distance(Location*, Location*)
|
||||||
|
00000112 t send_servo_out(mavlink_channel_t)
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000118 T GCS_MAVLINK::_queued_send()
|
00000130 t startup_ground()
|
||||||
00000130 t set_wp_with_index(Location, int)
|
00000130 t set_cmd_with_index(Location, int)
|
||||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||||
0000013e t process_may()
|
|
||||||
0000013e t calc_nav_roll()
|
0000013e t calc_nav_roll()
|
||||||
0000014e t verify_may()
|
0000013e t handle_process_condition_command()
|
||||||
0000014e T GCS_MAVLINK::update()
|
00000146 t send_vfr_hud(mavlink_channel_t)
|
||||||
0000016a t process_must()
|
00000152 t verify_condition_command()
|
||||||
0000016a t set_guided_WP()
|
0000015e t set_guided_WP()
|
||||||
00000172 t navigate()
|
0000015e t handle_process_nav_cmd()
|
||||||
0000019e t startup_ground()
|
0000016c t navigate()
|
||||||
000001ae T init_home()
|
0000016e t send_attitude(mavlink_channel_t)
|
||||||
|
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
0000017c t send_location(mavlink_channel_t)
|
||||||
|
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||||
|
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||||
|
00000192 T init_home()
|
||||||
|
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
000001a2 t set_mode(unsigned char)
|
||||||
|
000001a2 T GCS_MAVLINK::update()
|
||||||
000001b2 t update_crosstrack()
|
000001b2 t update_crosstrack()
|
||||||
000001ca t mavlink_delay(unsigned long)
|
000001bc t set_next_WP(Location*)
|
||||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
000001bc t send_nav_controller_output(mavlink_channel_t)
|
||||||
00000206 t set_next_WP(Location*)
|
000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
|
||||||
|
000001f4 t process_next_command()
|
||||||
00000208 t calc_throttle()
|
00000208 t calc_throttle()
|
||||||
0000021c t set_mode(unsigned char)
|
0000022a t send_gps_raw(mavlink_channel_t)
|
||||||
00000232 t verify_must()
|
00000230 t verify_nav_command()
|
||||||
0000024c t update_loiter()
|
0000024c t update_loiter()
|
||||||
000002e4 t read_radio()
|
000002e4 t read_radio()
|
||||||
00000320 t __static_initialization_and_destruction_0(int, int)
|
00000320 t __static_initialization_and_destruction_0(int, int)
|
||||||
0000033a W Parameters::~Parameters()
|
0000033a W Parameters::~Parameters()
|
||||||
000003c0 t process_next_command()
|
00000382 t handle_process_do_command()
|
||||||
000004b2 t mavlink_parse_char
|
00000494 t init_ardupilot()
|
||||||
00000518 t init_ardupilot()
|
00000920 W Parameters::Parameters()
|
||||||
00000831 b g
|
0000092b b g
|
||||||
0000090a W Parameters::Parameters()
|
0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||||
00001240 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
00001c82 T loop
|
||||||
00001868 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
|
||||||
00001aac T loop
|
|
||||||
|
|
|
@ -3,59 +3,71 @@
|
||||||
In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32:
|
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: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
|
/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
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
|
||||||
autogenerated:28: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
|
||||||
autogenerated:29: warning: 'int find_last_log_page(int)' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
|
||||||
/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/GCS_Mavlink.pde:502: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
|
||||||
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Control_Tuning()' defined but not used
|
autogenerated: At global scope:
|
||||||
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Raw()' defined but not used
|
autogenerated:34: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
|
||||||
autogenerated:40: warning: 'void Log_Read_Current()' declared 'static' but never defined
|
autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
|
||||||
autogenerated:41: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
|
autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
|
||||||
autogenerated:42: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used
|
||||||
autogenerated:43: warning: 'void Log_Read_Performance()' declared 'static' but never defined
|
autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined
|
||||||
autogenerated:44: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
|
autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined
|
||||||
autogenerated:45: warning: 'void Log_Read_Startup()' declared 'static' but never defined
|
autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined
|
||||||
autogenerated:46: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used
|
||||||
autogenerated:47: warning: 'void Log_Read_Mode()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:747: warning: 'void Log_Write_Control_Tuning()' defined but not used
|
||||||
autogenerated:48: warning: 'void Log_Read_GPS()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:748: warning: 'void Log_Write_Raw()' defined but not used
|
||||||
autogenerated:49: warning: 'void Log_Read_Raw()' declared 'static' but never defined
|
autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined
|
||||||
autogenerated:50: warning: 'void Log_Read(int, int)' declared 'static' but never defined
|
autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined
|
||||||
autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined
|
||||||
autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined
|
autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined
|
||||||
autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined
|
autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined
|
||||||
autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined
|
autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined
|
||||||
autogenerated:149: warning: 'void init_barometer()' declared 'static' but never defined
|
autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined
|
||||||
autogenerated:150: warning: 'long int read_barometer()' declared 'static' but never defined
|
autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined
|
||||||
autogenerated:152: warning: 'void zero_airspeed()' declared 'static' but never defined
|
autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined
|
||||||
autogenerated:154: warning: 'void report_batt_monitor()' declared 'static' but never defined
|
autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined
|
||||||
autogenerated:155: warning: 'void report_radio()' declared 'static' but never defined
|
autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined
|
||||||
autogenerated:156: warning: 'void report_gains()' declared 'static' but never defined
|
autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined
|
||||||
autogenerated:157: warning: 'void report_xtrack()' declared 'static' but never defined
|
/root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used
|
||||||
autogenerated:158: warning: 'void report_throttle()' declared 'static' but never defined
|
autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined
|
||||||
autogenerated:159: warning: 'void report_imu()' declared 'static' but never defined
|
autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined
|
||||||
autogenerated:160: warning: 'void report_compass()' declared 'static' but never defined
|
autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined
|
||||||
autogenerated:161: warning: 'void report_flight_modes()' declared 'static' but never defined
|
autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined
|
||||||
autogenerated:162: warning: 'void print_PID(PID*)' declared 'static' but never defined
|
autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined
|
||||||
autogenerated:163: warning: 'void print_radio_values()' declared 'static' but never defined
|
autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined
|
||||||
autogenerated:164: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
|
autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined
|
||||||
autogenerated:165: warning: 'void print_done()' declared 'static' but never defined
|
autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined
|
||||||
autogenerated:166: warning: 'void print_blanks(int)' declared 'static' but never defined
|
autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined
|
||||||
autogenerated:167: warning: 'void print_divider()' declared 'static' but never defined
|
autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined
|
||||||
autogenerated:168: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
|
autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined
|
||||||
autogenerated:169: warning: 'void zero_eeprom()' declared 'static' but never defined
|
autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined
|
||||||
autogenerated:170: warning: 'void print_enabled(bool)' declared 'static' but never defined
|
autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined
|
||||||
autogenerated:171: warning: 'void print_accel_offsets()' declared 'static' but never defined
|
autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined
|
||||||
autogenerated:172: warning: 'void print_gyro_offsets()' declared 'static' but never defined
|
autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined
|
||||||
autogenerated:183: warning: 'void print_hit_enter()' declared 'static' but never defined
|
autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined
|
||||||
autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
|
autogenerated:180: warning: 'void print_done()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:210: warning: 'comma' defined but not used
|
autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:212: warning: 'flight_mode_strings' defined but not used
|
autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:317: warning: 'airspeed_raw' defined but not used
|
autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:318: warning: 'airspeed_pressure' defined but not used
|
autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:322: warning: 'abs_pressure' defined but not used
|
autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined
|
||||||
/root/apm/ardupilot-mega/ArduPlane/Log.pde:742: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used
|
autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined
|
||||||
|
autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined
|
||||||
|
autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined
|
||||||
|
autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined
|
||||||
|
autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used
|
||||||
|
/root/apm/ardupilot-mega/ArduPlane/Log.pde:743: 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
|
/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_BMP085/APM_BMP085.o
|
||||||
|
%% libraries/APM_BMP085/APM_BMP085_hil.o
|
||||||
%% libraries/APM_RC/APM_RC.o
|
%% libraries/APM_RC/APM_RC.o
|
||||||
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
%% libraries/AP_ADC/AP_ADC_ADS7844.o
|
||||||
%% libraries/AP_ADC/AP_ADC.o
|
%% libraries/AP_ADC/AP_ADC.o
|
||||||
|
@ -83,11 +95,17 @@ autogenerated:184: warning: 'void test_wp_print(Location*, byte)' declared 'stat
|
||||||
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
%% libraries/AP_GPS/AP_GPS_UBLOX.o
|
||||||
%% libraries/AP_GPS/GPS.o
|
%% libraries/AP_GPS/GPS.o
|
||||||
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
%% libraries/AP_IMU/AP_IMU_Oilpan.o
|
||||||
|
%% libraries/AP_Mount/AP_Mount.o
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::control_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:182: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp: In member function 'void AP_Mount::status_msg(mavlink_message_t*)':
|
||||||
|
/root/apm/ardupilot-mega/libraries/AP_Mount/AP_Mount.cpp:226: warning: enumeration value 'MAV_MOUNT_MODE_ENUM_END' not handled in switch
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o
|
||||||
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o
|
||||||
%% libraries/AP_RangeFinder/RangeFinder.o
|
%% libraries/AP_RangeFinder/RangeFinder.o
|
||||||
|
%% libraries/AP_Relay/AP_Relay.o
|
||||||
%% libraries/DataFlash/DataFlash.o
|
%% libraries/DataFlash/DataFlash.o
|
||||||
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35:
|
In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36:
|
||||||
/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
|
/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
|
/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/BetterStream.o
|
||||||
|
@ -96,6 +114,7 @@ In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp
|
||||||
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
%% libraries/GCS_MAVLink/GCS_MAVLink.o
|
||||||
%% libraries/ModeFilter/ModeFilter.o
|
%% libraries/ModeFilter/ModeFilter.o
|
||||||
%% libraries/PID/PID.o
|
%% libraries/PID/PID.o
|
||||||
|
%% libraries/RC_Channel/RC_Channel_aux.o
|
||||||
%% libraries/RC_Channel/RC_Channel.o
|
%% libraries/RC_Channel/RC_Channel.o
|
||||||
%% libraries/memcheck/memcheck.o
|
%% libraries/memcheck/memcheck.o
|
||||||
%% libraries/FastSerial/ftoa_engine.o
|
%% libraries/FastSerial/ftoa_engine.o
|
||||||
|
|
|
@ -3,20 +3,21 @@
|
||||||
00000001 b home_is_set
|
00000001 b home_is_set
|
||||||
00000001 b ch3_failsafe
|
00000001 b ch3_failsafe
|
||||||
00000001 b land_complete
|
00000001 b land_complete
|
||||||
00000001 b command_may_ID
|
00000001 b mavlink_active
|
||||||
00000001 b command_must_ID
|
00000001 b nav_command_ID
|
||||||
00000001 b failsafeCounter
|
00000001 b failsafeCounter
|
||||||
00000001 b counter_one_herz
|
00000001 b counter_one_herz
|
||||||
00000001 b in_mavlink_delay
|
00000001 b in_mavlink_delay
|
||||||
00000001 b slow_loopCounter
|
00000001 b slow_loopCounter
|
||||||
00000001 d takeoff_complete
|
00000001 d takeoff_complete
|
||||||
00000001 b command_may_index
|
00000001 b nav_command_index
|
||||||
00000001 b command_must_index
|
|
||||||
00000001 b delta_ms_fast_loop
|
00000001 b delta_ms_fast_loop
|
||||||
00000001 d ground_start_count
|
00000001 d ground_start_count
|
||||||
00000001 b medium_loopCounter
|
00000001 b medium_loopCounter
|
||||||
|
00000001 b non_nav_command_ID
|
||||||
00000001 b rc_override_active
|
00000001 b rc_override_active
|
||||||
00000001 b delta_ms_medium_loop
|
00000001 b delta_ms_medium_loop
|
||||||
|
00000001 b non_nav_command_index
|
||||||
00000001 b superslow_loopCounter
|
00000001 b superslow_loopCounter
|
||||||
00000001 b event_id
|
00000001 b event_id
|
||||||
00000001 b GPS_light
|
00000001 b GPS_light
|
||||||
|
@ -24,11 +25,9 @@
|
||||||
00000001 D control_mode
|
00000001 D control_mode
|
||||||
00000001 B hindex
|
00000001 B hindex
|
||||||
00000001 B inverted_flight
|
00000001 B inverted_flight
|
||||||
00000001 B mavdelay
|
|
||||||
00000001 B n
|
00000001 B n
|
||||||
00000001 B oldSwitchPosition
|
00000001 B oldSwitchPosition
|
||||||
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
|
00000001 B relay
|
||||||
00000002 b climb_rate
|
|
||||||
00000002 b loiter_sum
|
00000002 b loiter_sum
|
||||||
00000002 b event_delay
|
00000002 b event_delay
|
||||||
00000002 b event_value
|
00000002 b event_value
|
||||||
|
@ -58,11 +57,11 @@
|
||||||
00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long))
|
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(IMU::Start_style, void (*)(unsigned long))
|
||||||
00000002 W AP_IMU_Shim::init_gyro(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 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
|
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 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
00000004 b event_timer
|
00000004 b event_timer
|
||||||
00000004 d hold_course
|
00000004 d hold_course
|
||||||
00000004 b loiter_time
|
00000004 b loiter_time
|
||||||
|
@ -71,6 +70,7 @@
|
||||||
00000004 b wp_distance
|
00000004 b wp_distance
|
||||||
00000004 b current_amps
|
00000004 b current_amps
|
||||||
00000004 b energy_error
|
00000004 b energy_error
|
||||||
|
00000004 b airspeed_fbwB
|
||||||
00000004 b bearing_error
|
00000004 b bearing_error
|
||||||
00000004 b current_total
|
00000004 b current_total
|
||||||
00000004 b nav_loopTimer
|
00000004 b nav_loopTimer
|
||||||
|
@ -106,8 +106,6 @@
|
||||||
00000004 b nav_roll
|
00000004 b nav_roll
|
||||||
00000004 b nav_pitch
|
00000004 b nav_pitch
|
||||||
00000004 b mavlink_delay(unsigned long)::last_1hz
|
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 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 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
|
||||||
|
@ -135,7 +133,6 @@
|
||||||
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
|
00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c
|
||||||
00000008 r __menu_name__planner_menu
|
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 V Parameters::Parameters()::__c
|
00000008 V Parameters::Parameters()::__c
|
||||||
|
@ -149,12 +146,13 @@
|
||||||
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
|
||||||
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
|
||||||
|
00000009 V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
|
0000000a r init_home()::__c
|
||||||
|
0000000a r verify_nav_wp()::__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
|
||||||
|
@ -162,18 +160,17 @@
|
||||||
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 RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a V Parameters::Parameters()::__c
|
0000000a V RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)::__c
|
||||||
0000000a T setup
|
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
|
||||||
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 T GCS_MAVLINK::send_text(gcs_severity, char const*)
|
||||||
0000000c V vtable for AP_IMU_Shim
|
0000000c V vtable for AP_IMU_Shim
|
||||||
0000000c V vtable for IMU
|
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
|
||||||
0000000c V Parameters::Parameters()::__c
|
0000000c V Parameters::Parameters()::__c
|
||||||
|
@ -182,6 +179,9 @@
|
||||||
0000000d r init_home()::__c
|
0000000d r init_home()::__c
|
||||||
0000000d r verify_RTL()::__c
|
0000000d r verify_RTL()::__c
|
||||||
0000000d r demo_servos(unsigned char)::__c
|
0000000d r demo_servos(unsigned char)::__c
|
||||||
|
0000000d r control_failsafe(unsigned int)::__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
|
||||||
|
@ -202,6 +202,7 @@
|
||||||
0000000d B sonar_mode_filter
|
0000000d B sonar_mode_filter
|
||||||
0000000e t global destructors keyed to Serial
|
0000000e t global destructors keyed to Serial
|
||||||
0000000e t global constructors keyed to Serial
|
0000000e t global constructors keyed to Serial
|
||||||
|
0000000e t send_statustext(mavlink_channel_t)
|
||||||
0000000e V vtable for AP_Float16
|
0000000e V vtable for AP_Float16
|
||||||
0000000e V vtable for AP_VarS<Matrix3<float> >
|
0000000e V vtable for AP_VarS<Matrix3<float> >
|
||||||
0000000e V vtable for AP_VarS<Vector3<float> >
|
0000000e V vtable for AP_VarS<Vector3<float> >
|
||||||
|
@ -209,7 +210,7 @@
|
||||||
0000000e V vtable for AP_VarT<float>
|
0000000e V vtable for AP_VarT<float>
|
||||||
0000000e V vtable for AP_VarT<int>
|
0000000e V vtable for AP_VarT<int>
|
||||||
0000000e V vtable for AP_VarT<long>
|
0000000e V vtable for AP_VarT<long>
|
||||||
0000000e r process_may()::__c
|
0000000e r control_failsafe(unsigned int)::__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
|
||||||
|
@ -230,12 +231,13 @@
|
||||||
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 current_loc
|
||||||
0000000f b next_command
|
0000000f b next_nav_command
|
||||||
|
0000000f b next_nonnav_command
|
||||||
0000000f b home
|
0000000f b home
|
||||||
0000000f b next_WP
|
0000000f b next_WP
|
||||||
0000000f b prev_WP
|
0000000f b prev_WP
|
||||||
0000000f b guided_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
|
||||||
0000000f V Parameters::Parameters()::__c
|
0000000f V Parameters::Parameters()::__c
|
||||||
|
@ -243,15 +245,16 @@
|
||||||
0000000f V Parameters::Parameters()::__c
|
0000000f V Parameters::Parameters()::__c
|
||||||
00000010 b rc_override
|
00000010 b rc_override
|
||||||
00000010 r planner_menu_commands
|
00000010 r planner_menu_commands
|
||||||
|
00000010 T GCS_MAVLINK::send_message(ap_message)
|
||||||
00000010 W AP_VarT<float>::cast_to_float() const
|
00000010 W AP_VarT<float>::cast_to_float() const
|
||||||
00000010 W AP_VarT<long>::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 startup_ground()::__c
|
||||||
00000011 r load_next_command_from_EEPROM()::__c
|
00000011 r process_next_command()::__c
|
||||||
|
00000011 r failsafe_short_on_event()::__c
|
||||||
00000012 B Serial
|
00000012 B Serial
|
||||||
00000012 B Serial1
|
00000012 B Serial1
|
||||||
00000012 B Serial3
|
00000012 B Serial3
|
||||||
|
00000012 t gcs_update()
|
||||||
00000012 W AP_Float16::~AP_Float16()
|
00000012 W AP_Float16::~AP_Float16()
|
||||||
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
00000012 W AP_VarS<Vector3<float> >::~AP_VarS()
|
||||||
|
@ -260,24 +263,23 @@
|
||||||
00000012 W AP_VarT<int>::~AP_VarT()
|
00000012 W AP_VarT<int>::~AP_VarT()
|
||||||
00000012 W AP_VarT<long>::~AP_VarT()
|
00000012 W AP_VarT<long>::~AP_VarT()
|
||||||
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
00000012 W AP_VarT<signed char>::serialize(void*, unsigned int) const
|
||||||
|
00000012 r handle_no_commands()::__c
|
||||||
00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
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>::unserialize(void*, unsigned int)
|
||||||
00000014 W AP_VarT<signed char>::cast_to_float() const
|
00000014 W AP_VarT<signed char>::cast_to_float() const
|
||||||
00000014 W AP_VarT<int>::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 map_baudrate(signed char, unsigned long)::__c
|
||||||
|
00000015 r verify_nav_wp()::__c
|
||||||
00000015 r init_ardupilot()::__c
|
00000015 r init_ardupilot()::__c
|
||||||
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
|
||||||
00000016 r GCS_MAVLINK::update()::__c
|
00000016 B adc
|
||||||
00000016 B sonar
|
00000016 B sonar
|
||||||
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
|
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 failsafe_long_on_event()::__c
|
||||||
00000019 r GCS_MAVLINK::update()::__c
|
00000019 r handle_process_nav_cmd()::__c
|
||||||
|
00000019 r handle_process_do_command()::__c
|
||||||
|
00000019 r handle_process_condition_command()::__c
|
||||||
0000001a t startup_IMU_ground()
|
0000001a t startup_IMU_ground()
|
||||||
0000001a r reset_control_switch()::__c
|
|
||||||
0000001a r failsafe_short_on_event()::__c
|
0000001a r failsafe_short_on_event()::__c
|
||||||
0000001b r failsafe_short_off_event()::__c
|
0000001b r failsafe_short_off_event()::__c
|
||||||
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
|
||||||
|
@ -285,9 +287,12 @@
|
||||||
0000001c W AP_VarT<int>::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<Matrix3<float> >::serialize(void*, unsigned int) const
|
||||||
0000001c W AP_VarS<Vector3<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
|
0000001e r startup_ground()::__c
|
||||||
|
00000020 t gcs_send_message(ap_message)
|
||||||
00000020 t byte_swap_4
|
00000020 t byte_swap_4
|
||||||
|
00000021 r verify_loiter_time()::__c
|
||||||
|
00000021 r process_next_command()::__c
|
||||||
|
00000022 t failsafe_short_off_event()
|
||||||
00000022 t reset_I()
|
00000022 t reset_I()
|
||||||
00000022 W AP_Float16::~AP_Float16()
|
00000022 W AP_Float16::~AP_Float16()
|
||||||
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
|
||||||
|
@ -296,117 +301,133 @@
|
||||||
00000022 W AP_VarT<float>::~AP_VarT()
|
00000022 W AP_VarT<float>::~AP_VarT()
|
||||||
00000022 W AP_VarT<int>::~AP_VarT()
|
00000022 W AP_VarT<int>::~AP_VarT()
|
||||||
00000022 W AP_VarT<long>::~AP_VarT()
|
00000022 W AP_VarT<long>::~AP_VarT()
|
||||||
00000022 r increment_WP_index()::__c
|
00000022 r process_next_command()::__c
|
||||||
00000022 r verify_loiter_time()::__c
|
00000022 r process_next_command()::__c
|
||||||
|
00000023 r verify_loiter_turns()::__c
|
||||||
00000023 r navigate()::__c
|
00000023 r navigate()::__c
|
||||||
00000024 r verify_loiter_turns()::__c
|
|
||||||
00000026 b mavlink_queue
|
|
||||||
00000026 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
00000027 r init_ardupilot()::__c
|
00000026 r init_ardupilot()::__c
|
||||||
00000028 t increment_WP_index()
|
00000027 r change_command(unsigned char)::__c
|
||||||
|
00000028 t demo_servos(unsigned char)
|
||||||
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
00000028 W AP_VarT<float>::unserialize(void*, unsigned int)
|
||||||
00000028 W AP_VarT<long>::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<float>::serialize(void*, unsigned int) const
|
||||||
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
|
00000028 W AP_VarT<long>::serialize(void*, unsigned int) const
|
||||||
00000028 B imu
|
0000002a r verify_nav_command()::__c
|
||||||
0000002a t demo_servos(unsigned char)
|
0000002a t _mav_put_int8_t_array
|
||||||
0000002b r verify_must()::__c
|
|
||||||
0000002b r change_command(unsigned char)::__c
|
0000002b r change_command(unsigned char)::__c
|
||||||
0000002e t reset_control_switch()
|
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
|
||||||
0000002e t send_rate(unsigned int, unsigned int)
|
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
|
||||||
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
|
||||||
0000002e r verify_nav_wp()::__c
|
00000030 t send_heartbeat(mavlink_channel_t)
|
||||||
00000030 r verify_may()::__c
|
00000030 B imu
|
||||||
00000032 T GCS_MAVLINK::init(FastSerial*)
|
00000032 T GCS_MAVLINK::init(FastSerial*)
|
||||||
|
00000032 r init_ardupilot()::__c
|
||||||
|
00000033 b pending_status
|
||||||
00000034 t _MAV_RETURN_float
|
00000034 t _MAV_RETURN_float
|
||||||
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
00000034 W AP_Float16::serialize(void*, unsigned int) const
|
||||||
00000034 t _mav_put_int8_t_array
|
00000034 t mavlink_msg_statustext_send
|
||||||
|
00000035 r verify_condition_command()::__c
|
||||||
|
00000038 t send_current_waypoint(mavlink_channel_t)
|
||||||
00000039 r init_ardupilot()::__c
|
00000039 r init_ardupilot()::__c
|
||||||
|
0000003a t verify_loiter_turns()
|
||||||
0000003a W PID::~PID()
|
0000003a W PID::~PID()
|
||||||
0000003a B g_gps_driver
|
0000003a B g_gps_driver
|
||||||
0000003c t verify_loiter_turns()
|
0000003c t verify_RTL()
|
||||||
0000003c W RC_Channel::~RC_Channel()
|
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
|
||||||
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)
|
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 W AP_Float16::unserialize(void*, unsigned int)
|
||||||
00000040 t byte_swap_8
|
00000040 t byte_swap_8
|
||||||
00000040 t crc_accumulate
|
|
||||||
00000040 B history
|
00000040 B history
|
||||||
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
|
||||||
|
00000046 W RC_Channel::~RC_Channel()
|
||||||
|
00000048 t failsafe_long_on_event()
|
||||||
|
0000004a t send_meminfo(mavlink_channel_t)
|
||||||
0000004a W AP_VarT<int>::AP_VarT(AP_Var_group*, unsigned int, 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 b mavlink_queue
|
||||||
00000050 t failsafe_long_on_event()
|
|
||||||
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
|
||||||
00000056 t change_command(unsigned char)
|
00000052 W AP_IMU_Shim::update()
|
||||||
|
00000056 T GCS_MAVLINK::queued_waypoint_send()
|
||||||
00000057 B dcm
|
00000057 B dcm
|
||||||
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
0000005a W AP_VarT<float>::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char)
|
||||||
0000005e T GCS_MAVLINK::_count_parameters()
|
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 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(mavlink_channel_t, char const*, float, unsigned char, unsigned int, unsigned int)
|
||||||
00000064 t mavlink_msg_param_value_send
|
00000064 W RC_Channel_aux::~RC_Channel_aux()
|
||||||
|
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
|
||||||
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
0000006a W GCS_MAVLINK::~GCS_MAVLINK()
|
||||||
|
0000006e t do_RTL()
|
||||||
00000070 r init_ardupilot()::__c
|
00000070 r init_ardupilot()::__c
|
||||||
00000074 t verify_loiter_time()
|
00000072 t verify_loiter_time()
|
||||||
0000007c t failsafe_short_on_event()
|
00000078 t gcs_send_text_fmt(prog_char_t const*, ...)
|
||||||
00000080 t do_RTL()
|
0000007c t send_gps_status(mavlink_channel_t)
|
||||||
00000080 T __vector_25
|
00000080 T __vector_25
|
||||||
00000080 T __vector_36
|
00000080 T __vector_36
|
||||||
00000080 T __vector_54
|
00000080 T __vector_54
|
||||||
|
00000084 t change_command(unsigned char)
|
||||||
|
0000008e t failsafe_short_on_event()
|
||||||
|
00000090 t handle_no_commands()
|
||||||
|
00000092 T GCS_MAVLINK::queued_param_send()
|
||||||
00000096 t map_baudrate(signed char, unsigned long)
|
00000096 t map_baudrate(signed char, unsigned long)
|
||||||
|
0000009b B gcs0
|
||||||
|
0000009b B gcs3
|
||||||
0000009c t update_servo_switches()
|
0000009c t update_servo_switches()
|
||||||
0000009d B gcs
|
000000a2 t verify_nav_wp()
|
||||||
0000009d B hil
|
|
||||||
000000a4 T __vector_26
|
000000a4 T __vector_26
|
||||||
000000a4 T __vector_37
|
000000a4 T __vector_37
|
||||||
000000a4 T __vector_55
|
000000a4 T __vector_55
|
||||||
|
000000a6 t planner_gcs(unsigned char, Menu::arg const*)
|
||||||
000000ab B compass
|
000000ab B compass
|
||||||
000000b4 t planner_gcs(unsigned char, Menu::arg const*)
|
000000be t update_events()
|
||||||
000000c0 t calc_bearing_error()
|
000000c0 t calc_bearing_error()
|
||||||
000000c4 t update_events()
|
000000ca t send_radio_out(mavlink_channel_t)
|
||||||
000000c4 t load_next_command_from_EEPROM()
|
|
||||||
000000ca t control_failsafe(unsigned int)
|
000000ca t control_failsafe(unsigned int)
|
||||||
000000cc t read_control_switch()
|
000000cc t read_control_switch()
|
||||||
|
000000ce t send_radio_in(mavlink_channel_t)
|
||||||
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&)
|
||||||
000000d0 t get_bearing(Location*, Location*)
|
000000d0 t get_bearing(Location*, Location*)
|
||||||
000000d8 t verify_nav_wp()
|
|
||||||
000000e0 b mavlink_parse_char::m_mavlink_message
|
|
||||||
000000f0 t throttle_slew_limit()
|
000000f0 t throttle_slew_limit()
|
||||||
000000f4 t _mav_finalize_message_chan_send
|
|
||||||
00000106 t calc_nav_pitch()
|
00000106 t calc_nav_pitch()
|
||||||
00000106 t get_wp_with_index(int)
|
0000010a t mavlink_delay(unsigned long)
|
||||||
0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
00000110 t get_cmd_with_index(int)
|
||||||
00000112 t get_distance(Location*, Location*)
|
00000112 t get_distance(Location*, Location*)
|
||||||
|
00000112 t send_servo_out(mavlink_channel_t)
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
|
||||||
00000118 T GCS_MAVLINK::_queued_send()
|
00000130 t startup_ground()
|
||||||
00000130 t set_wp_with_index(Location, int)
|
00000130 t set_cmd_with_index(Location, int)
|
||||||
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
|
00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
|
||||||
0000013e t process_may()
|
|
||||||
0000013e t calc_nav_roll()
|
0000013e t calc_nav_roll()
|
||||||
0000014e t verify_may()
|
0000013e t handle_process_condition_command()
|
||||||
0000014e T GCS_MAVLINK::update()
|
00000146 t send_vfr_hud(mavlink_channel_t)
|
||||||
0000016a t process_must()
|
00000152 t verify_condition_command()
|
||||||
0000016a t set_guided_WP()
|
0000015e t set_guided_WP()
|
||||||
00000172 t navigate()
|
0000015e t handle_process_nav_cmd()
|
||||||
0000019e t startup_ground()
|
0000016c t navigate()
|
||||||
000001ae T init_home()
|
0000016e t send_attitude(mavlink_channel_t)
|
||||||
|
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
0000017c t send_location(mavlink_channel_t)
|
||||||
|
00000180 t send_extended_status1(mavlink_channel_t, unsigned int)
|
||||||
|
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
||||||
|
00000190 T init_home()
|
||||||
|
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
|
||||||
|
000001a2 t set_mode(unsigned char)
|
||||||
|
000001a2 T GCS_MAVLINK::update()
|
||||||
000001b2 t update_crosstrack()
|
000001b2 t update_crosstrack()
|
||||||
000001ca t mavlink_delay(unsigned long)
|
000001bc t set_next_WP(Location*)
|
||||||
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
|
000001bc t send_nav_controller_output(mavlink_channel_t)
|
||||||
00000206 t set_next_WP(Location*)
|
000001da W RC_Channel_aux::RC_Channel_aux(unsigned int, prog_char_t const*)
|
||||||
|
000001f4 t process_next_command()
|
||||||
00000208 t calc_throttle()
|
00000208 t calc_throttle()
|
||||||
0000021c t set_mode(unsigned char)
|
0000022a t send_gps_raw(mavlink_channel_t)
|
||||||
00000232 t verify_must()
|
00000230 t verify_nav_command()
|
||||||
0000024c t update_loiter()
|
0000024c t update_loiter()
|
||||||
000002e4 t read_radio()
|
000002e4 t read_radio()
|
||||||
00000320 t __static_initialization_and_destruction_0(int, int)
|
00000320 t __static_initialization_and_destruction_0(int, int)
|
||||||
0000033a W Parameters::~Parameters()
|
0000033a W Parameters::~Parameters()
|
||||||
000003c0 t process_next_command()
|
00000382 t handle_process_do_command()
|
||||||
000004b2 t mavlink_parse_char
|
00000492 t init_ardupilot()
|
||||||
00000518 t init_ardupilot()
|
00000920 W Parameters::Parameters()
|
||||||
00000831 b g
|
0000092b b g
|
||||||
0000090a W Parameters::Parameters()
|
0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
||||||
00001240 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
|
00001c82 T loop
|
||||||
00001868 T GCS_MAVLINK::handleMessage(__mavlink_message*)
|
|
||||||
00001aac T loop
|
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
|
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
|
||||||
<name>ArduPlane V2.24 </name>
|
<name>ArduPlane V2.24 </name>
|
||||||
<desc></desc>
|
<desc></desc>
|
||||||
<format_version>11</format_version>
|
<format_version>12</format_version>
|
||||||
</Firmware>
|
</Firmware>
|
||||||
<Firmware>
|
<Firmware>
|
||||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
|
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
|
||||||
|
@ -39,14 +39,14 @@
|
||||||
#define AIRSPEED_CRUISE 25
|
#define AIRSPEED_CRUISE 25
|
||||||
#define THROTTLE_FAILSAFE ENABLED
|
#define THROTTLE_FAILSAFE ENABLED
|
||||||
</desc>
|
</desc>
|
||||||
<format_version>11</format_version>
|
<format_version>12</format_version>
|
||||||
</Firmware>
|
</Firmware>
|
||||||
<Firmware>
|
<Firmware>
|
||||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
|
<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>
|
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
|
||||||
<name>ArduPlane V2.24 APM trunk</name>
|
<name>ArduPlane V2.24 APM trunk</name>
|
||||||
<desc></desc>
|
<desc></desc>
|
||||||
<format_version>11</format_version>
|
<format_version>12</format_version>
|
||||||
</Firmware>
|
</Firmware>
|
||||||
<Firmware>
|
<Firmware>
|
||||||
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
||||||
|
|
|
@ -1,545 +1,183 @@
|
||||||
From https://code.google.com/p/ardupilot-mega
|
From https://code.google.com/p/ardupilot-mega
|
||||||
b0bfa54..8d3fb35 APM_Camera -> origin/APM_Camera
|
46f9a14..d69430d master -> origin/master
|
||||||
cd1bcd6..34c9a18 master -> origin/master
|
Updating 46f9a14..d69430d
|
||||||
Updating cd1bcd6..34c9a18
|
|
||||||
Fast-forward
|
Fast-forward
|
||||||
.gitignore | 4 +-
|
.project | 11 +
|
||||||
ArduBoat/ArduBoat.cpp | 7 +-
|
ArduBoat/.cproject | 46 -
|
||||||
ArduBoat/ArduBoat.pde | 2 +-
|
ArduBoat/.project | 79 -
|
||||||
ArduBoat/BoatGeneric.h | 39 +-
|
ArduBoat/ArduBoat.cpp | 25 -
|
||||||
ArduBoat/ControllerBoat.h | 157 +-
|
ArduBoat/ControllerBoat.h | 2 +-
|
||||||
ArduCopter/APM_Config.h | 7 +-
|
ArduCopter/.cproject | 970 -------
|
||||||
ArduCopter/ArduCopter.pde | 64 +-
|
ArduCopter/.project | 84 -
|
||||||
ArduCopter/Attitude.pde | 54 +-
|
ArduCopter/APM_Config.h | 2 -
|
||||||
ArduCopter/CMakeLists.txt | 165 -
|
ArduCopter/ArduCopter.pde | 336 ++-
|
||||||
ArduCopter/GCS.h | 7 +-
|
ArduCopter/Attitude.pde | 201 +-
|
||||||
ArduCopter/GCS_Mavlink.pde | 23 +-
|
ArduCopter/GCS.h | 1 +
|
||||||
ArduCopter/Log.pde | 261 +-
|
ArduCopter/GCS_Mavlink.pde | 122 +-
|
||||||
ArduCopter/Parameters.h | 12 +-
|
ArduCopter/Log.pde | 437 ++--
|
||||||
ArduCopter/config.h | 45 +-
|
ArduCopter/Parameters.h | 31 +-
|
||||||
ArduCopter/control_modes.pde | 8 +-
|
ArduCopter/commands.pde | 61 +-
|
||||||
ArduCopter/defines.h | 1 +
|
ArduCopter/commands_logic.pde | 48 +-
|
||||||
ArduCopter/heli.pde | 25 +
|
ArduCopter/commands_process.pde | 51 +-
|
||||||
ArduCopter/motors.pde | 4 +-
|
ArduCopter/config.h | 19 +-
|
||||||
ArduCopter/navigation.pde | 42 +-
|
ArduCopter/control_modes.pde | 100 +-
|
||||||
ArduCopter/radio.pde | 14 +-
|
ArduCopter/heli.pde | 81 +-
|
||||||
ArduCopter/system.pde | 36 +-
|
ArduCopter/motors.pde | 215 +-
|
||||||
ArduPlane/.gitignore | 1 -
|
ArduCopter/motors_y6.pde | 6 +-
|
||||||
ArduPlane/ArduPlane.pde | 27 +-
|
ArduCopter/navigation.pde | 92 +-
|
||||||
ArduPlane/CMakeLists.txt | 168 -
|
ArduCopter/radio.pde | 9 +-
|
||||||
ArduPlane/GCS.h | 7 +-
|
ArduCopter/sensors.pde | 6 +-
|
||||||
ArduPlane/GCS_Mavlink.pde | 464 +++-
|
ArduCopter/setup.pde | 48 +-
|
||||||
ArduPlane/Log.pde | 10 +-
|
ArduCopter/system.pde | 63 +-
|
||||||
ArduPlane/Mavlink_compat.h | 172 +
|
ArduCopter/test.pde | 37 +-
|
||||||
ArduPlane/Parameters.h | 12 +-
|
ArduPlane/.cproject | 468 ----
|
||||||
ArduPlane/commands.pde | 65 +-
|
ArduPlane/.project | 80 -
|
||||||
ArduPlane/commands_logic.pde | 152 +-
|
ArduPlane/ArduPlane.pde | 15 +
|
||||||
ArduPlane/commands_process.pde | 183 +-
|
ArduPlane/GCS.h | 1 +
|
||||||
ArduPlane/config.h | 5 +
|
ArduPlane/GCS_Mavlink.pde | 102 +-
|
||||||
ArduPlane/defines.h | 3 +-
|
ArduPlane/Log.pde | 7 +-
|
||||||
|
ArduPlane/commands.pde | 1 +
|
||||||
|
ArduPlane/commands_logic.pde | 19 +
|
||||||
|
ArduPlane/commands_process.pde | 26 +-
|
||||||
|
ArduPlane/config.h | 14 +
|
||||||
ArduPlane/navigation.pde | 2 +-
|
ArduPlane/navigation.pde | 2 +-
|
||||||
ArduPlane/system.pde | 21 +-
|
ArduRover/.cproject | 46 -
|
||||||
ArduPlane/test.pde | 6 +-
|
ArduRover/.project | 79 -
|
||||||
ArduRover/ArduRover.cpp | 6 +-
|
ArduRover/ArduRover.cpp | 27 -
|
||||||
ArduRover/ArduRover.pde | 1 +
|
ArduRover/CarStampede.h | 2 +
|
||||||
ArduRover/CarStampede.h | 31 +-
|
ArduRover/ControllerCar.h | 57 +-
|
||||||
ArduRover/ControllerCar.h | 158 +-
|
CMakeLists.txt | 102 +-
|
||||||
ArduRover/ControllerTank.h | 176 +-
|
README.txt | 52 +
|
||||||
ArduRover/TankGeneric.h | 16 +-
|
Tools/ArdupilotMegaPlanner/ArduinoDetect.cs | 23 +-
|
||||||
CMakeLists.txt | 9 +-
|
Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 8 +-
|
||||||
Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 9 +
|
Tools/ArdupilotMegaPlanner/ArdupilotMega.sln | 3 -
|
||||||
Tools/ArdupilotMegaPlanner/Camera.Designer.cs | 421 +++
|
Tools/ArdupilotMegaPlanner/AviWriter.cs | 37 +-
|
||||||
Tools/ArdupilotMegaPlanner/Camera.cs | 139 +
|
Tools/ArdupilotMegaPlanner/Camera.Designer.cs | 407 ++--
|
||||||
Tools/ArdupilotMegaPlanner/Camera.resx | 120 +
|
Tools/ArdupilotMegaPlanner/Camera.cs | 308 ++-
|
||||||
Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 12 +-
|
Tools/ArdupilotMegaPlanner/Common.cs | 111 +-
|
||||||
Tools/ArdupilotMegaPlanner/CurrentState.cs | 81 +-
|
Tools/ArdupilotMegaPlanner/CurrentState.cs | 180 ++-
|
||||||
.../GCSViews/Configuration.Designer.cs | 137 +-
|
.../GCSViews/Configuration.Designer.cs | 340 ++--
|
||||||
.../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 47 +-
|
.../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 82 +-
|
||||||
.../GCSViews/Configuration.resx | 2088 +++++-------
|
Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 7 +-
|
||||||
Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 12 +-
|
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 64 +-
|
||||||
.../GCSViews/FlightData.Designer.cs | 155 +-
|
.../GCSViews/FlightPlanner.Designer.cs | 85 +-
|
||||||
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 164 +-
|
.../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 32 +-
|
||||||
.../ArdupilotMegaPlanner/GCSViews/FlightData.resx | 604 ++--
|
.../GCSViews/FlightPlanner.resx | 2733 ++++++++++----------
|
||||||
.../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 4 +-
|
Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 158 +-
|
||||||
Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 18 +-
|
Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs | 70 +-
|
||||||
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 7 +
|
Tools/ArdupilotMegaPlanner/Joystick.cs | 16 +-
|
||||||
Tools/ArdupilotMegaPlanner/Joystick.cs | 50 +-
|
Tools/ArdupilotMegaPlanner/JoystickSetup.cs | 6 +-
|
||||||
.../ArdupilotMegaPlanner/JoystickSetup.Designer.cs | 276 ++-
|
Tools/ArdupilotMegaPlanner/MAVLink.cs | 511 ++++-
|
||||||
Tools/ArdupilotMegaPlanner/JoystickSetup.cs | 125 +-
|
Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs | 1374 +++++-----
|
||||||
Tools/ArdupilotMegaPlanner/JoystickSetup.resx | 763 ++++-
|
Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs | 1480 +++++++++++
|
||||||
Tools/ArdupilotMegaPlanner/MAVLink.cs | 11 +-
|
Tools/ArdupilotMegaPlanner/MainV2.cs | 97 +-
|
||||||
Tools/ArdupilotMegaPlanner/MainV2.cs | 87 +-
|
Tools/ArdupilotMegaPlanner/Program.cs | 7 +
|
||||||
Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 9 +-
|
|
||||||
Tools/ArdupilotMegaPlanner/Program.cs | 1 +
|
|
||||||
.../Properties/AssemblyInfo.cs | 2 +-
|
.../Properties/AssemblyInfo.cs | 2 +-
|
||||||
Tools/ArdupilotMegaPlanner/SerialOutput.cs | 13 +-
|
Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 59 +-
|
||||||
Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 4 +-
|
Tools/ArdupilotMegaPlanner/Setup/Setup.resx | 4 +-
|
||||||
Tools/ArdupilotMegaPlanner/Updater/Updater.csproj | 2 +-
|
Tools/ArdupilotMegaPlanner/app.config | 6 -
|
||||||
.../bin/Release/ArdupilotMegaPlanner.application | 2 +-
|
.../bin/Release/ArdupilotMegaPlanner.application | 2 +-
|
||||||
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194944 -> 2188288 bytes
|
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2188288 -> 2194432 bytes
|
||||||
.../bin/Release/GCSViews/Configuration.resx | 2088 +++++-------
|
.../bin/Release/ArdupilotMegaPlanner.exe.config | 6 -
|
||||||
.../bin/Release/GCSViews/FlightData.resx | 604 ++--
|
.../bin/Release/GCSViews/FlightPlanner.resx | 2733 ++++++++++----------
|
||||||
.../bin/Release/JoystickSetup.resx | 763 ++++-
|
.../bin/Release/Setup/Setup.resx | 4 +-
|
||||||
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
|
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
|
||||||
|
.../bin/Release/dataflashlog.xml | 43 +-
|
||||||
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
|
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
|
||||||
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
|
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
|
||||||
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
|
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
|
||||||
Tools/scripts/format.sh | 13 +
|
Tools/ArdupilotMegaPlanner/dataflashlog.xml | 43 +-
|
||||||
apo/ControllerPlane.h | 329 +-
|
Tools/ArdupilotMegaPlanner/mavlinklist.pl | 13 +-
|
||||||
apo/ControllerQuad.h | 414 +--
|
Tools/autotest/ArduCopter.parm | 32 +
|
||||||
apo/PlaneEasystar.h | 18 +-
|
Tools/autotest/ArduPlane.parm | 38 +
|
||||||
apo/QuadArducopter.h | 17 +-
|
Tools/autotest/README | 1 +
|
||||||
apo/apo.pde | 5 +-
|
Tools/autotest/ap1.txt | 7 +
|
||||||
libraries/APM_BMP085/APM_BMP085.h | 2 +-
|
Tools/autotest/arducopter.py | 340 +++
|
||||||
libraries/APM_PI/APM_PI.cpp | 8 +-
|
Tools/autotest/arduplane.py | 269 ++
|
||||||
libraries/APO/APO.h | 6 +-
|
Tools/autotest/autotest.py | 283 ++
|
||||||
libraries/APO/APO_DefaultSetup.h | 321 +-
|
Tools/autotest/common.py | 181 ++
|
||||||
libraries/APO/AP_ArmingMechanism.cpp | 14 +-
|
Tools/autotest/mission1.txt | 11 +
|
||||||
libraries/APO/AP_ArmingMechanism.h | 10 +-
|
Tools/autotest/mission_ttt.txt | 28 +
|
||||||
libraries/APO/AP_Autopilot.cpp | 461 ++--
|
Tools/autotest/util.py | 179 ++
|
||||||
libraries/APO/AP_Autopilot.h | 195 +-
|
Tools/autotest/web/css/images/bg.png | Bin 0 -> 161 bytes
|
||||||
libraries/APO/AP_BatteryMonitor.h | 1 -
|
Tools/autotest/web/css/images/logo.png | Bin 0 -> 8440 bytes
|
||||||
libraries/APO/AP_CommLink.cpp | 1280 ++++----
|
Tools/autotest/web/css/main.css | 132 +
|
||||||
libraries/APO/AP_CommLink.h | 126 +-
|
Tools/autotest/web/index.html | 42 +
|
||||||
libraries/APO/AP_Controller.cpp | 111 +-
|
apo/.cproject | 46 -
|
||||||
libraries/APO/AP_Controller.h | 402 ++-
|
apo/.project | 79 -
|
||||||
libraries/APO/AP_Guide.cpp | 429 ++-
|
libraries/.cproject | 270 --
|
||||||
libraries/APO/AP_Guide.h | 203 +-
|
libraries/.project | 79 -
|
||||||
libraries/APO/AP_HardwareAbstractionLayer.cpp | 1 +
|
libraries/APM_BMP085/APM_BMP085.cpp | 26 +-
|
||||||
libraries/APO/AP_HardwareAbstractionLayer.h | 258 +-
|
libraries/APM_BMP085/APM_BMP085.h | 6 +-
|
||||||
libraries/APO/AP_MavlinkCommand.cpp | 304 +-
|
libraries/APM_BMP085/APM_BMP085_hil.h | 3 -
|
||||||
libraries/APO/AP_MavlinkCommand.h | 654 ++--
|
libraries/APM_PI/APM_PI.cpp | 17 +-
|
||||||
libraries/APO/AP_Navigator.cpp | 298 +-
|
libraries/APM_PI/APM_PI.h | 3 +-
|
||||||
libraries/APO/AP_Navigator.h | 358 +-
|
libraries/APO/APO_DefaultSetup.h | 2 +-
|
||||||
libraries/APO/AP_RcChannel.cpp | 125 +-
|
libraries/APO/AP_Guide.cpp | 57 +-
|
||||||
libraries/APO/AP_RcChannel.h | 103 +-
|
libraries/APO/AP_Guide.h | 4 -
|
||||||
libraries/APO/AP_Var_keys.h | 21 +-
|
libraries/AP_Common/AP_Common.h | 20 +
|
||||||
libraries/APO/constants.h | 1 +
|
libraries/AP_Common/Arduino.mk | 3 +
|
||||||
libraries/APO/examples/MavlinkTest/MavlinkTest.pde | 64 +-
|
libraries/AP_Common/menu.cpp | 6 +-
|
||||||
libraries/APO/examples/ServoManual/ServoManual.pde | 144 +-
|
libraries/AP_DCM/AP_DCM.cpp | 25 +-
|
||||||
libraries/APO/examples/ServoSweep/ServoSweep.pde | 184 +-
|
libraries/AP_DCM/AP_DCM.h | 6 +-
|
||||||
libraries/AP_Common/AP_Common.h | 20 +-
|
libraries/AP_GPS/AP_GPS_IMU.cpp | 2 +-
|
||||||
libraries/AP_Common/AP_Test.h | 4 +-
|
libraries/AP_Mount/AP_Mount.cpp | 296 +++
|
||||||
libraries/AP_Common/AP_Var.cpp | 80 +-
|
libraries/AP_Mount/AP_Mount.h | 96 +
|
||||||
libraries/AP_Common/AP_Var.h | 12 +-
|
libraries/DataFlash/DataFlash.cpp | 1 +
|
||||||
libraries/AP_Common/c++.cpp | 22 +-
|
libraries/DataFlash/DataFlash.h | 40 +-
|
||||||
libraries/AP_Common/examples/menu/menu.pde | 22 +-
|
libraries/Desktop/Desktop.mk | 32 +-
|
||||||
libraries/AP_Common/include/menu.h | 186 +-
|
libraries/Desktop/Makefile.desktop | 17 +-
|
||||||
libraries/AP_Common/menu.cpp | 198 +-
|
libraries/Desktop/README | 33 +-
|
||||||
libraries/AP_DCM/AP_DCM_HIL.cpp | 12 +-
|
libraries/Desktop/support/Arduino.cpp | 9 +-
|
||||||
libraries/AP_GPS/AP_GPS_406.cpp | 72 +-
|
libraries/Desktop/support/DataFlash.cpp | 259 ++
|
||||||
libraries/AP_GPS/AP_GPS_406.h | 8 +-
|
libraries/Desktop/support/FastSerial.cpp | 32 +-
|
||||||
libraries/AP_GPS/AP_GPS_Auto.cpp | 316 +-
|
libraries/Desktop/support/desktop.h | 10 +
|
||||||
libraries/AP_GPS/AP_GPS_Auto.h | 58 +-
|
libraries/Desktop/support/digital.c | 22 +
|
||||||
libraries/AP_GPS/AP_GPS_HIL.cpp | 18 +-
|
libraries/Desktop/support/ftoa_engine.c | 7 -
|
||||||
libraries/AP_GPS/AP_GPS_HIL.h | 10 +-
|
libraries/Desktop/support/main.cpp | 75 +-
|
||||||
libraries/AP_GPS/AP_GPS_IMU.cpp | 294 +-
|
libraries/Desktop/support/ultoa_invert.c | 12 -
|
||||||
libraries/AP_GPS/AP_GPS_IMU.h | 68 +-
|
libraries/FastSerial/vprintf.cpp | 32 +-
|
||||||
libraries/AP_GPS/AP_GPS_MTK.cpp | 226 +-
|
.../GCS_MAVLink/message_definitions/common.xml | 6 +-
|
||||||
libraries/AP_GPS/AP_GPS_MTK.h | 74 +-
|
.../message_definitions_v1.0/common.xml | 22 +-
|
||||||
libraries/AP_GPS/AP_GPS_MTK16.cpp | 240 +-
|
libraries/RC_Channel/RC_Channel.cpp | 4 +
|
||||||
libraries/AP_GPS/AP_GPS_MTK16.h | 78 +-
|
libraries/RC_Channel/RC_Channel_aux.cpp | 46 +
|
||||||
libraries/AP_GPS/AP_GPS_NMEA.cpp | 528 ++--
|
libraries/RC_Channel/RC_Channel_aux.h | 13 +-
|
||||||
libraries/AP_GPS/AP_GPS_NMEA.h | 118 +-
|
140 files changed, 10797 insertions(+), 7801 deletions(-)
|
||||||
libraries/AP_GPS/AP_GPS_None.h | 8 +-
|
create mode 100644 .project
|
||||||
libraries/AP_GPS/AP_GPS_SIRF.cpp | 280 +-
|
delete mode 100644 ArduBoat/.cproject
|
||||||
libraries/AP_GPS/AP_GPS_SIRF.h | 130 +-
|
delete mode 100644 ArduBoat/.project
|
||||||
libraries/AP_GPS/AP_GPS_Shim.h | 38 +-
|
delete mode 100644 ArduBoat/ArduBoat.cpp
|
||||||
libraries/AP_GPS/AP_GPS_UBLOX.cpp | 292 +-
|
delete mode 100644 ArduCopter/.cproject
|
||||||
libraries/AP_GPS/AP_GPS_UBLOX.h | 184 +-
|
delete mode 100644 ArduCopter/.project
|
||||||
libraries/AP_GPS/GPS.cpp | 50 +-
|
delete mode 100644 ArduPlane/.cproject
|
||||||
libraries/AP_GPS/GPS.h | 330 +-
|
delete mode 100644 ArduPlane/.project
|
||||||
.../AP_GPS/examples/GPS_406_test/GPS_406_test.pde | 62 +-
|
delete mode 100644 ArduRover/.cproject
|
||||||
.../examples/GPS_AUTO_test/GPS_AUTO_test.pde | 42 +-
|
delete mode 100644 ArduRover/.project
|
||||||
.../AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde | 60 +-
|
delete mode 100644 ArduRover/ArduRover.cpp
|
||||||
.../examples/GPS_NMEA_test/GPS_NMEA_test.pde | 81 +-
|
create mode 100644 Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
|
||||||
.../examples/GPS_UBLOX_test/GPS_UBLOX_test.pde | 60 +-
|
create mode 100644 Tools/autotest/ArduCopter.parm
|
||||||
libraries/Desktop/Desktop.mk | 2 +-
|
create mode 100644 Tools/autotest/ArduPlane.parm
|
||||||
libraries/Desktop/Makefile.desktop | 3 +
|
create mode 100644 Tools/autotest/README
|
||||||
libraries/GCS_MAVLink/GCS_MAVLink.cpp | 6 +-
|
create mode 100644 Tools/autotest/ap1.txt
|
||||||
libraries/GCS_MAVLink/GCS_MAVLink.h | 18 +-
|
create mode 100644 Tools/autotest/arducopter.py
|
||||||
.../include/ardupilotmega/ardupilotmega.h | 74 +-
|
create mode 100644 Tools/autotest/arduplane.py
|
||||||
.../include/ardupilotmega/mavlink_msg_ap_adc.h | 254 ++
|
create mode 100755 Tools/autotest/autotest.py
|
||||||
.../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++
|
create mode 100644 Tools/autotest/common.py
|
||||||
.../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++
|
create mode 100644 Tools/autotest/mission1.txt
|
||||||
.../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++
|
create mode 100644 Tools/autotest/mission_ttt.txt
|
||||||
.../ardupilotmega/mavlink_msg_mount_control.h | 254 ++
|
create mode 100644 Tools/autotest/util.py
|
||||||
.../ardupilotmega/mavlink_msg_mount_status.h | 232 ++
|
create mode 100644 Tools/autotest/web/css/images/bg.png
|
||||||
.../GCS_MAVLink/include/ardupilotmega/testsuite.h | 340 ++
|
create mode 100644 Tools/autotest/web/css/images/logo.png
|
||||||
.../GCS_MAVLink/include/ardupilotmega/version.h | 2 +-
|
create mode 100644 Tools/autotest/web/css/main.css
|
||||||
libraries/GCS_MAVLink/include/bittest.c | 39 -
|
create mode 100644 Tools/autotest/web/index.html
|
||||||
libraries/GCS_MAVLink/include/common/common.h | 52 +-
|
delete mode 100644 apo/.cproject
|
||||||
.../mavlink_msg_attitude_controller_output.h | 169 -
|
delete mode 100644 apo/.project
|
||||||
.../include/common/mavlink_msg_attitude_new.h | 268 --
|
delete mode 100644 libraries/.cproject
|
||||||
.../include/common/mavlink_msg_auth_key.h | 6 +-
|
delete mode 100644 libraries/.project
|
||||||
.../common/mavlink_msg_change_operator_control.h | 6 +-
|
create mode 100644 libraries/AP_Mount/AP_Mount.cpp
|
||||||
.../include/common/mavlink_msg_debug_vect.h | 6 +-
|
create mode 100644 libraries/AP_Mount/AP_Mount.h
|
||||||
.../include/common/mavlink_msg_full_state.h | 428 ---
|
create mode 100644 libraries/Desktop/support/DataFlash.cpp
|
||||||
.../include/common/mavlink_msg_gps_status.h | 30 +-
|
create mode 100644 libraries/Desktop/support/desktop.h
|
||||||
.../include/common/mavlink_msg_named_value_float.h | 6 +-
|
create mode 100644 libraries/Desktop/support/digital.c
|
||||||
.../include/common/mavlink_msg_named_value_int.h | 6 +-
|
delete mode 100644 libraries/Desktop/support/ftoa_engine.c
|
||||||
.../common/mavlink_msg_object_detection_event.h | 6 +-
|
delete mode 100644 libraries/Desktop/support/ultoa_invert.c
|
||||||
.../common/mavlink_msg_param_request_read.h | 6 +-
|
|
||||||
.../include/common/mavlink_msg_param_set.h | 6 +-
|
|
||||||
.../include/common/mavlink_msg_param_value.h | 6 +-
|
|
||||||
.../mavlink_msg_position_controller_output.h | 169 -
|
|
||||||
.../mavlink_msg_request_dynamic_gyro_calibration.h | 177 -
|
|
||||||
.../mavlink_msg_request_static_calibration.h | 138 -
|
|
||||||
.../common/mavlink_msg_set_roll_pitch_yaw.h | 184 -
|
|
||||||
.../common/mavlink_msg_set_roll_pitch_yaw_speed.h | 184 -
|
|
||||||
.../include/common/mavlink_msg_statustext.h | 6 +-
|
|
||||||
.../mavlink_msg_waypoint_set_global_reference.h | 294 --
|
|
||||||
libraries/GCS_MAVLink/include/common/testsuite.h | 30 +-
|
|
||||||
libraries/GCS_MAVLink/include/common/version.h | 2 +-
|
|
||||||
libraries/GCS_MAVLink/include/documentation.dox | 41 -
|
|
||||||
libraries/GCS_MAVLink/include/mavlink_helpers.h | 8 +-
|
|
||||||
libraries/GCS_MAVLink/include/minimal/mavlink.h | 11 -
|
|
||||||
.../include/minimal/mavlink_msg_heartbeat.h | 132 -
|
|
||||||
libraries/GCS_MAVLink/include/minimal/minimal.h | 45 -
|
|
||||||
libraries/GCS_MAVLink/include/pixhawk/mavlink.h | 11 -
|
|
||||||
.../include/pixhawk/mavlink_msg_attitude_control.h | 257 --
|
|
||||||
.../include/pixhawk/mavlink_msg_aux_status.h | 204 -
|
|
||||||
.../include/pixhawk/mavlink_msg_brief_feature.h | 249 --
|
|
||||||
.../include/pixhawk/mavlink_msg_control_status.h | 203 -
|
|
||||||
.../mavlink_msg_data_transmission_handshake.h | 174 -
|
|
||||||
.../include/pixhawk/mavlink_msg_debug_vect.h | 156 -
|
|
||||||
.../pixhawk/mavlink_msg_encapsulated_data.h | 124 -
|
|
||||||
.../pixhawk/mavlink_msg_encapsulated_image.h | 76 -
|
|
||||||
.../include/pixhawk/mavlink_msg_get_image_ack.h | 104 -
|
|
||||||
.../include/pixhawk/mavlink_msg_image_available.h | 586 ---
|
|
||||||
.../pixhawk/mavlink_msg_image_trigger_control.h | 101 -
|
|
||||||
.../include/pixhawk/mavlink_msg_image_triggered.h | 352 --
|
|
||||||
.../include/pixhawk/mavlink_msg_manual_control.h | 191 -
|
|
||||||
.../include/pixhawk/mavlink_msg_marker.h | 236 --
|
|
||||||
.../include/pixhawk/mavlink_msg_pattern_detected.h | 160 -
|
|
||||||
.../pixhawk/mavlink_msg_point_of_interest.h | 241 --
|
|
||||||
.../mavlink_msg_point_of_interest_connection.h | 307 --
|
|
||||||
.../mavlink_msg_position_control_offset_set.h | 206 -
|
|
||||||
.../mavlink_msg_position_control_setpoint.h | 192 -
|
|
||||||
.../mavlink_msg_position_control_setpoint_set.h | 226 --
|
|
||||||
.../include/pixhawk/mavlink_msg_raw_aux.h | 226 --
|
|
||||||
.../pixhawk/mavlink_msg_request_data_stream.h | 118 -
|
|
||||||
.../mavlink_msg_request_dynamic_gyro_calibration.h | 123 -
|
|
||||||
.../mavlink_msg_request_static_calibration.h | 90 -
|
|
||||||
.../include/pixhawk/mavlink_msg_set_altitude.h | 78 -
|
|
||||||
.../include/pixhawk/mavlink_msg_set_cam_shutter.h | 197 -
|
|
||||||
.../include/pixhawk/mavlink_msg_watchdog_command.h | 158 -
|
|
||||||
.../pixhawk/mavlink_msg_watchdog_heartbeat.h | 124 -
|
|
||||||
.../pixhawk/mavlink_msg_watchdog_process_info.h | 186 -
|
|
||||||
.../pixhawk/mavlink_msg_watchdog_process_status.h | 200 -
|
|
||||||
libraries/GCS_MAVLink/include/pixhawk/pixhawk.h | 79 -
|
|
||||||
libraries/GCS_MAVLink/include/protocol.h | 37 +-
|
|
||||||
libraries/GCS_MAVLink/include/slugs/mavlink.h | 11 -
|
|
||||||
.../include/slugs/mavlink_msg_air_data.h | 148 -
|
|
||||||
.../include/slugs/mavlink_msg_cpu_load.h | 138 -
|
|
||||||
.../include/slugs/mavlink_msg_ctrl_srfc_pt.h | 121 -
|
|
||||||
.../include/slugs/mavlink_msg_data_log.h | 216 --
|
|
||||||
.../include/slugs/mavlink_msg_diagnostic.h | 210 --
|
|
||||||
.../include/slugs/mavlink_msg_filtered_data.h | 216 --
|
|
||||||
.../include/slugs/mavlink_msg_gps_date_time.h | 203 -
|
|
||||||
.../include/slugs/mavlink_msg_mid_lvl_cmds.h | 167 -
|
|
||||||
.../GCS_MAVLink/include/slugs/mavlink_msg_pid.h | 130 -
|
|
||||||
.../include/slugs/mavlink_msg_pilot_console.h | 145 -
|
|
||||||
.../include/slugs/mavlink_msg_pwm_commands.h | 235 --
|
|
||||||
.../include/slugs/mavlink_msg_sensor_bias.h | 216 --
|
|
||||||
.../include/slugs/mavlink_msg_slugs_action.h | 138 -
|
|
||||||
.../include/slugs/mavlink_msg_slugs_navigation.h | 272 --
|
|
||||||
libraries/GCS_MAVLink/include/slugs/slugs.h | 56 -
|
|
||||||
libraries/GCS_MAVLink/include/ualberta/mavlink.h | 11 -
|
|
||||||
.../include/ualberta/mavlink_msg_nav_filter_bias.h | 242 --
|
|
||||||
.../ualberta/mavlink_msg_radio_calibration.h | 204 -
|
|
||||||
.../mavlink_msg_request_radio_calibration.h | 59 -
|
|
||||||
.../ualberta/mavlink_msg_request_rc_channels.h | 101 -
|
|
||||||
.../ualberta/mavlink_msg_ualberta_sys_status.h | 135 -
|
|
||||||
libraries/GCS_MAVLink/include/ualberta/ualberta.h | 79 -
|
|
||||||
.../include_v1.0/ardupilotmega/ardupilotmega.h | 122 +
|
|
||||||
.../include_v1.0/ardupilotmega/mavlink.h | 27 +
|
|
||||||
.../ardupilotmega/mavlink_msg_ap_adc.h | 254 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_meminfo.h | 166 +
|
|
||||||
.../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_mount_control.h | 254 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_mount_status.h | 232 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_sensor_offsets.h | 386 ++
|
|
||||||
.../ardupilotmega/mavlink_msg_set_mag_offsets.h | 232 ++
|
|
||||||
.../include_v1.0/ardupilotmega/testsuite.h | 538 +++
|
|
||||||
.../include_v1.0/ardupilotmega/version.h | 12 +
|
|
||||||
libraries/GCS_MAVLink/include_v1.0/checksum.h | 89 +
|
|
||||||
libraries/GCS_MAVLink/include_v1.0/common/common.h | 429 +++
|
|
||||||
.../GCS_MAVLink/include_v1.0/common/mavlink.h | 27 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_attitude.h | 276 ++
|
|
||||||
.../common/mavlink_msg_attitude_quaternion.h | 298 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_auth_key.h | 144 +
|
|
||||||
.../common/mavlink_msg_change_operator_control.h | 204 +
|
|
||||||
.../mavlink_msg_change_operator_control_ack.h | 188 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_command_ack.h | 166 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_command_long.h | 364 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_data_stream.h | 188 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_debug.h | 188 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_debug_vect.h | 226 ++
|
|
||||||
.../common/mavlink_msg_extended_message.h | 188 +
|
|
||||||
.../common/mavlink_msg_global_position_int.h | 320 ++
|
|
||||||
.../mavlink_msg_global_position_setpoint_int.h | 232 ++
|
|
||||||
.../mavlink_msg_global_vision_position_estimate.h | 276 ++
|
|
||||||
.../common/mavlink_msg_gps_global_origin.h | 188 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_gps_raw_int.h | 342 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_gps_status.h | 252 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_heartbeat.h | 251 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_hil_controls.h | 364 ++
|
|
||||||
.../common/mavlink_msg_hil_rc_inputs_raw.h | 430 +++
|
|
||||||
.../include_v1.0/common/mavlink_msg_hil_state.h | 474 +++
|
|
||||||
.../common/mavlink_msg_local_position_ned.h | 276 ++
|
|
||||||
.../common/mavlink_msg_local_position_setpoint.h | 232 ++
|
|
||||||
.../common/mavlink_msg_manual_control.h | 320 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_memory_vect.h | 204 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_mission_ack.h | 188 +
|
|
||||||
.../common/mavlink_msg_mission_clear_all.h | 166 +
|
|
||||||
.../common/mavlink_msg_mission_count.h | 188 +
|
|
||||||
.../common/mavlink_msg_mission_current.h | 144 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_mission_item.h | 430 +++
|
|
||||||
.../common/mavlink_msg_mission_item_reached.h | 144 +
|
|
||||||
.../common/mavlink_msg_mission_request.h | 188 +
|
|
||||||
.../common/mavlink_msg_mission_request_list.h | 166 +
|
|
||||||
.../mavlink_msg_mission_request_partial_list.h | 210 ++
|
|
||||||
.../common/mavlink_msg_mission_set_current.h | 188 +
|
|
||||||
.../mavlink_msg_mission_write_partial_list.h | 210 ++
|
|
||||||
.../common/mavlink_msg_named_value_float.h | 182 +
|
|
||||||
.../common/mavlink_msg_named_value_int.h | 182 +
|
|
||||||
.../common/mavlink_msg_nav_controller_output.h | 298 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_optical_flow.h | 254 ++
|
|
||||||
.../common/mavlink_msg_param_request_list.h | 166 +
|
|
||||||
.../common/mavlink_msg_param_request_read.h | 204 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_param_set.h | 226 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_param_value.h | 226 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_ping.h | 210 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_raw_imu.h | 342 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_raw_pressure.h | 232 ++
|
|
||||||
.../common/mavlink_msg_rc_channels_override.h | 342 ++
|
|
||||||
.../common/mavlink_msg_rc_channels_raw.h | 364 ++
|
|
||||||
.../common/mavlink_msg_rc_channels_scaled.h | 364 ++
|
|
||||||
.../common/mavlink_msg_request_data_stream.h | 232 ++
|
|
||||||
...link_msg_roll_pitch_yaw_speed_thrust_setpoint.h | 232 ++
|
|
||||||
.../mavlink_msg_roll_pitch_yaw_thrust_setpoint.h | 232 ++
|
|
||||||
.../common/mavlink_msg_safety_allowed_area.h | 276 ++
|
|
||||||
.../common/mavlink_msg_safety_set_allowed_area.h | 320 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_scaled_imu.h | 342 ++
|
|
||||||
.../common/mavlink_msg_scaled_pressure.h | 210 ++
|
|
||||||
.../common/mavlink_msg_servo_output_raw.h | 342 ++
|
|
||||||
.../mavlink_msg_set_global_position_setpoint_int.h | 232 ++
|
|
||||||
.../common/mavlink_msg_set_gps_global_origin.h | 210 ++
|
|
||||||
.../mavlink_msg_set_local_position_setpoint.h | 276 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_set_mode.h | 188 +
|
|
||||||
.../mavlink_msg_set_roll_pitch_yaw_speed_thrust.h | 254 ++
|
|
||||||
.../common/mavlink_msg_set_roll_pitch_yaw_thrust.h | 254 ++
|
|
||||||
.../common/mavlink_msg_state_correction.h | 320 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_statustext.h | 160 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_sys_status.h | 408 ++
|
|
||||||
.../include_v1.0/common/mavlink_msg_system_time.h | 166 +
|
|
||||||
.../include_v1.0/common/mavlink_msg_vfr_hud.h | 254 ++
|
|
||||||
.../common}/mavlink_msg_vicon_position_estimate.h | 198 +-
|
|
||||||
.../common}/mavlink_msg_vision_position_estimate.h | 198 +-
|
|
||||||
.../common}/mavlink_msg_vision_speed_estimate.h | 148 +-
|
|
||||||
.../GCS_MAVLink/include_v1.0/common/testsuite.h | 3908 ++++++++++++++++++++
|
|
||||||
.../GCS_MAVLink/include_v1.0/common/version.h | 12 +
|
|
||||||
.../GCS_MAVLink/include_v1.0/mavlink_helpers.h | 488 +++
|
|
||||||
libraries/GCS_MAVLink/include_v1.0/mavlink_types.h | 182 +
|
|
||||||
libraries/GCS_MAVLink/include_v1.0/protocol.h | 319 ++
|
|
||||||
.../message_definitions/ardupilotmega.xml | 132 +
|
|
||||||
libraries/GCS_MAVLink/message_definitions/test.xml | 31 +
|
|
||||||
.../message_definitions_v1.0/ardupilotmega.xml | 177 +
|
|
||||||
.../message_definitions_v1.0/common.xml | 1536 ++++++++
|
|
||||||
.../message_definitions_v1.0/minimal.xml | 16 +
|
|
||||||
.../message_definitions_v1.0/pixhawk.xml | 193 +
|
|
||||||
.../GCS_MAVLink/message_definitions_v1.0/slugs.xml | 144 +
|
|
||||||
.../GCS_MAVLink/message_definitions_v1.0/test.xml | 31 +
|
|
||||||
.../message_definitions_v1.0/ualberta.xml | 54 +
|
|
||||||
libraries/RC_Channel/RC_Channel.cpp | 2 +-
|
|
||||||
libraries/RC_Channel/RC_Channel.h | 8 +-
|
|
||||||
libraries/RC_Channel/RC_Channel_aux.cpp | 2 +-
|
|
||||||
libraries/RC_Channel/RC_Channel_aux.h | 1 +
|
|
||||||
355 files changed, 43388 insertions(+), 22115 deletions(-)
|
|
||||||
delete mode 100644 ArduCopter/CMakeLists.txt
|
|
||||||
delete mode 100644 ArduPlane/.gitignore
|
|
||||||
delete mode 100644 ArduPlane/CMakeLists.txt
|
|
||||||
create mode 100644 ArduPlane/Mavlink_compat.h
|
|
||||||
create mode 100644 Tools/ArdupilotMegaPlanner/Camera.Designer.cs
|
|
||||||
create mode 100644 Tools/ArdupilotMegaPlanner/Camera.cs
|
|
||||||
create mode 100644 Tools/ArdupilotMegaPlanner/Camera.resx
|
|
||||||
create mode 100755 Tools/scripts/format.sh
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_configure.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_control.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_configure.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_control.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_status.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/bittest.c
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_controller_output.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_new.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_position_controller_output.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_static_calibration.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_global_reference.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/documentation.dox
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/minimal/minimal.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_attitude_control.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_aux_status.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_brief_feature.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_control_status.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_data_transmission_handshake.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_debug_vect.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_data.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_image.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_get_image_ack.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_trigger_control.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_manual_control.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_marker.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_pattern_detected.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest_connection.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_offset_set.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_raw_aux.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_data_stream.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_static_calibration.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_altitude.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_cam_shutter.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_command.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_info.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_status.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/pixhawk.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_filtered_data.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pid.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pilot_console.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pwm_commands.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/slugs/slugs.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_nav_filter_bias.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_radio_calibration.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_rc_channels.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h
|
|
||||||
delete mode 100644 libraries/GCS_MAVLink/include/ualberta/ualberta.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_ap_adc.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_control.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_configure.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_control.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_status.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/checksum.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/common.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_partial_list.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_write_partial_list.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h
|
|
||||||
rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vicon_position_estimate.h (54%)
|
|
||||||
rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_position_estimate.h (54%)
|
|
||||||
rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_speed_estimate.h (57%)
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/testsuite.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/version.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_helpers.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_types.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/include_v1.0/protocol.h
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions/test.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/common.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/test.xml
|
|
||||||
create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml
|
|
||||||
|
|
Loading…
Reference in New Issue