firmware build

This commit is contained in:
Michael Oborne 2011-10-13 12:19:35 +08:00
parent be10a861c0
commit af20d508dd
22 changed files with 727 additions and 851 deletions

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -277,7 +272,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c 0000000c r report_frame()::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char 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 GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
00000090 t dump_log(unsigned char, Menu::arg const*) 00000090 t dump_log(unsigned char, Menu::arg const*)
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning() 00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode() 000000a0 t Log_Read_Mode()
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -566,45 +568,44 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e t send_extended_status1(mavlink_channel_t, unsigned int) 0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
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 set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001cc t start_new_log()
000001ca t mavlink_delay(unsigned long)
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000210 t setup_motors(unsigned char, Menu::arg const*) 00000210 t setup_motors(unsigned char, Menu::arg const*)
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*) 00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005ee t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001c58 T loop 00001bc4 T loop

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -277,7 +272,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c 0000000c r report_frame()::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t report_version() 00000050 t report_version()
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
0000008e t dump_log(unsigned char, Menu::arg const*) 0000008e t dump_log(unsigned char, Menu::arg const*)
00000090 t report_tuning() 00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode() 0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -566,45 +568,44 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e t send_extended_status1(mavlink_channel_t, unsigned int) 0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
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 set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001cc t start_new_log()
000001ca t mavlink_delay(unsigned long)
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000210 t setup_motors(unsigned char, Menu::arg const*) 00000210 t setup_motors(unsigned char, Menu::arg const*)
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*) 0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005ec t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001c56 T loop 00001bc2 T loop

View File

@ -6,71 +6,60 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined autogenerated:103: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined autogenerated:109: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:132: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:138: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/Log.pde:738: warning: 'void Log_Write_Attitude()' defined but not used /root/apm/ardupilot-mega/ArduCopter/Log.pde:738: warning: 'void Log_Write_Attitude()' defined but not used
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
autogenerated:268: warning: 'void ReadSCP1000()' declared 'static' but never defined autogenerated:245: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:269: warning: 'void init_barometer()' declared 'static' but never defined autogenerated:246: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:271: warning: 'long int read_barometer()' declared 'static' but never defined autogenerated:248: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:272: warning: 'void read_airspeed()' declared 'static' but never defined autogenerated:249: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:273: warning: 'void zero_airspeed()' declared 'static' but never defined autogenerated:250: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:358: warning: 'old_altitude' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:336: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:376: warning: 'abs_pressure' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:354: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'ground_pressure' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:355: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'ground_temperature' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:356: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:383: warning: 'baro_alt' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:361: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
@ -105,8 +94,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -71,7 +69,6 @@
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 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -147,8 +144,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -276,7 +271,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 AP_IMU_Shim 0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
@ -299,6 +294,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> >
@ -344,6 +340,7 @@
0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -354,6 +351,8 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 t startup_ground()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -369,7 +368,6 @@
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c 00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c 00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 t startup_ground()
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::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
@ -381,13 +379,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B adc 00000016 B adc
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int) 0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
@ -397,6 +393,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -418,7 +415,6 @@
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -434,18 +430,21 @@
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002c B imu 0000002c B imu
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -457,20 +456,20 @@
0000003a t report_imu() 0000003a t report_imu()
0000003a B g_gps_driver 0000003a B g_gps_driver
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char 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 GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
@ -479,6 +478,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
00000057 B dcm 00000057 B dcm
0000005c t get_num_logs() 0000005c t get_num_logs()
@ -490,10 +490,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -502,19 +504,20 @@
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
00000090 t init_compass() 00000090 t init_compass()
00000090 t dump_log(unsigned char, Menu::arg const*) 00000090 t dump_log(unsigned char, Menu::arg const*)
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning() 00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode() 000000a0 t Log_Read_Mode()
@ -527,7 +530,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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&)
000000be t update_events() 000000be t update_events()
000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*)
@ -554,43 +556,42 @@
000000ee t report_batt_monitor() 000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 t send_extended_status1(mavlink_channel_t, 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) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
0000012e t arm_motors()
00000130 t report_compass() 00000130 t report_compass()
00000132 t arm_motors()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000184 t test_imu(unsigned char, Menu::arg const*) 00000184 t test_imu(unsigned char, Menu::arg const*)
00000198 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001c8 t setup_motors(unsigned char, Menu::arg const*) 000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001ca t mavlink_delay(unsigned long) 000001cc t start_new_log()
000001ce t start_new_log()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000216 t set_mode(unsigned char)
00000220 t test_wp(unsigned char, Menu::arg const*) 00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000330 t tuning() 00000330 t tuning()
@ -600,10 +601,10 @@
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
00000588 t __static_initialization_and_destruction_0(int, int) 00000588 t __static_initialization_and_destruction_0(int, int)
000005de t init_ardupilot() 000005d4 t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
000014f2 T GCS_MAVLINK::handleMessage(__mavlink_message*) 00001530 T loop
000015ac T loop 00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)

View File

@ -6,71 +6,60 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()': /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()': /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined autogenerated:103: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined autogenerated:109: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:132: warning: 'void Log_Write_Raw()' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:138: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/Log.pde:738: warning: 'void Log_Write_Attitude()' defined but not used /root/apm/ardupilot-mega/ArduCopter/Log.pde:738: warning: 'void Log_Write_Attitude()' defined but not used
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
autogenerated:268: warning: 'void ReadSCP1000()' declared 'static' but never defined autogenerated:245: warning: 'void ReadSCP1000()' declared 'static' but never defined
autogenerated:269: warning: 'void init_barometer()' declared 'static' but never defined autogenerated:246: warning: 'void init_barometer()' declared 'static' but never defined
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
autogenerated:271: warning: 'long int read_barometer()' declared 'static' but never defined autogenerated:248: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:272: warning: 'void read_airspeed()' declared 'static' but never defined autogenerated:249: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:273: warning: 'void zero_airspeed()' declared 'static' but never defined autogenerated:250: warning: 'void zero_airspeed()' declared 'static' but never defined
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:358: warning: 'old_altitude' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:336: warning: 'old_altitude' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:376: warning: 'abs_pressure' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:354: warning: 'abs_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'ground_pressure' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:355: warning: 'ground_pressure' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:378: warning: 'ground_temperature' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:356: warning: 'ground_temperature' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:383: warning: 'baro_alt' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:361: warning: 'baro_alt' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
@ -105,8 +94,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -71,7 +69,6 @@
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 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -147,8 +144,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -276,7 +271,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 AP_IMU_Shim 0000000c V vtable for AP_IMU_Shim
0000000c V vtable for IMU 0000000c V vtable for IMU
0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
@ -299,6 +294,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> >
@ -344,6 +340,7 @@
0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f r test_imu(unsigned char, Menu::arg const*)::__c
00000010 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -354,6 +351,8 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 t startup_ground()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -369,7 +368,6 @@
00000013 r setup_compass(unsigned char, Menu::arg const*)::__c 00000013 r setup_compass(unsigned char, Menu::arg const*)::__c
00000013 r change_command(unsigned char)::__c 00000013 r change_command(unsigned char)::__c
00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c
00000014 t startup_ground()
00000014 W AP_VarT<signed char>::unserialize(void*, unsigned int) 00000014 W AP_VarT<signed char>::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
@ -381,13 +379,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B adc 00000016 B adc
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int) 0000001c W AP_VarS<Matrix3<float> >::unserialize(void*, unsigned int)
@ -397,6 +393,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -418,7 +415,6 @@
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -434,18 +430,21 @@
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002c B imu 0000002c B imu
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -457,20 +456,20 @@
0000003a t report_imu() 0000003a t report_imu()
0000003a B g_gps_driver 0000003a B g_gps_driver
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t report_version() 00000050 t report_version()
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
@ -479,6 +478,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
00000057 B dcm 00000057 B dcm
0000005c t get_num_logs() 0000005c t get_num_logs()
@ -490,10 +490,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -502,19 +504,20 @@
00000080 T __vector_25 00000080 T __vector_25
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008e t dump_log(unsigned char, Menu::arg const*) 0000008e t dump_log(unsigned char, Menu::arg const*)
00000090 t init_compass() 00000090 t init_compass()
00000090 t report_tuning() 00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode() 0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
@ -527,7 +530,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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&)
000000be t update_events() 000000be t update_events()
000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t test_eedump(unsigned char, Menu::arg const*)
@ -554,43 +556,42 @@
000000ee t report_batt_monitor() 000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 t send_extended_status1(mavlink_channel_t, 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) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
0000012e t arm_motors()
00000130 t report_compass() 00000130 t report_compass()
00000132 t arm_motors()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000184 t test_imu(unsigned char, Menu::arg const*) 00000184 t test_imu(unsigned char, Menu::arg const*)
00000198 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) 00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001c8 t setup_motors(unsigned char, Menu::arg const*) 000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001ca t mavlink_delay(unsigned long) 000001cc t start_new_log()
000001ce t start_new_log()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
000001ea T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000216 t set_mode(unsigned char)
0000021c t test_wp(unsigned char, Menu::arg const*) 0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000330 t tuning() 00000330 t tuning()
@ -600,10 +601,10 @@
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
00000588 t __static_initialization_and_destruction_0(int, int) 00000588 t __static_initialization_and_destruction_0(int, int)
000005de t init_ardupilot() 000005d2 t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
000014f2 T GCS_MAVLINK::handleMessage(__mavlink_message*) 0000152e T loop
000015aa T loop 00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -277,7 +272,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c 0000000c r report_frame()::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char 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 GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
00000090 t dump_log(unsigned char, Menu::arg const*) 00000090 t dump_log(unsigned char, Menu::arg const*)
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning() 00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode() 000000a0 t Log_Read_Mode()
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -566,45 +568,44 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e t send_extended_status1(mavlink_channel_t, unsigned int) 0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
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 set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001c8 t setup_motors(unsigned char, Menu::arg const*) 000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001ca t mavlink_delay(unsigned long) 000001cc t start_new_log()
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*) 00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005f2 t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001b26 T loop 00001abe T loop

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -277,7 +272,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r report_frame()::__c 0000000c r report_frame()::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t report_version() 00000050 t report_version()
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
0000008e t dump_log(unsigned char, Menu::arg const*) 0000008e t dump_log(unsigned char, Menu::arg const*)
00000090 t report_tuning() 00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode() 0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -566,45 +568,44 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e t send_extended_status1(mavlink_channel_t, unsigned int) 0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
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 set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
000001c8 t setup_motors(unsigned char, Menu::arg const*) 000001c8 t setup_motors(unsigned char, Menu::arg const*)
000001ca t mavlink_delay(unsigned long) 000001cc t start_new_log()
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*) 0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005f0 t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001b24 T loop 00001abc T loop

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -278,7 +273,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r test_baro(unsigned char, Menu::arg const*)::__c 0000000c r test_baro(unsigned char, Menu::arg const*)::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char 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 GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
00000090 t dump_log(unsigned char, Menu::arg const*) 00000090 t dump_log(unsigned char, Menu::arg const*)
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning() 00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode() 000000a0 t Log_Read_Mode()
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -567,44 +569,43 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 t send_extended_status1(mavlink_channel_t, 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) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001cc t start_new_log()
000001ca t mavlink_delay(unsigned long)
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*) 00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005f2 t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001a86 T loop 000019fa T loop

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -278,7 +273,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r test_baro(unsigned char, Menu::arg const*)::__c 0000000c r test_baro(unsigned char, Menu::arg const*)::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t report_version() 00000050 t report_version()
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
0000008e t dump_log(unsigned char, Menu::arg const*) 0000008e t dump_log(unsigned char, Menu::arg const*)
00000090 t report_tuning() 00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode() 0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -567,44 +569,43 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int) 00000112 t send_extended_status1(mavlink_channel_t, 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) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001cc t start_new_log()
000001ca t mavlink_delay(unsigned long)
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*) 0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005f0 t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001a84 T loop 000019f8 T loop

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -278,7 +273,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r test_baro(unsigned char, Menu::arg const*)::__c 0000000c r test_baro(unsigned char, Menu::arg const*)::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char 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 GCS_MAVLINK::_find_parameter(unsigned int) 00000050 T GCS_MAVLINK::_find_parameter(unsigned int)
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
00000090 t dump_log(unsigned char, Menu::arg const*) 00000090 t dump_log(unsigned char, Menu::arg const*)
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning() 00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode() 000000a0 t Log_Read_Mode()
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -566,45 +568,44 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e t send_extended_status1(mavlink_channel_t, unsigned int) 0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
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 set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
0000015c t setup_motors(unsigned char, Menu::arg const*) 0000015c t setup_motors(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001cc t start_new_log()
000001ca t mavlink_delay(unsigned long)
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*) 00000220 t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005ee t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001b66 T loop 00001ad2 T loop

View File

@ -6,61 +6,43 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
/root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/Parameters.h:390: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_loiter_turns()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:302: warning: statement has no effect
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_nav_wp()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:413: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'bool verify_loiter_time()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:440: warning: comparison between signed and unsigned integer expressions
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde: In function 'void do_jump()':
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:653: warning: unused variable 'temp'
autogenerated: At global scope: autogenerated: At global scope:
autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined autogenerated:107: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined autogenerated:117: warning: 'void decrement_WP_index()' declared 'static' but never defined
autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined
autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined
autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined
autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined
autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined
autogenerated:89: warning: 'void print_position()' declared 'static' but never defined
autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined
autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined
autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined
autogenerated:136: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:146: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
autogenerated:208: warning: 'void heli_init_swash()' declared 'static' but never defined autogenerated:179: warning: 'void heli_init_swash()' declared 'static' but never defined
autogenerated:209: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined autogenerated:180: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined
autogenerated:210: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined autogenerated:181: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined
autogenerated:233: warning: 'void debug_motors()' declared 'static' but never defined autogenerated:208: warning: 'void debug_motors()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:171: warning: 'int get_loiter_angle()' defined but not used
autogenerated:252: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined autogenerated:229: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
autogenerated:253: warning: 'long int cross_track_test()' declared 'static' but never defined autogenerated:230: warning: 'long int cross_track_test()' declared 'static' but never defined
autogenerated:254: warning: 'void reset_crosstrack()' declared 'static' but never defined autogenerated:231: warning: 'void reset_crosstrack()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:235: warning: 'long int get_altitude_above_home()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used /root/apm/ardupilot-mega/ArduCopter/navigation.pde:256: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:129: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/radio.pde:186: warning: 'void trim_yaw()' defined but not used /root/apm/ardupilot-mega/ArduCopter/radio.pde:187: warning: 'void trim_yaw()' defined but not used
autogenerated:266: warning: 'void readCommands()' declared 'static' but never defined autogenerated:243: warning: 'void readCommands()' declared 'static' but never defined
autogenerated:267: warning: 'void parseCommand(char*)' declared 'static' but never defined autogenerated:244: warning: 'void parseCommand(char*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
autogenerated:270: warning: 'long int read_baro_filtered()' declared 'static' but never defined autogenerated:247: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
autogenerated:284: warning: 'void report_heli()' declared 'static' but never defined autogenerated:261: warning: 'void report_heli()' declared 'static' but never defined
autogenerated:285: warning: 'void report_gyro()' declared 'static' but never defined autogenerated:262: warning: 'void report_gyro()' declared 'static' but never defined
autogenerated:292: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined autogenerated:269: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined
autogenerated:293: warning: 'int read_num_from_serial()' declared 'static' but never defined autogenerated:270: warning: 'int read_num_from_serial()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:459: warning: 'void set_failsafe(boolean)' defined but not used /root/apm/ardupilot-mega/ArduCopter/system.pde:439: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:307: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:284: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never defined autogenerated:291: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:450: warning: 'undo_event' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:428: warning: 'undo_event' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:456: warning: 'condition_rate' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:434: warning: 'condition_rate' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:470: warning: 'simple_WP' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:448: warning: 'simple_WP' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:475: warning: 'new_location' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:453: warning: 'new_location' defined but not used
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:32: warning: 'int8_t test_xbee(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_PI/APM_PI.o %% libraries/APM_PI/APM_PI.o
@ -93,8 +75,8 @@ autogenerated:315: warning: 'void fake_out_gps()' declared 'static' but never de
%% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_IMU/AP_IMU_Oilpan.o
%% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o
In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28:
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined
/usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
%% libraries/AP_OpticalFlow/AP_OpticalFlow.o %% libraries/AP_OpticalFlow/AP_OpticalFlow.o
%% 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

View File

@ -40,9 +40,7 @@
00000001 b dancing_light()::step 00000001 b dancing_light()::step
00000001 b read_control_switch()::switch_debouncer 00000001 b read_control_switch()::switch_debouncer
00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav
00000001 B mavdelay
00000001 B relay 00000001 B relay
00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char)
00000002 b climb_rate 00000002 b climb_rate
00000002 b loiter_sum 00000002 b loiter_sum
00000002 b event_delay 00000002 b event_delay
@ -70,7 +68,6 @@
00000002 b airspeed 00000002 b airspeed
00000002 b baro_alt 00000002 b baro_alt
00000002 b sonar_alt 00000002 b sonar_alt
00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char)
00000002 b arm_motors()::arming_counter 00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@ -148,8 +145,6 @@
00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c 00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000004 r print_switch(unsigned char, unsigned char, bool)::__c 00000004 r print_switch(unsigned char, unsigned char, bool)::__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(unsigned char)::__c 00000004 r print_enabled(unsigned char)::__c
00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c
@ -278,7 +273,7 @@
0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*)
0000000c b omega 0000000c b omega
0000000c t test_mode(unsigned char, Menu::arg const*) 0000000c t test_mode(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 print_switch(unsigned char, unsigned char, bool)::__c 0000000c r print_switch(unsigned char, unsigned char, bool)::__c
0000000c r test_baro(unsigned char, Menu::arg const*)::__c 0000000c r test_baro(unsigned char, Menu::arg const*)::__c
@ -300,6 +295,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> >
@ -346,6 +342,7 @@
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 r planner_menu_commands 00000010 r planner_menu_commands
00000010 b motor_out 00000010 b motor_out
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 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c
00000010 r report_compass()::__c 00000010 r report_compass()::__c
@ -355,6 +352,7 @@
00000012 B Serial 00000012 B Serial
00000012 B Serial1 00000012 B Serial1
00000012 B Serial3 00000012 B Serial3
00000012 t gcs_update()
00000012 r flight_mode_strings 00000012 r flight_mode_strings
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()
@ -382,13 +380,11 @@
00000015 r print_hit_enter()::__c 00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c 00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep() 00000016 T piezo_beep()
00000016 r GCS_MAVLINK::update()::__c
00000016 B sonar 00000016 B sonar
00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_tune(unsigned char, Menu::arg const*)
00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*)
00000018 r __menu_name__main_menu 00000018 r __menu_name__main_menu
00000018 W AP_VarT<int>::serialize(void*, unsigned int) const 00000018 W AP_VarT<int>::serialize(void*, unsigned int) const
00000019 r GCS_MAVLINK::update()::__c
0000001a r print_log_menu()::__c 0000001a r print_log_menu()::__c
0000001a r Log_Read_Nav_Tuning()::__c 0000001a r Log_Read_Nav_Tuning()::__c
0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int) 0000001c W AP_VarA<float, (unsigned char)6>::unserialize(void*, unsigned int)
@ -400,6 +396,7 @@
0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const 0000001c W AP_VarS<Vector3<float> >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c 0000001d r Log_Read_Attitude()::__c
0000001e r Log_Read_Optflow()::__c 0000001e r Log_Read_Optflow()::__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 t byte_swap_4 00000020 t byte_swap_4
00000021 r print_log_menu()::__c 00000021 r print_log_menu()::__c
@ -409,6 +406,7 @@
00000022 t clear_leds() 00000022 t clear_leds()
00000022 t print_blanks(int) 00000022 t print_blanks(int)
00000022 t reset_hold_I() 00000022 t reset_hold_I()
00000022 t startup_ground()
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()
00000022 W AP_VarS<Matrix3<float> >::~AP_VarS() 00000022 W AP_VarS<Matrix3<float> >::~AP_VarS()
@ -418,12 +416,10 @@
00000022 W AP_VarT<int>::~AP_VarT() 00000022 W AP_VarT<int>::~AP_VarT()
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c 00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c 00000023 r print_gyro_offsets()::__c
00000024 t startup_ground()
00000024 r init_ardupilot()::__c 00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c 00000024 r print_accel_offsets()::__c
00000025 r setup_factory(unsigned char, Menu::arg const*)::__c 00000025 r setup_factory(unsigned char, Menu::arg const*)::__c
00000026 t print_done() 00000026 t print_done()
00000026 b mavlink_queue
00000026 t print_hit_enter() 00000026 t print_hit_enter()
00000026 t Log_Read_Startup() 00000026 t Log_Read_Startup()
00000026 r Log_Read_Control_Tuning()::__c 00000026 r Log_Read_Control_Tuning()::__c
@ -438,17 +434,20 @@
0000002a t setup_declination(unsigned char, Menu::arg const*) 0000002a t setup_declination(unsigned char, Menu::arg const*)
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c 0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t print_divider() 0000002e t print_divider()
0000002e t send_rate(unsigned int, unsigned int) 0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
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)
0000002f r test_radio(unsigned char, Menu::arg const*)::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c
0000002f r init_ardupilot()::__c 0000002f r init_ardupilot()::__c
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 send_heartbeat(mavlink_channel_t)
00000032 T GCS_MAVLINK::init(BetterStream*) 00000032 T GCS_MAVLINK::init(FastSerial*)
00000032 W APM_PI::~APM_PI() 00000032 W APM_PI::~APM_PI()
00000032 r Log_Read_GPS()::__c 00000032 r Log_Read_GPS()::__c
00000033 b pending_status
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 _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
00000036 t report_radio() 00000036 t report_radio()
00000037 r print_wp(Location*, unsigned char)::__c 00000037 r print_wp(Location*, unsigned char)::__c
@ -460,7 +459,7 @@
0000003a t report_imu() 0000003a t report_imu()
0000003c W RC_Channel::~RC_Channel() 0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver 0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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 t read_AHRS() 00000040 t read_AHRS()
00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 W AP_Float16::unserialize(void*, unsigned int)
@ -469,13 +468,13 @@
00000042 t report_sonar() 00000042 t report_sonar()
00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 t setup_show(unsigned char, Menu::arg const*)
00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) 00000044 W AP_VarT<int>::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
00000048 t change_command(unsigned char)
00000048 t update_motor_leds() 00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
0000004a t send_meminfo(mavlink_channel_t) 0000004a t send_meminfo(mavlink_channel_t)
0000004a t change_command(unsigned char)
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)
0000004c t update_auto_yaw() 0000004c t update_auto_yaw()
0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) 00000050 b mavlink_queue
00000050 t report_version() 00000050 t report_version()
00000050 r log_menu_commands 00000050 r log_menu_commands
00000050 r main_menu_commands 00000050 r main_menu_commands
@ -485,6 +484,7 @@
00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c 00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c
00000056 t readSwitch() 00000056 t readSwitch()
00000056 t dancing_light() 00000056 t dancing_light()
00000056 T GCS_MAVLINK::queued_waypoint_send()
00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 r help_log(unsigned char, Menu::arg const*)::__c
0000005c t get_num_logs() 0000005c t get_num_logs()
0000005c t setup_esc(unsigned char, Menu::arg const*) 0000005c t setup_esc(unsigned char, Menu::arg const*)
@ -494,10 +494,12 @@
00000064 t mavlink_msg_param_value_send 00000064 t mavlink_msg_param_value_send
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 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006c t setup_sonar(unsigned char, Menu::arg const*)
0000006e T output_min() 0000006e T output_min()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
00000078 t do_RTL()
0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t setup_factory(unsigned char, Menu::arg const*)
0000007a t read_control_switch() 0000007a t read_control_switch()
0000007a t report_flight_modes() 0000007a t report_flight_modes()
@ -508,7 +510,6 @@
00000080 T __vector_36 00000080 T __vector_36
00000080 T __vector_54 00000080 T __vector_54
00000082 t Log_Write_Attitude() 00000082 t Log_Write_Attitude()
00000082 t do_RTL()
00000088 t Log_Read_Raw() 00000088 t Log_Read_Raw()
0000008c t setup_frame(unsigned char, Menu::arg const*) 0000008c t setup_frame(unsigned char, Menu::arg const*)
0000008c t print_gyro_offsets() 0000008c t print_gyro_offsets()
@ -516,13 +517,15 @@
0000008e t dump_log(unsigned char, Menu::arg const*) 0000008e t dump_log(unsigned char, Menu::arg const*)
00000090 t report_tuning() 00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
00000095 r init_ardupilot()::__c 00000095 r init_ardupilot()::__c
00000096 t map_baudrate(signed char, unsigned long) 00000096 t map_baudrate(signed char, unsigned long)
00000096 t print_wp(Location*, unsigned char) 00000096 t print_wp(Location*, unsigned char)
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass() 0000009a t init_compass()
0000009a t Log_Read_Motors() 0000009a t Log_Read_Motors()
0000009d B gcs 0000009b B gcs0
0000009d B hil 0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode() 0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*) 0000009e t Log_Write_Cmd(unsigned char, Location*)
@ -534,7 +537,6 @@
000000ae t report_frame() 000000ae t report_frame()
000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b2 t erase_logs(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
000000be t update_events() 000000be t update_events()
@ -566,45 +568,44 @@
000000f6 t Log_Read_Cmd() 000000f6 t Log_Read_Cmd()
000000fa t calc_loiter_pitch_roll() 000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands 00000100 r test_menu_commands
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*) 0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*)
0000010e t send_servo_out(mavlink_channel_t)
0000010e t send_extended_status1(mavlink_channel_t, unsigned int) 0000010e t send_extended_status1(mavlink_channel_t, unsigned int)
0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000112 t set_next_WP(Location*)
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 set_command_with_index(Location, int) 00000118 t set_command_with_index(Location, int)
00000118 T GCS_MAVLINK::_queued_send()
0000011c t get_command_with_index(int) 0000011c t get_command_with_index(int)
00000130 t report_compass() 00000130 t report_compass()
00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long)
00000138 t get_stabilize_roll(long) 00000138 t get_stabilize_roll(long)
00000138 t get_stabilize_pitch(long) 00000138 t get_stabilize_pitch(long)
0000013a t set_next_WP(Location*)
00000148 t Log_Read_GPS() 00000148 t Log_Read_GPS()
00000152 T GCS_MAVLINK::update() 0000014e t send_servo_out(mavlink_channel_t)
00000158 t update_commands() 00000156 t update_commands()
0000015c t update_trig() 0000015c t update_trig()
0000015c t setup_motors(unsigned char, Menu::arg const*) 0000015c t setup_motors(unsigned char, Menu::arg const*)
00000160 t send_location(mavlink_channel_t) 00000160 t send_location(mavlink_channel_t)
00000160 t send_nav_controller_output(mavlink_channel_t) 00000160 t send_nav_controller_output(mavlink_channel_t)
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t) 00000166 t send_vfr_hud(mavlink_channel_t)
00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*) 0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t) 0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values() 000001a8 t print_radio_values()
000001be t arm_motors() 000001be t arm_motors()
000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001cc t start_new_log()
000001ca t mavlink_delay(unsigned long)
000001ce t start_new_log()
000001d6 t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int)
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home() 000001ea t init_home()
00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t) 0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*) 0000021c t test_wp(unsigned char, Menu::arg const*)
00000228 t setup_radio(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*)
00000228 t set_mode(unsigned char)
0000022a t send_gps_raw(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int) 00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t) 00000268 t send_raw_imu3(mavlink_channel_t)
@ -614,11 +615,11 @@
000003a0 t read_battery() 000003a0 t read_battery()
00000410 T update_yaw_mode() 00000410 T update_yaw_mode()
0000046e T update_roll_pitch_mode() 0000046e T update_roll_pitch_mode()
000005fc t init_ardupilot() 000005ec t init_ardupilot()
000006fa t update_nav_wp() 000006f0 t update_nav_wp()
000007b8 t __static_initialization_and_destruction_0(int, int) 000007b8 t __static_initialization_and_destruction_0(int, int)
00000824 b g 00000824 b g
0000086a t process_next_command() 00000870 t process_next_command()
000008f4 W Parameters::Parameters() 000008f4 W Parameters::Parameters()
00001228 T GCS_MAVLINK::handleMessage(__mavlink_message*) 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
00001b64 T loop 00001ad0 T loop

View File

@ -58,7 +58,7 @@
<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>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<name>ArduCopter V2.0.47 Beta Quad</name> <name>ArduCopter V2.0.48 Beta Quad</name>
<desc> <desc>
#define FRAME_CONFIG QUAD_FRAME #define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION X_FRAME #define FRAME_ORIENTATION X_FRAME
@ -69,7 +69,7 @@
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<name>ArduCopter V2.0.47 Beta Tri</name> <name>ArduCopter V2.0.48 Beta Tri</name>
<desc> <desc>
#define FRAME_CONFIG TRI_FRAME #define FRAME_CONFIG TRI_FRAME
#define FRAME_ORIENTATION X_FRAME #define FRAME_ORIENTATION X_FRAME
@ -80,7 +80,7 @@
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<name>ArduCopter V2.0.47 Beta Hexa</name> <name>ArduCopter V2.0.48 Beta Hexa</name>
<desc> <desc>
#define FRAME_CONFIG HEXA_FRAME #define FRAME_CONFIG HEXA_FRAME
#define FRAME_ORIENTATION X_FRAME #define FRAME_ORIENTATION X_FRAME
@ -91,7 +91,7 @@
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<name>ArduCopter V2.0.47 Beta Y6</name> <name>ArduCopter V2.0.48 Beta Y6</name>
<desc> <desc>
#define FRAME_CONFIG Y6_FRAME #define FRAME_CONFIG Y6_FRAME
#define FRAME_ORIENTATION X_FRAME #define FRAME_ORIENTATION X_FRAME
@ -148,7 +148,7 @@
<Firmware> <Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url> <url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560> <url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
<name>ArduCopter V2.0.47 Beta Quad Hil</name> <name>ArduCopter V2.0.48 Beta Quad Hil</name>
<desc> <desc>
#define FRAME_CONFIG QUAD_FRAME #define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME #define FRAME_ORIENTATION PLUS_FRAME

View File

@ -1,12 +1,44 @@
From https://code.google.com/p/ardupilot-mega From https://code.google.com/p/ardupilot-mega
2ceba2f..eb0b7eb master -> origin/master 25b258c..a188536 APM_Camera -> origin/APM_Camera
Updating 2ceba2f..eb0b7eb 36e7d95..9f44a2e master -> origin/master
Updating 36e7d95..9f44a2e
Fast-forward Fast-forward
ArduCopter/ArduCopter.pde | 6 +- ArduCopter/ArduCopter.pde | 11 +-
Tools/ArdupilotMegaPlanner/ArdupilotMega.suo | Bin 83456 -> 0 bytes ArduCopter/commands_logic.pde | 2 +-
Tools/ArdupilotMegaPlanner/Capture.cs | 125 +- ArduCopter/config.h | 10 +-
.../GCSViews/Configuration.Designer.cs | 114 +- ArduCopter/motors.pde | 2 +-
.../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 82 +- ArduCopter/motors_hexa.pde | 14 ++-
.../GCSViews/Configuration.resx | 1936 ++++++++++++++------ ArduCopter/motors_octa.pde | 19 ++-
6 files changed, 1573 insertions(+), 690 deletions(-) ArduCopter/motors_octa_quad.pde | 13 +-
delete mode 100644 Tools/ArdupilotMegaPlanner/ArdupilotMega.suo ArduCopter/motors_quad.pde | 11 +
ArduCopter/motors_tri.pde | 13 ++
ArduCopter/motors_y6.pde | 14 ++-
ArduCopter/radio.pde | 1 +
ArduCopter/system.pde | 4 +-
Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 1 +
Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 222 ++++++++++++++++++++
Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 7 +-
Tools/ArdupilotMegaPlanner/JoystickSetup.cs | 2 +-
Tools/ArdupilotMegaPlanner/MainV2.cs | 7 +
.../Properties/AssemblyInfo.cs | 2 +-
Tools/ArdupilotMegaPlanner/bin/Release/.gitignore | 3 +-
.../ArdupilotMegaPlanner/bin/Release/ArduPlane.exe | Bin 0 -> 673167 bytes
.../bin/Release/ArdupilotMegaPlanner.application | 2 +-
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2186240 -> 2189824 bytes
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
Tools/ArdupilotMegaPlanner/bin/Release/cygwin1.dll | Bin 0 -> 2666500 bytes
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
apo/ControllerQuad.h | 91 ++++----
apo/QuadArducopter.h | 32 ++--
apo/apo.pde | 2 +-
libraries/APO/APO_DefaultSetup.h | 17 +-
libraries/APO/AP_Navigator.h | 3 +-
libraries/APO/AP_RcChannel.h | 2 +-
libraries/Desktop/Desktop.mk | 5 +-
libraries/Desktop/support/Arduino.cpp | 24 ++-
35 files changed, 438 insertions(+), 98 deletions(-)
create mode 100644 Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/ArduPlane.exe
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/cygwin1.dll