From 28ff9015363e3245c47bc7e8397b31ae45058650 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sun, 18 Sep 2011 17:38:36 +0800 Subject: [PATCH] firmware build --- .../Firmware/AC2-Heli-1280.build.log | 362 ++--- .../Firmware/AC2-Heli-1280.size.txt | 1298 +++++++++-------- .../Firmware/AC2-Heli-2560.build.log | 362 ++--- .../Firmware/AC2-Heli-2560.size.txt | 1298 +++++++++-------- .../Firmware/firmware2.xml | 15 +- 5 files changed, 1479 insertions(+), 1856 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log index 9185b06998..cd38550546 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log @@ -1,94 +1,64 @@ - -%%%% Making all in ArduCopterMega/ %%%% - -make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega' -%% ArduCopterMega.cpp -%% ArduCopterMega.o -In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53: +%% ArduCopter.cpp +%% ArduCopter.o +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:68: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions -/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde: In function 'void init_compass()': -/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:458: warning: unused variable 'junkbool' -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)': -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_tail' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_tail' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_coll' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_coll' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_pitch' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_roll' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:433: warning: 'temp' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde: At global scope: -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1494: warning: 'void tuning()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1586: warning: 'void point_at_home_yaw()' defined but not used -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined -autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined -autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined -autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined -autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined -autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined -autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined -autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined -autogenerated:89: warning: 'void print_position()' declared 'static' but never defined -autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined -autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined -autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined -autogenerated:135: warning: 'void Log_Write_Optflow()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:127: warning: 'void decrement_WP_index()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:148: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:429: warning: 'bool verify_loiter_unlim()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:40: warning: 'void update_servo_switches()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:49: warning: 'void low_battery_event()' defined but not used -autogenerated:232: warning: 'void debug_motors()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:194: warning: 'void calc_altitude_smoothing_error()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:267: warning: 'void reset_crosstrack()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:272: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:293: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)': +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_coll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_coll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_pitch' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_roll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:444: warning: 'temp' may be used uninitialized in this function +autogenerated: At global scope: +autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined +autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined +autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined +autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined +autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined +autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined +autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined +autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined +autogenerated:92: warning: 'void print_position()' declared 'static' but never defined +autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined +autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined +autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined +autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used +autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined +autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:78: warning: 'void read_airspeed()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:83: warning: 'void zero_airspeed()' defined but not used -autogenerated:282: warning: 'void report_gains()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:420: warning: 'void set_failsafe(boolean)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used +autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined +/root/apm/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/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1099: warning: 'void print_motor_out()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_min' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_max' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:280: warning: 'heli_servo_out' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:294: warning: 'rate_yaw_flag' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:296: warning: 'did_clear_yaw_control' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:303: warning: 'timer_light' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:322: warning: 'nav_gain_scaler' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:324: warning: 'last_ground_speed' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:339: warning: 'simple_bearing_is_set' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:356: warning: 'distance_error' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:388: warning: 'baro_alt_offset' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:397: warning: 'landing_distance' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:420: warning: 'set_throttle_cruise_flag' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:437: warning: 'next_wp_index' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:447: warning: 'repeat_forever' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'undo_event' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:454: warning: 'condition_rate' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:473: warning: 'optflow_offset' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:474: warning: 'new_location' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:485: warning: 'imu_health' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:488: warning: 'gcs_messages_sent' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:493: warning: 'GCS_buffer' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:494: warning: 'display_PID' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:517: warning: 'elapsedTime' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:46: warning: 'trim_timer' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:991: warning: 'void print_motor_out()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_min' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_max' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:284: warning: 'heli_servo_out' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:443: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:449: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:463: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'optflow_offset' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used %% libraries/APM_BMP085/APM_BMP085.o +%% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o %% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC.o @@ -117,59 +87,50 @@ autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never de %% libraries/AP_GPS/GPS.o %% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o -In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: +In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: /usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of | -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of & -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of | -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of & -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of | +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of & +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of | +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of & +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function %% libraries/AP_OpticalFlow/AP_OpticalFlow.o -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i' -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function -%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i' +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()': -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp' %% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/FastSerial.o %% libraries/FastSerial/vprintf.o %% libraries/GCS_MAVLink/GCS_MAVLink.o -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions %% libraries/ModeFilter/ModeFilter.o -%% libraries/PID/PID.o %% libraries/RC_Channel/RC_Channel.o +%% libraries/memcheck/memcheck.o %% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ultoa_invert.o %% libraries/SPI/SPI.o @@ -244,157 +205,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25: /usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." %% arduino/core.a -%% ArduCopterMega.elf -%% ArduCopterMega.eep -%% ArduCopterMega.hex -make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega' - -%%%% Making all in ArduPilotMega/ %%%% - -make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega' -%% ArduPilotMega.cpp -%% ArduPilotMega.o -In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32: -/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined -/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:46: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions -autogenerated: At global scope: -autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined -autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined -autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined -autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:334: warning: 'landing_distance' defined but not used -%% libraries/APM_BMP085/APM_BMP085.o -%% libraries/APM_RC/APM_RC.o -%% libraries/AP_ADC/AP_ADC_ADS7844.o -%% libraries/AP_ADC/AP_ADC.o -%% libraries/AP_ADC/AP_ADC_HIL.o -%% libraries/AP_Common/AP_Common.o -%% libraries/AP_Common/AP_Loop.o -%% libraries/AP_Common/AP_MetaClass.o -%% libraries/AP_Common/AP_Var.o -%% libraries/AP_Common/AP_Var_menufuncs.o -%% libraries/AP_Common/c++.o -%% libraries/AP_Common/menu.o -%% libraries/AP_Compass/AP_Compass_HIL.o -%% libraries/AP_Compass/AP_Compass_HMC5843.o -%% libraries/AP_Compass/Compass.o -%% libraries/AP_DCM/AP_DCM.o -%% libraries/AP_DCM/AP_DCM_HIL.o -%% libraries/AP_GPS/AP_GPS_406.o -%% libraries/AP_GPS/AP_GPS_Auto.o -%% libraries/AP_GPS/AP_GPS_HIL.o -%% libraries/AP_GPS/AP_GPS_IMU.o -%% libraries/AP_GPS/AP_GPS_MTK16.o -%% libraries/AP_GPS/AP_GPS_MTK.o -%% libraries/AP_GPS/AP_GPS_NMEA.o -%% libraries/AP_GPS/AP_GPS_SIRF.o -%% libraries/AP_GPS/AP_GPS_UBLOX.o -%% libraries/AP_GPS/GPS.o -%% libraries/AP_IMU/AP_IMU_Oilpan.o -%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o -%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o -%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o -%% libraries/AP_RangeFinder/RangeFinder.o -%% libraries/DataFlash/DataFlash.o -In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35: -/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined -/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()': -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp' -%% libraries/FastSerial/BetterStream.o -%% libraries/FastSerial/FastSerial.o -%% libraries/FastSerial/vprintf.o -%% libraries/GCS_MAVLink/GCS_MAVLink.o -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions -%% libraries/ModeFilter/ModeFilter.o -%% libraries/PID/PID.o -%% libraries/RC_Channel/RC_Channel.o -%% libraries/FastSerial/ftoa_engine.o -%% libraries/FastSerial/ultoa_invert.o -%% libraries/SPI/SPI.o -In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12: -/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined -/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -%% libraries/Wire/Wire.o -%% libraries/Wire/utility/twi.o -cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C -%% arduino/HardwareSerial.o -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -%% arduino/main.o -%% arduino/Print.o -%% arduino/Tone.o -/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area -%% arduino/WMath.o -%% arduino/WString.o -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -%% arduino/core.a -%% ArduPilotMega.elf -%% ArduPilotMega.eep -%% ArduPilotMega.hex -make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega' +%% ArduCopter.elf +%% ArduCopter.eep +%% ArduCopter.hex diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt index 028f88a480..3a95d45ae1 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt @@ -1,668 +1,670 @@ -00000001 b _ZL10wp_control -00000001 b _ZL11GPS_enabled -00000001 b _ZL11home_is_set -00000001 b _ZL11motor_armed -00000001 b _ZL11motor_light -00000001 b _ZL12control_mode -00000001 b _ZL12flight_timer -00000001 d _ZL12yaw_tracking -00000001 b _ZL13land_complete -00000001 b _ZL14command_may_ID -00000001 b _ZL14wp_verify_byte -00000001 d _ZL15altitude_sensor -00000001 b _ZL15command_must_ID -00000001 b _ZL15command_yaw_dir -00000001 b _ZL16counter_one_herz -00000001 b _ZL16delta_ms_fiftyhz -00000001 b _ZL16did_ground_start -00000001 b _ZL16invalid_throttle -00000001 b _ZL16motor_auto_armed -00000001 b _ZL16old_control_mode -00000001 b _ZL16slow_loopCounter -00000001 b _ZL16takeoff_complete -00000001 b _ZL17baro_filter_index -00000001 b _ZL17command_may_index -00000001 b _ZL17oldSwitchPosition -00000001 b _ZL18command_must_index -00000001 b _ZL18delta_ms_fast_loop -00000001 d _ZL18ground_start_count -00000001 b _ZL18medium_loopCounter -00000001 b _ZL20command_yaw_relative -00000001 b _ZL20delta_ms_medium_loop -00000001 b _ZL8event_id -00000001 b _ZL8led_mode -00000001 b _ZL9GPS_light -00000001 b _ZL9loop_step -00000001 b _ZL9trim_flag -00000001 b _ZL9yaw_debug -00000001 b _ZZL13dancing_lightvE4step -00000001 b _ZZL17update_motor_ledsvE5blink -00000001 b _ZZL18radio_input_switchvE7bouncer -00000001 d _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE7mav_nav +00000001 b wp_control +00000001 b GPS_enabled +00000001 b home_is_set +00000001 b motor_armed +00000001 b motor_light +00000001 b control_mode +00000001 b simple_timer +00000001 d yaw_tracking +00000001 b land_complete +00000001 b throttle_mode +00000001 b command_may_ID +00000001 b wp_verify_byte +00000001 b xtrack_enabled +00000001 d altitude_sensor +00000001 b command_must_ID +00000001 b command_yaw_dir +00000001 b roll_pitch_mode +00000001 b counter_one_herz +00000001 b delta_ms_fiftyhz +00000001 b did_ground_start +00000001 b in_mavlink_delay +00000001 b invalid_throttle +00000001 b motor_auto_armed +00000001 b old_control_mode +00000001 b slow_loopCounter +00000001 b takeoff_complete +00000001 b command_may_index +00000001 b oldSwitchPosition +00000001 b command_must_index +00000001 b delta_ms_fast_loop +00000001 d ground_start_count +00000001 b medium_loopCounter +00000001 b command_yaw_relative +00000001 b delta_ms_medium_loop +00000001 b event_id +00000001 b led_mode +00000001 b yaw_mode +00000001 b GPS_light +00000001 b alt_timer +00000001 b loop_step +00000001 b trim_flag +00000001 b dancing_light()::step +00000001 b update_motor_leds()::blink +00000001 b radio_input_switch()::bouncer +00000001 b read_control_switch()::switch_debouncer +00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay -00000002 T _Z19mavlink_acknowledge17mavlink_channel_thhh -00000002 b _ZL10climb_rate -00000002 b _ZL11event_delay -00000002 b _ZL11event_value -00000002 b _ZL12event_repeat -00000002 b _ZL12nav_throttle -00000002 b _ZL13gps_fix_count -00000002 b _ZL13velocity_land -00000002 b _ZL14mainLoop_count -00000002 b _ZL14waypoint_speed -00000002 b _ZL16command_yaw_time -00000002 b _ZL16event_undo_value -00000002 b _ZL16loiter_error_max -00000002 b _ZL17command_yaw_speed -00000002 b _ZL18auto_level_counter -00000002 b _ZL18ground_temperature -00000002 b _ZL20heli_manual_override -00000002 b _ZL21superslow_loopCounter -00000002 r _ZL5comma -00000002 b _ZL5g_gps -00000002 b _ZL8G_Dt_max -00000002 b _ZL8airspeed -00000002 b _ZL8baro_alt -00000002 b _ZL9sonar_alt -00000002 T _ZN11GCS_MAVLINK11acknowledgeEhhh -00000002 b _ZZL10arm_motorsvE14arming_counter -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_0 -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_1 -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_2 -00000002 r _ZZL7test_wphPKN4Menu3argEE3__c_0 -00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c -00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_0 -00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_1 +00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) +00000002 b climb_rate +00000002 b event_delay +00000002 b event_value +00000002 b event_repeat +00000002 b nav_throttle +00000002 b altitude_rate +00000002 b gps_fix_count +00000002 b velocity_land +00000002 b mainLoop_count +00000002 b command_yaw_time +00000002 b event_undo_value +00000002 b command_yaw_speed +00000002 b auto_level_counter +00000002 b ground_temperature +00000002 b heli_manual_override +00000002 b superslow_loopCounter +00000002 r comma +00000002 b g_gps +00000002 b G_Dt_max +00000002 b airspeed +00000002 b baro_alt +00000002 b sonar_alt +00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char) +00000002 b arm_motors()::arming_counter +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r test_wp(unsigned char, Menu::arg const*)::__c +00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c +00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 B adc -00000003 r _ZZL10setup_gyrohPKN4Menu3argEE3__c -00000003 r _ZZL11select_logshPKN4Menu3argEE3__c_4 -00000003 r _ZZL11setup_sonarhPKN4Menu3argEE3__c -00000003 r _ZZL13print_enabledhE3__c -00000003 r _ZZL13setup_compasshPKN4Menu3argEE3__c -00000004 d _ZL10cos_roll_x -00000004 b _ZL10land_start -00000004 b _ZL10long_error -00000004 b _ZL10sin_roll_y -00000004 d _ZL11cos_pitch_x -00000004 b _ZL11event_timer -00000004 b _ZL11loiter_time -00000004 b _ZL11nav_bearing -00000004 d _ZL11scaleLongUp -00000004 b _ZL11sin_pitch_y -00000004 b _ZL11wp_distance -00000004 b _ZL12abs_pressure -00000004 b _ZL12current_amps -00000004 b _ZL12original_alt -00000004 b _ZL13bearing_error -00000004 b _ZL13current_total -00000004 b _ZL13nav_loopTimer -00000004 d _ZL13scaleLongDown -00000004 t _ZL13test_failsafehPKN4Menu3argE -00000004 b _ZL14altitude_error -00000004 b _ZL14fast_loopTimer -00000004 b _ZL14perf_mon_timer -00000004 b _ZL14target_bearing -00000004 d _ZL15battery_voltage -00000004 b _ZL15command_yaw_end -00000004 b _ZL15condition_start -00000004 b _ZL15condition_value -00000004 b _ZL15ground_pressure -00000004 b _ZL15loiter_time_max -00000004 b _ZL15target_altitude -00000004 d _ZL16battery_voltage1 -00000004 d _ZL16battery_voltage2 -00000004 d _ZL16battery_voltage3 -00000004 d _ZL16battery_voltage4 -00000004 b _ZL16crosstrack_error -00000004 b _ZL16medium_loopTimer -00000004 b _ZL16wp_totalDistance -00000004 b _ZL17command_yaw_delta -00000004 b _ZL17command_yaw_start -00000004 b _ZL17fiftyhz_loopTimer -00000004 b _ZL18crosstrack_bearing -00000004 b _ZL18fast_loopTimeStamp -00000004 b _ZL19throttle_integrator -00000004 b _ZL20saved_target_bearing -00000004 r _ZL21__menu_name__log_menu -00000004 b _ZL22command_yaw_start_time -00000004 b _ZL22initial_simple_bearing -00000004 d _ZL4G_Dt -00000004 b _ZL4load -00000004 b _ZL5dTnav -00000004 b _ZL7nav_lat -00000004 b _ZL7nav_lon -00000004 b _ZL7nav_yaw -00000004 b _ZL7old_alt -00000004 b _ZL8nav_roll -00000004 d _ZL9cos_yaw_x -00000004 b _ZL9lat_error -00000004 b _ZL9nav_pitch -00000004 b _ZL9sin_yaw_y -00000004 b _ZL9yaw_error -00000004 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_0 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_0 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_10 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_3 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_8 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_9 -00000004 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_0 -00000004 b _ZZL13mavlink_delaymE8last_1hz -00000004 b _ZZL13mavlink_delaymE8last_3hz -00000004 b _ZZL13mavlink_delaymE9last_10hz -00000004 b _ZZL13mavlink_delaymE9last_50hz -00000004 r _ZZL13print_enabledhE3__c_0 -00000004 r _ZZL13setup_compasshPKN4Menu3argEE3__c_0 -00000004 r _ZZL14print_log_menuvE3__c_4 -00000004 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c -00000004 r _ZZL20Log_Read_PerformancevE3__c -00000004 r _ZZL8test_adchPKN4Menu3argEE3__c_0 -00000004 V _ZZN10ParametersC1EvE3__c_32 -00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c -00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_1 -00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_2 -00000005 r _ZL22__menu_name__test_menu -00000005 r _ZZL10report_imuvE3__c -00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_5 -00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_6 -00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_7 -00000005 r _ZZL12Log_Read_RawvE3__c -00000005 r _ZZL13Log_Read_ModevE3__c -00000005 r _ZZL14print_log_menuvE3__c_0 -00000005 r _ZZL14print_log_menuvE3__c_3 -00000005 r _ZZL14print_log_menuvE3__c_7 -00000005 r _ZZL14print_log_menuvE3__c_8 -00000005 r _ZZL8test_adchPKN4Menu3argEE3__c -00000005 V _ZZN10ParametersC1EvE3__c_35 -00000005 V _ZZN10ParametersC1EvE3__c_36 -00000005 V _ZZN10ParametersC1EvE3__c_37 -00000005 V _ZZN10ParametersC1EvE3__c_38 -00000005 V _ZZN10ParametersC1EvE3__c_49 -00000005 V _ZZN10ParametersC1EvE3__c_50 -00000005 V _ZZN10ParametersC1EvE3__c_51 -00000005 V _ZZN10ParametersC1EvE3__c_52 -00000005 V _ZZN10ParametersC1EvE3__c_53 -00000005 V _ZZN10ParametersC1EvE3__c_54 -00000005 V _ZZN10ParametersC1EvE3__c_55 -00000005 V _ZZN10ParametersC1EvE3__c_56 -00000005 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_0 -00000005 r _ZZN11GCS_MAVLINKC1EjE3__c -00000005 r _ZZN11GCS_MAVLINKC1EjE3__c_0 -00000005 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_2 -00000006 T _Z17mavlink_send_text17mavlink_channel_thPKc -00000006 r _ZL23__menu_name__setup_menu -00000006 r _ZZL10report_gpsvE3__c -00000006 r _ZZL11report_helivE3__c -00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c -00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c_0 -00000006 r _ZZL11zero_eepromvE3__c_0 -00000006 r _ZZL13Log_Read_ModevE3__c_0 -00000006 r _ZZL14print_log_menuvE3__c_5 -00000006 r _ZZL14print_log_menuvE3__c_6 -00000006 V _ZZN10ParametersC1EvE3__c_33 -00000006 t put_float_by_index -00000006 T setup -00000007 b _ZL10setup_menu -00000007 b _ZL12planner_menu -00000007 b _ZL8log_menu -00000007 b _ZL9main_menu -00000007 b _ZL9test_menu -00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_11 -00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_13 -00000007 r _ZZL12report_framevE3__c -00000007 r _ZZL12report_radiovE3__c -00000007 r _ZZL12report_sonarvE3__c -00000007 r _ZZL13print_enabledhE3__c_1 -00000007 r _ZZL7test_wphPKN4Menu3argEE3__c_2 -00000007 V _ZZN10ParametersC1EvE3__c_57 -00000007 V _ZZN10ParametersC1EvE3__c_58 -00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_6 -00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_7 -00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_8 -00000008 t _ZL11setup_erasehPKN4Menu3argE -00000008 r _ZL25__menu_name__planner_menu -00000008 r _ZZL11select_logshPKN4Menu3argEE3__c_12 -00000008 r _ZZL14print_log_menuvE3__c_10 -00000008 r _ZZL19report_batt_monitorvE3__c_0 -00000008 r _ZZL19report_batt_monitorvE3__c_1 -00000008 r _ZZL7test_wphPKN4Menu3argEE3__c_1 -00000008 V _ZZN10ParametersC1EvE3__c_10 -00000008 V _ZZN10ParametersC1EvE3__c_17 -00000008 V _ZZN10ParametersC1EvE3__c_18 -00000008 V _ZZN10ParametersC1EvE3__c_67 -00000008 V _ZZN10ParametersC1EvE3__c_69 -00000008 r _ZZN11GCS_MAVLINKC1EjE3__c_3 -00000009 r _ZZL11report_gyrovE3__c_0 -00000009 r _ZZL12print_switchhhE3__c -00000009 r _ZZL14print_log_menuvE3__c_11 -00000009 r _ZZL14print_log_menuvE3__c_9 -00000009 r _ZZL14report_compassvE3__c -00000009 V _ZZN10ParametersC1EvE3__c_11 -00000009 V _ZZN10ParametersC1EvE3__c_12 -00000009 V _ZZN10ParametersC1EvE3__c_23 -00000009 V _ZZN10ParametersC1EvE3__c_24 -00000009 V _ZZN10ParametersC1EvE3__c_25 -00000009 V _ZZN10ParametersC1EvE3__c_26 -00000009 V _ZZN10ParametersC1EvE3__c_27 -00000009 V _ZZN10ParametersC1EvE3__c_28 -00000009 V _ZZN10ParametersC1EvE3__c_34 -00000009 V _ZZN10ParametersC1EvE3__c_39 -00000009 V _ZZN10ParametersC1EvE3__c_40 -00000009 V _ZZN10ParametersC1EvE3__c_41 -00000009 V _ZZN10ParametersC1EvE3__c_42 -00000009 V _ZZN10ParametersC1EvE3__c_43 -00000009 V _ZZN10ParametersC1EvE3__c_44 -00000009 V _ZZN10ParametersC1EvE3__c_45 -00000009 V _ZZN10ParametersC1EvE3__c_46 -00000009 V _ZZN10ParametersC1EvE3__c_62 -00000009 V _ZZN10ParametersC1EvE3__c_63 -00000009 V _ZZN10ParametersC1EvE3__c_64 -00000009 V _ZZN10ParametersC1EvE3__c_65 -00000009 V _ZZN10ParametersC1EvE3__c_66 -00000009 V _ZZN10ParametersC1EvE3__c_68 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_1 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_2 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_4 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_5 -0000000a r _ZZL10test_relayhPKN4Menu3argEE3__c -0000000a r _ZZL11test_tuninghPKN4Menu3argEE3__c -0000000a r _ZZL13start_new_logvE3__c -0000000a r _ZZL14print_log_menuvE3__c_13 -0000000a r _ZZL16Log_Read_StartupvE3__c -0000000a r _ZZL7test_wphPKN4Menu3argEE3__c -0000000a r _ZZL8test_maghPKN4Menu3argEE3__c_0 -0000000a V _ZZN10ParametersC1EvE3__c_14 -0000000a V _ZZN10ParametersC1EvE3__c_29 -0000000a V _ZZN10ParametersC1EvE3__c_48 -0000000a V _ZZN10ParametersC1EvE3__c_59 -0000000a V _ZZN10ParametersC1EvE3__c_60 -0000000a V _ZZN10ParametersC1EvE3__c_61 -0000000b r _ZZL10test_relayhPKN4Menu3argEE3__c_0 -0000000b r _ZZL19report_batt_monitorvE3__c_2 -0000000b r _ZZL8set_modehE3__c -0000000b V _ZZN10ParametersC1EvE3__c_8 -0000000c t _ZL12process_logshPKN4Menu3argE -0000000c b _ZL15heli_rollFactor -0000000c b _ZL16heli_pitchFactor -0000000c b _ZL5omega -0000000c t _ZL9test_modehPKN4Menu3argE -0000000c T _ZN11GCS_MAVLINK9send_textEhPKc -0000000c V _ZTV3IMU -0000000c r _ZZL12report_framevE3__c_0 -0000000c r _ZZL9test_barohPKN4Menu3argEE3__c -0000000c V _ZZN10ParametersC1EvE3__c_2 -0000000c V _ZZN10ParametersC1EvE3__c_30 -0000000c V _ZZN10ParametersC1EvE3__c_47 -0000000c V _ZZN10ParametersC1EvE3__c_9 -0000000d r _ZZL10verify_RTLvE3__c -0000000d r _ZZL11select_logshPKN4Menu3argEE3__c_2 -0000000d r _ZZL12test_batteryhPKN4Menu3argEE3__c -0000000d r _ZZL14startup_groundvE3__c -0000000d r _ZZL7test_wphPKN4Menu3argEE3__c_3 -0000000d V _ZZN10ParametersC1EvE3__c_16 -0000000d V _ZZN10ParametersC1EvE3__c_19 -0000000d V _ZZN10ParametersC1EvE3__c_21 -0000000d V _ZZN10ParametersC1EvE3__c_3 -0000000d V _ZZN10ParametersC1EvE3__c_31 -0000000d V _ZZN10ParametersC1EvE3__c_5 -0000000d V _ZZN10ParametersC1EvE3__c_6 +00000002 B x_actual_speed +00000002 B x_rate_error +00000002 B y_actual_speed +00000002 B y_rate_error +00000003 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000003 r select_logs(unsigned char, Menu::arg const*)::__c +00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c +00000003 r print_enabled(unsigned char)::__c +00000003 r setup_compass(unsigned char, Menu::arg const*)::__c +00000004 d cos_roll_x +00000004 b land_start +00000004 b long_error +00000004 b sin_roll_y +00000004 d cos_pitch_x +00000004 b event_timer +00000004 b loiter_time +00000004 b nav_bearing +00000004 d scaleLongUp +00000004 b sin_pitch_y +00000004 b wp_distance +00000004 b abs_pressure +00000004 b circle_angle +00000004 b current_amps +00000004 b old_altitude +00000004 b original_alt +00000004 b bearing_error +00000004 b current_total +00000004 b nav_loopTimer +00000004 d scaleLongDown +00000004 t test_failsafe(unsigned char, Menu::arg const*) +00000004 b altitude_error +00000004 b fast_loopTimer +00000004 b perf_mon_timer +00000004 b target_bearing +00000004 d battery_voltage +00000004 b command_yaw_end +00000004 b condition_start +00000004 b condition_value +00000004 b ground_pressure +00000004 b loiter_time_max +00000004 b target_altitude +00000004 d battery_voltage1 +00000004 d battery_voltage2 +00000004 d battery_voltage3 +00000004 d battery_voltage4 +00000004 b medium_loopTimer +00000004 b wp_totalDistance +00000004 b command_yaw_delta +00000004 b command_yaw_start +00000004 b fiftyhz_loopTimer +00000004 b crosstrack_bearing +00000004 b fast_loopTimeStamp +00000004 b throttle_integrator +00000004 b saved_target_bearing +00000004 r __menu_name__log_menu +00000004 b command_yaw_start_time +00000004 b initial_simple_bearing +00000004 d G_Dt +00000004 b dTnav +00000004 b nav_lat +00000004 b nav_lon +00000004 b nav_yaw +00000004 b old_alt +00000004 b auto_yaw +00000004 b nav_roll +00000004 d cos_yaw_x +00000004 b lat_error +00000004 b nav_pitch +00000004 b sin_yaw_y +00000004 b yaw_error +00000004 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c +00000004 b mavlink_delay(unsigned long)::last_1hz +00000004 b mavlink_delay(unsigned long)::last_3hz +00000004 b mavlink_delay(unsigned long)::last_10hz +00000004 b mavlink_delay(unsigned long)::last_50hz +00000004 r print_enabled(unsigned char)::__c +00000004 r setup_compass(unsigned char, Menu::arg const*)::__c +00000004 r print_log_menu()::__c +00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c +00000004 r test_adc(unsigned char, Menu::arg const*)::__c +00000004 V Parameters::Parameters()::__c +00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000004 B tuning_value +00000005 r __menu_name__test_menu +00000005 r report_imu()::__c +00000005 r select_logs(unsigned char, Menu::arg const*)::__c +00000005 r select_logs(unsigned char, Menu::arg const*)::__c +00000005 r select_logs(unsigned char, Menu::arg const*)::__c +00000005 r Log_Read_Raw()::__c +00000005 r Log_Read_Mode()::__c +00000005 r report_tuning()::__c +00000005 r print_log_menu()::__c +00000005 r print_log_menu()::__c +00000005 r print_log_menu()::__c +00000005 r print_log_menu()::__c +00000005 r test_adc(unsigned char, Menu::arg const*)::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c +00000006 r __menu_name__setup_menu +00000006 r report_gps()::__c +00000006 r report_heli()::__c +00000006 r test_eedump(unsigned char, Menu::arg const*)::__c +00000006 r test_eedump(unsigned char, Menu::arg const*)::__c +00000006 r zero_eeprom()::__c +00000006 r Log_Read_Mode()::__c +00000006 r print_log_menu()::__c +00000006 r print_log_menu()::__c +00000006 V Parameters::Parameters()::__c +00000007 b setup_menu +00000007 b planner_menu +00000007 b log_menu +00000007 b main_menu +00000007 b test_menu +00000007 r select_logs(unsigned char, Menu::arg const*)::__c +00000007 r select_logs(unsigned char, Menu::arg const*)::__c +00000007 r report_frame()::__c +00000007 r report_radio()::__c +00000007 r report_sonar()::__c +00000007 r print_enabled(unsigned char)::__c +00000007 r test_wp(unsigned char, Menu::arg const*)::__c +00000007 V Parameters::Parameters()::__c +00000007 V Parameters::Parameters()::__c +00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000008 t setup_erase(unsigned char, Menu::arg const*) +00000008 r __menu_name__planner_menu +00000008 r select_logs(unsigned char, Menu::arg const*)::__c +00000008 r report_tuning()::__c +00000008 r print_log_menu()::__c +00000008 r report_batt_monitor()::__c +00000008 r report_batt_monitor()::__c +00000008 r test_wp(unsigned char, Menu::arg const*)::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r report_gyro()::__c +00000009 r print_switch(unsigned char, unsigned char)::__c +00000009 r print_log_menu()::__c +00000009 r print_log_menu()::__c +00000009 r report_compass()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +0000000a r test_relay(unsigned char, Menu::arg const*)::__c +0000000a r start_new_log()::__c +0000000a r print_log_menu()::__c +0000000a r Log_Read_Startup()::__c +0000000a r test_wp(unsigned char, Menu::arg const*)::__c +0000000a r test_mag(unsigned char, Menu::arg const*)::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a T setup +0000000b r test_relay(unsigned char, Menu::arg const*)::__c +0000000b r report_batt_monitor()::__c +0000000b V Parameters::Parameters()::__c +0000000c t process_logs(unsigned char, Menu::arg const*) +0000000c b heli_rollFactor +0000000c b heli_pitchFactor +0000000c b omega +0000000c t test_mode(unsigned char, Menu::arg const*) +0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) +0000000c V vtable for IMU +0000000c r report_frame()::__c +0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c V Parameters::Parameters()::__c +0000000c V Parameters::Parameters()::__c +0000000c V Parameters::Parameters()::__c +0000000c V Parameters::Parameters()::__c +0000000d r verify_RTL()::__c +0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r test_tuning(unsigned char, Menu::arg const*)::__c +0000000d r test_battery(unsigned char, Menu::arg const*)::__c +0000000d r startup_ground()::__c +0000000d r test_wp(unsigned char, Menu::arg const*)::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter -0000000e t _GLOBAL__D_Serial -0000000e t _GLOBAL__I_Serial -0000000e V _ZTV10AP_Float16 -0000000e V _ZTV7AP_VarAIfLh6EE -0000000e V _ZTV7AP_VarSI7Matrix3IfEE -0000000e V _ZTV7AP_VarSI7Vector3IfEE -0000000e V _ZTV7AP_VarTIaE -0000000e V _ZTV7AP_VarTIfE -0000000e V _ZTV7AP_VarTIiE -0000000e r _ZZL10erase_logshPKN4Menu3argEE3__c_0 -0000000e r _ZZL10setup_helihPKN4Menu3argEE3__c -0000000e r _ZZL10setup_modehPKN4Menu3argEE3__c -0000000e r _ZZL10test_sonarhPKN4Menu3argEE3__c_0 -0000000e r _ZZL11select_logshPKN4Menu3argEE3__c_1 -0000000e r _ZZL14print_log_menuvE3__c_2 -0000000e r _ZZL18print_radio_valuesvE3__c -0000000e r _ZZL18print_radio_valuesvE3__c_0 -0000000e r _ZZL18print_radio_valuesvE3__c_1 -0000000e r _ZZL18print_radio_valuesvE3__c_2 -0000000e r _ZZL18print_radio_valuesvE3__c_3 -0000000e r _ZZL18print_radio_valuesvE3__c_4 -0000000e r _ZZL18print_radio_valuesvE3__c_5 -0000000e r _ZZL19report_batt_monitorvE3__c_3 -0000000e r _ZZL19report_flight_modesvE3__c -0000000e r _ZZL8dump_loghPKN4Menu3argEE3__c -0000000e V _ZZN10ParametersC1EvE3__c -0000000e V _ZZN10ParametersC1EvE3__c_0 -0000000e V _ZZN10ParametersC1EvE3__c_1 -0000000e V _ZZN10ParametersC1EvE3__c_13 -0000000e V _ZZN10ParametersC1EvE3__c_15 -0000000e V _ZZN10ParametersC1EvE3__c_20 -0000000e V _ZZN10ParametersC1EvE3__c_22 -0000000e V _ZZN10ParametersC1EvE3__c_4 -0000000e V _ZZN10ParametersC1EvE3__c_7 -0000000f b _ZL11current_loc -0000000f b _ZL12next_command -0000000f r _ZL22__menu_name__main_menu -0000000f b _ZL4home -0000000f b _ZL7next_WP -0000000f b _ZL7prev_WP -0000000f b _ZL9guided_WP -0000000f b _ZL9simple_WP -0000000f b _ZL9target_WP -0000000f r _ZZL11report_helivE3__c_5 -0000000f r _ZZL14print_log_menuvE3__c -0000000f r _ZZL14print_log_menuvE3__c_1 -0000000f r _ZZL14report_versionvE3__c -0000000f r _ZZL19report_batt_monitorvE3__c -0000000f r _ZZL8test_imuhPKN4Menu3argEE3__c -0000000f V _ZZN13AP_IMU_OilpanC1EP6AP_ADCjE3__c -00000010 r _ZL21planner_menu_commands -00000010 b _ZL9motor_out -00000010 W _ZNK7AP_VarTIfE13cast_to_floatEv -00000010 r _ZZL10test_sonarhPKN4Menu3argEE3__c -00000010 r _ZZL11report_gyrovE3__c -00000010 r _ZZL11report_helivE3__c_6 -00000010 r _ZZL14report_compassvE3__c_0 +0000000e t global destructors keyed to Serial +0000000e t global constructors keyed to Serial +0000000e V vtable for AP_Float16 +0000000e V vtable for AP_VarA +0000000e V vtable for AP_VarS > +0000000e V vtable for AP_VarS > +0000000e V vtable for AP_VarT +0000000e V vtable for AP_VarT +0000000e V vtable for AP_VarT +0000000e r erase_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_heli(unsigned char, Menu::arg const*)::__c +0000000e r setup_mode(unsigned char, Menu::arg const*)::__c +0000000e r test_sonar(unsigned char, Menu::arg const*)::__c +0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r print_log_menu()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r report_batt_monitor()::__c +0000000e r report_flight_modes()::__c +0000000e r dump_log(unsigned char, Menu::arg const*)::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000f b current_loc +0000000f b next_command +0000000f b home +0000000f b next_WP +0000000f b prev_WP +0000000f b guided_WP +0000000f b target_WP +0000000f r report_heli()::__c +0000000f r print_log_menu()::__c +0000000f r print_log_menu()::__c +0000000f r report_version()::__c +0000000f r report_batt_monitor()::__c +0000000f r test_imu(unsigned char, Menu::arg const*)::__c +0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c +00000010 r planner_menu_commands +00000010 b motor_out +00000010 W AP_VarT::cast_to_float() const +00000010 r test_sonar(unsigned char, Menu::arg const*)::__c +00000010 r report_gyro()::__c +00000010 r report_heli()::__c +00000010 r report_compass()::__c 00000010 t mavlink_get_channel_status -00000011 r _ZZL10erase_logshPKN4Menu3argEE3__c -00000011 r _ZZL10setup_helihPKN4Menu3argEE3__c_8 -00000011 r _ZZL11zero_eepromvE3__c -00000011 r _ZZL15update_commandsvE3__c -00000011 r _ZZL17Log_Read_AttitudevE3__c +00000011 r erase_logs(unsigned char, Menu::arg const*)::__c +00000011 r setup_heli(unsigned char, Menu::arg const*)::__c +00000011 r zero_eeprom()::__c +00000011 r update_commands()::__c +00000011 r Log_Read_Attitude()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 -00000012 r _ZL19flight_mode_strings -00000012 W _ZN10AP_Float16D1Ev -00000012 W _ZN7AP_VarAIfLh6EED1Ev -00000012 W _ZN7AP_VarSI7Matrix3IfEED1Ev -00000012 W _ZN7AP_VarSI7Vector3IfEED1Ev -00000012 W _ZN7AP_VarTIaED1Ev -00000012 W _ZN7AP_VarTIfED1Ev -00000012 W _ZN7AP_VarTIiED1Ev -00000012 W _ZNK7AP_VarTIaE9serializeEPvj -00000012 r _ZZL10print_donevE3__c -00000012 r _ZZL10setup_helihPKN4Menu3argEE3__c_12 -00000012 r _ZZL11select_logshPKN4Menu3argEE3__c -00000012 r _ZZL11setup_framehPKN4Menu3argEE3__c_3 -00000012 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c -00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_13 -00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_6 -00000013 r _ZZL11report_helivE3__c_1 -00000013 r _ZZL11report_helivE3__c_2 -00000013 r _ZZL11report_helivE3__c_3 -00000013 r _ZZL11report_helivE3__c_4 -00000013 r _ZZL13setup_compasshPKN4Menu3argEE3__c_1 -00000013 r _ZZL14change_commandhE3__c -00000013 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c_0 -00000014 W _ZN7AP_VarTIaE11unserializeEPvj -00000014 W _ZNK7AP_VarTIaE13cast_to_floatEv -00000014 W _ZNK7AP_VarTIiE13cast_to_floatEv -00000014 r _ZZL10setup_helihPKN4Menu3argEE3__c_1 -00000014 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_1 -00000014 r _ZZL8test_trihPKN4Menu3argEE3__c -00000015 r _ZZL12map_baudrateamE3__c -00000015 r _ZZL14init_ardupilotvE3__c_0 -00000015 r _ZZL15Log_Read_MotorsvE3__c -00000015 r _ZZL15print_hit_entervE3__c -00000015 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c_0 -00000016 r _ZZL10setup_helihPKN4Menu3argEE3__c_0 -00000016 r _ZZL14init_ardupilotvE3__c -00000016 r _ZZN11GCS_MAVLINK6updateEvE3__c +00000012 r flight_mode_strings +00000012 W AP_Float16::~AP_Float16() +00000012 W AP_VarA::~AP_VarA() +00000012 W AP_VarS >::~AP_VarS() +00000012 W AP_VarS >::~AP_VarS() +00000012 W AP_VarT::~AP_VarT() +00000012 W AP_VarT::~AP_VarT() +00000012 W AP_VarT::~AP_VarT() +00000012 W AP_VarT::serialize(void*, unsigned int) const +00000012 r print_done()::__c +00000012 r setup_heli(unsigned char, Menu::arg const*)::__c +00000012 r select_logs(unsigned char, Menu::arg const*)::__c +00000012 r setup_frame(unsigned char, Menu::arg const*)::__c +00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c +00000013 r setup_heli(unsigned char, Menu::arg const*)::__c +00000013 r setup_heli(unsigned char, Menu::arg const*)::__c +00000013 r report_heli()::__c +00000013 r report_heli()::__c +00000013 r report_heli()::__c +00000013 r report_heli()::__c +00000013 r setup_compass(unsigned char, Menu::arg const*)::__c +00000013 r change_command(unsigned char)::__c +00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c +00000014 W AP_VarT::unserialize(void*, unsigned int) +00000014 W AP_VarT::cast_to_float() const +00000014 W AP_VarT::cast_to_float() const +00000014 r setup_heli(unsigned char, Menu::arg const*)::__c +00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c +00000014 r test_tri(unsigned char, Menu::arg const*)::__c +00000015 r map_baudrate(signed char, unsigned long)::__c +00000015 r init_ardupilot()::__c +00000015 r Log_Read_Motors()::__c +00000015 r print_hit_enter()::__c +00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c +00000016 r setup_heli(unsigned char, Menu::arg const*)::__c +00000016 r init_ardupilot()::__c +00000016 r GCS_MAVLINK::update()::__c 00000016 B sonar -00000018 b _ZL11baro_filter -00000018 t _ZL11setup_accelhPKN4Menu3argE -00000018 T _ZN11GCS_MAVLINK12send_messageEhm -00000018 W _ZNK7AP_VarTIiE9serializeEPvj -00000019 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_1 -00000019 r _ZZN11GCS_MAVLINK6updateEvE3__c_0 -0000001a t _ZL10clear_ledsv -0000001a r _ZZL14print_log_menuvE3__c_12 -0000001b r _ZZL10setup_helihPKN4Menu3argEE3__c_2 -0000001b r _ZZL11report_helivE3__c_0 -0000001c W _ZN7AP_VarAIfLh6EE11unserializeEPvj -0000001c W _ZN7AP_VarSI7Matrix3IfEE11unserializeEPvj -0000001c W _ZN7AP_VarSI7Vector3IfEE11unserializeEPvj -0000001c W _ZN7AP_VarTIiE11unserializeEPvj -0000001c W _ZNK7AP_VarAIfLh6EE9serializeEPvj -0000001c W _ZNK7AP_VarSI7Matrix3IfEE9serializeEPvj -0000001c W _ZNK7AP_VarSI7Vector3IfEE9serializeEPvj -0000001c b _ZZ26mavlink_get_channel_statusE16m_mavlink_status -0000001e r _ZZL11report_helivE3__c_7 -0000001e r _ZZL16Log_Read_OptflowvE3__c -0000001f r _ZZL8test_maghPKN4Menu3argEE3__c -00000020 r _ZZL12test_currenthPKN4Menu3argEE3__c -00000021 r _ZZL10setup_helihPKN4Menu3argEE3__c_7 -00000021 r _ZZL14print_log_menuvE3__c_14 -00000021 r _ZZL14report_compassvE3__c_1 -00000021 r _ZZL16Log_Read_CurrentvE3__c -00000022 t _ZL12print_blanksi -00000022 W _ZN10AP_Float16D0Ev -00000022 W _ZN7AP_VarAIfLh6EED0Ev -00000022 W _ZN7AP_VarSI7Matrix3IfEED0Ev -00000022 W _ZN7AP_VarSI7Vector3IfEED0Ev -00000022 W _ZN7AP_VarTIaED0Ev -00000022 W _ZN7AP_VarTIfED0Ev -00000022 W _ZN7AP_VarTIiED0Ev -00000023 r _ZZL10setup_helihPKN4Menu3argEE3__c_4 -00000023 r _ZZL10setup_modehPKN4Menu3argEE3__c_1 -00000023 r _ZZL18print_gyro_offsetsvE3__c -00000024 r _ZZL10setup_helihPKN4Menu3argEE3__c_3 -00000024 r _ZZL19print_accel_offsetsvE3__c -00000025 r _ZZL13setup_factoryhPKN4Menu3argEE3__c_0 -00000026 t _ZL10print_donev -00000026 t _ZL15print_hit_enterv -00000026 t _ZL16Log_Read_Startupv -00000026 r _ZZL19Log_Read_Nav_TuningvE3__c -00000026 B barometer -00000027 r _ZZL9test_xbeehPKN4Menu3argEE3__c -00000028 t _ZL12test_batteryhPKN4Menu3argE -00000028 t _ZL14main_menu_helphPKN4Menu3argE -00000028 t _ZL8help_loghPKN4Menu3argE -00000028 W _ZN7AP_VarTIfE11unserializeEPvj -00000028 W _ZNK7AP_VarTIfE9serializeEPvj -00000028 r _ZZL12Log_Read_CmdvE3__c -00000029 r _ZZL10setup_helihPKN4Menu3argEE3__c_9 -00000029 r _ZZL10setup_modehPKN4Menu3argEE3__c_0 -00000029 r _ZZL8test_gpshPKN4Menu3argEE3__c -0000002a t _ZL11reset_nav_Iv -0000002a t _ZL17setup_declinationhPKN4Menu3argE -0000002b r _ZZL12planner_modehPKN4Menu3argEE3__c -0000002c t _ZL7freeRAMv -0000002e t _ZL12setup_motorshPKN4Menu3argE -0000002e t _ZL13print_dividerv -0000002e t _ZL9send_ratejj -0000002e W _ZN12AP_Var_groupC1EjPK11prog_char_th -0000002f r _ZZL10test_radiohPKN4Menu3argEE3__c -00000030 t _ZL12planner_modehPKN4Menu3argE -00000030 t put_int32_t_by_index -00000032 T _ZN11GCS_MAVLINK4initEP12BetterStream -00000032 r _ZZL10setup_helihPKN4Menu3argEE3__c_5 -00000034 t _ZL14heli_get_servoi -00000034 W _ZNK10AP_Float169serializeEPvj -00000035 r _ZZL14test_radio_pwmhPKN4Menu3argEE3__c -00000036 t _ZL12report_radiov -00000036 r _ZZL12Log_Read_GPSvE3__c -00000037 r _ZZL8print_wpP8LocationhE3__c -00000038 t _ZL20init_throttle_cruisev -00000038 r _ZZL11setup_radiohPKN4Menu3argEE3__c -00000038 r _ZZL13setup_factoryhPKN4Menu3argEE3__c -0000003a t _ZL10report_gpsv -0000003a t _ZL10report_imuv -0000003a t _ZL12comm_send_ch17mavlink_channel_th -0000003a W _ZN3PIDD1Ev -0000003c W _ZN10RC_ChannelD1Ev -0000003d r _ZZL23Log_Read_Control_TuningvE3__c +00000017 r __menu_name__main_menu +00000018 t setup_tune(unsigned char, Menu::arg const*) +00000018 t setup_accel(unsigned char, Menu::arg const*) +00000018 W AP_VarT::serialize(void*, unsigned int) const +00000018 b mavlink_get_channel_status::m_mavlink_status +00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000019 r GCS_MAVLINK::update()::__c +0000001a r print_log_menu()::__c +0000001b r setup_heli(unsigned char, Menu::arg const*)::__c +0000001b r report_heli()::__c +0000001c W AP_VarA::unserialize(void*, unsigned int) +0000001c W AP_VarS >::unserialize(void*, unsigned int) +0000001c W AP_VarS >::unserialize(void*, unsigned int) +0000001c W AP_VarT::unserialize(void*, unsigned int) +0000001c W AP_VarA::serialize(void*, unsigned int) const +0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001e r report_heli()::__c +0000001e r Log_Read_Optflow()::__c +0000001e r Log_Read_Nav_Tuning()::__c +0000001f r test_mag(unsigned char, Menu::arg const*)::__c +00000020 r test_current(unsigned char, Menu::arg const*)::__c +00000020 t byte_swap_4 +00000021 r setup_heli(unsigned char, Menu::arg const*)::__c +00000021 r print_log_menu()::__c +00000021 r report_compass()::__c +00000021 r Log_Read_Current()::__c +00000022 t clear_leds() +00000022 t print_blanks(int) +00000022 t reset_hold_I() +00000022 W AP_Float16::~AP_Float16() +00000022 W AP_VarA::~AP_VarA() +00000022 W AP_VarS >::~AP_VarS() +00000022 W AP_VarS >::~AP_VarS() +00000022 W AP_VarT::~AP_VarT() +00000022 W AP_VarT::~AP_VarT() +00000022 W AP_VarT::~AP_VarT() +00000023 r setup_heli(unsigned char, Menu::arg const*)::__c +00000023 r setup_mode(unsigned char, Menu::arg const*)::__c +00000023 r print_gyro_offsets()::__c +00000024 t startup_ground() +00000024 r setup_heli(unsigned char, Menu::arg const*)::__c +00000024 r init_ardupilot()::__c +00000024 r print_accel_offsets()::__c +00000025 r setup_factory(unsigned char, Menu::arg const*)::__c +00000026 t print_done() +00000026 b mavlink_queue +00000026 t print_hit_enter() +00000026 t Log_Read_Startup() +00000027 r test_xbee(unsigned char, Menu::arg const*)::__c +00000028 t test_battery(unsigned char, Menu::arg const*) +00000028 t main_menu_help(unsigned char, Menu::arg const*) +00000028 t help_log(unsigned char, Menu::arg const*) +00000028 W AP_VarT::unserialize(void*, unsigned int) +00000028 W AP_VarT::serialize(void*, unsigned int) const +00000028 r Log_Read_Cmd()::__c +00000029 r setup_heli(unsigned char, Menu::arg const*)::__c +00000029 r setup_mode(unsigned char, Menu::arg const*)::__c +00000029 r test_gps(unsigned char, Menu::arg const*)::__c +0000002a t setup_declination(unsigned char, Menu::arg const*) +0000002a r Log_Read_Control_Tuning()::__c +0000002b r planner_mode(unsigned char, Menu::arg const*)::__c +0000002e t setup_motors(unsigned char, Menu::arg const*) +0000002e t print_divider() +0000002e t send_rate(unsigned int, unsigned int) +0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) +0000002e r Log_Read_Performance()::__c +0000002f r test_radio(unsigned char, Menu::arg const*)::__c +00000030 t planner_mode(unsigned char, Menu::arg const*) +00000032 T GCS_MAVLINK::init(BetterStream*) +00000032 W APM_PI::~APM_PI() +00000032 r setup_heli(unsigned char, Menu::arg const*)::__c +00000034 t heli_get_servo(int) +00000034 W AP_Float16::serialize(void*, unsigned int) const +00000034 t _mav_put_int8_t_array +00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c +00000036 t report_radio() +00000036 r Log_Read_GPS()::__c +00000037 r print_wp(Location*, unsigned char)::__c +00000038 t init_throttle_cruise() +00000038 r setup_radio(unsigned char, Menu::arg const*)::__c +00000038 r setup_factory(unsigned char, Menu::arg const*)::__c +0000003a t report_gps() +0000003a t report_imu() +0000003c W RC_Channel::~RC_Channel() 0000003d B g_gps_driver -0000003e t _ZL10verify_RTLv -0000003e T _ZN11GCS_MAVLINK9send_textEhPK11prog_char_t -0000003e W _ZN7AP_VarTIaEC1EajPK11prog_char_th -00000040 W _ZN10AP_Float1611unserializeEPvj -00000042 T _Z10output_minv -00000042 t _ZL12report_sonarv -00000042 r _ZZL10setup_helihPKN4Menu3argEE3__c_10 -00000044 W _ZN7AP_VarTIiEC1EijPK11prog_char_th -0000004a t _ZL19read_control_switchv -0000004a W _ZN7AP_VarTIiEC1EP12AP_Var_groupjiPK11prog_char_th -0000004a t mavlink_msg_waypoint_current_send -0000004a t mavlink_update_checksum -0000004c t _ZL10setup_showhPKN4Menu3argE -0000004c t _ZL14update_nav_yawv +0000003e t verify_RTL() +0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) +0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) +00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 t byte_swap_8 +00000040 t crc_accumulate +00000042 T output_min() +00000042 t report_sonar() +00000042 r setup_heli(unsigned char, Menu::arg const*)::__c +00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) +0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) +0000004c t setup_show(unsigned char, Menu::arg const*) +0000004c t update_auto_yaw() 0000004c B imu -0000004e t mavlink_msg_waypoint_ack_send -00000050 r _ZL17log_menu_commands -00000050 r _ZL18main_menu_commands -00000050 t _ZL9read_AHRSv -00000050 T _ZN11GCS_MAVLINK15_find_parameterEj -00000050 t mavlink_msg_waypoint_request_send -00000052 t _ZL14change_commandh -00000052 t _ZL14report_versionv -00000054 t _ZL13print_enabledh -00000054 t _ZL17update_motor_ledsv -00000054 t _ZL19report_flight_modesv -00000055 r _ZZL14main_menu_helphPKN4Menu3argEE3__c -00000055 r _ZZL17setup_flightmodeshPKN4Menu3argEE3__c -00000056 t _ZL10readSwitchv -00000056 t _ZL13dancing_lightv -00000057 r _ZZL8help_loghPKN4Menu3argEE3__c -00000058 t _ZL11test_tuninghPKN4Menu3argE -00000058 t _ZL14startup_groundv -00000058 t _ZL18Log_Write_Attitudev -0000005a t _ZL12report_framev -0000005a t mavlink_msg_statustext_send -0000005c t _ZL12get_num_logsv -0000005c t _ZL9setup_eschPKN4Menu3argE -0000005e t _ZL16update_GPS_lightv -0000005e t _ZL18radio_input_switchv -0000005e T _ZN11GCS_MAVLINK17_count_parametersEv -0000005f r _ZZL10setup_helihPKN4Menu3argEE3__c_11 -00000060 W _ZN10AP_Float16C1EP12AP_Var_groupjfPK11prog_char_th -00000062 t _ZL12print_switchhh -00000064 t _ZL9test_xbeehPKN4Menu3argE -00000068 t _ZL11zero_eepromv -00000068 t _ZL18find_last_log_pagei -0000006a t _ZL20read_num_from_serialv -0000006a W _ZN11GCS_MAVLINKD1Ev -0000006c t _ZL11setup_sonarhPKN4Menu3argE -00000074 t _ZL19output_motors_armedv -00000078 t _ZL18setup_batt_monitorhPKN4Menu3argE -0000007a t _ZL13setup_factoryhPKN4Menu3argE -0000007a t _ZL18get_nav_yaw_offsetii -0000007c t _ZL9test_barohPKN4Menu3argE -0000007e t _ZL11test_rawgpshPKN4Menu3argE +0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) +00000050 r log_menu_commands +00000050 r main_menu_commands +00000050 t read_AHRS() +00000050 T GCS_MAVLINK::_find_parameter(unsigned int) +00000052 t change_command(unsigned char) +00000052 t report_version() +00000054 t print_enabled(unsigned char) +00000054 t update_motor_leds() +00000054 t report_flight_modes() +00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c +00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000056 t readSwitch() +00000056 t dancing_light() +00000057 r help_log(unsigned char, Menu::arg const*)::__c +00000058 t Log_Write_Attitude() +0000005a t report_frame() +0000005a t read_control_switch() +0000005c t get_num_logs() +0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t update_GPS_light() +0000005e t radio_input_switch() +0000005e T GCS_MAVLINK::_count_parameters() +0000005f r setup_heli(unsigned char, Menu::arg const*)::__c +00000060 t _mavlink_send_uart +00000060 B barometer +00000062 t print_switch(unsigned char, unsigned char) +00000064 t test_xbee(unsigned char, Menu::arg const*) +00000064 t mavlink_msg_param_value_send +00000068 t zero_eeprom() +00000068 t find_last_log_page(int) +0000006a t read_num_from_serial() +0000006a W GCS_MAVLINK::~GCS_MAVLINK() +0000006c t setup_sonar(unsigned char, Menu::arg const*) +00000074 t output_motors_armed() +00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) +0000007a t setup_factory(unsigned char, Menu::arg const*) +0000007c t test_baro(unsigned char, Menu::arg const*) +0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 -00000082 t _ZL6do_RTLv -00000084 t mavlink_send_uart -00000086 t _ZL17Log_Read_Attitudev -00000088 t _ZL12Log_Read_Rawv -0000008c t _ZL11setup_framehPKN4Menu3argE -0000008c t _ZL18print_gyro_offsetsv -0000008c t _ZL19print_accel_offsetsv -00000092 t _ZL11report_gyrov -00000095 r _ZZL14init_ardupilotvE3__c_1 -00000096 t _ZL12map_baudrateam -00000096 t _ZL8print_wpP8Locationh -0000009a t _ZL12init_compassv -0000009a t _ZL14init_barometerv -0000009a t _ZL15Log_Read_Motorsv +00000082 t do_RTL() +00000086 t Log_Read_Attitude() +00000088 t Log_Read_Raw() +0000008c t setup_frame(unsigned char, Menu::arg const*) +0000008c t print_gyro_offsets() +0000008c t print_accel_offsets() +00000090 t dump_log(unsigned char, Menu::arg const*) +00000092 t report_gyro() +00000092 t test_tuning(unsigned char, Menu::arg const*) +00000092 t report_tuning() +00000095 r init_ardupilot()::__c +00000096 t map_baudrate(signed char, unsigned long) +00000096 t print_wp(Location*, unsigned char) +0000009a t init_compass() +0000009a t Log_Read_Motors() 0000009d B gcs 0000009d B hil -0000009e t _ZL10setup_modehPKN4Menu3argE -0000009e t _ZL13Log_Write_CmdhP8Location -000000a0 t _ZL13Log_Read_Modev +0000009e t setup_mode(unsigned char, Menu::arg const*) +0000009e t Log_Write_Cmd(unsigned char, Location*) +000000a0 t Log_Read_Mode() 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 -000000a6 t mavlink_msg_param_value_send -000000aa t _ZL10test_sonarhPKN4Menu3argE -000000ac t _ZL20Log_Read_Performancev -000000ae t _ZL13auto_throttlev -000000b0 t _ZL10read_radiov -000000b2 t _ZL10erase_logshPKN4Menu3argE -000000b2 t _ZL8dump_loghPKN4Menu3argE -000000b4 t _ZL10test_relayhPKN4Menu3argE -000000b4 t _ZL11planner_gcshPKN4Menu3argE -000000b6 t _ZL18get_log_boundarieshRiS_ +000000aa t test_sonar(unsigned char, Menu::arg const*) +000000b0 t read_radio() +000000b2 t erase_logs(unsigned char, Menu::arg const*) +000000b4 t test_relay(unsigned char, Menu::arg const*) +000000b4 t planner_gcs(unsigned char, Menu::arg const*) +000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass -000000c2 t _ZL13setup_compasshPKN4Menu3argE -000000c4 t _ZL12get_distanceP8LocationS0_ -000000c4 t _ZL13update_eventsv -000000c4 r _ZZL9setup_eschPKN4Menu3argEE3__c -000000c6 t _ZL11test_eedumphPKN4Menu3argE -000000c6 t _ZL8Log_Readii -000000c6 t _ZL8test_trihPKN4Menu3argE +000000be t Log_Read_Nav_Tuning() +000000c2 t setup_compass(unsigned char, Menu::arg const*) +000000c4 t get_distance(Location*, Location*) +000000c4 t update_events() +000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c +000000c6 t test_eedump(unsigned char, Menu::arg const*) +000000c6 t Log_Read(int, int) +000000c6 t test_tri(unsigned char, Menu::arg const*) 000000c7 B dcm -000000c8 t _ZL14read_barometerv -000000ca t _ZL12get_throttlei -000000ce W _ZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKi -000000d0 t _ZL11get_bearingP8LocationS0_ -000000d8 t _ZL10test_radiohPKN4Menu3argE -000000dc t _ZL18read_baro_filteredv -000000de t _ZL8test_adchPKN4Menu3argE -000000e4 t _ZL14test_radio_pwmhPKN4Menu3argE -000000e4 t _ZL16Log_Read_Optflowv -000000e6 t _ZL17setup_flightmodeshPKN4Menu3argE -000000e6 t _ZL19Log_Read_Nav_Tuningv -000000e6 t mavlink_finalize_message_chan -000000e8 t _ZL16Log_Read_Currentv -000000ec t put_uint64_t_by_index -000000ee t _ZL19report_batt_monitorv -000000f0 r _ZL19setup_menu_commands -000000f2 t _ZL18get_stabilize_rolll -000000f2 t _ZL19get_stabilize_pitchl -000000f6 t _ZL12Log_Read_Cmdv -000000fc T _ZN11GCS_MAVLINK12_queued_sendEv -00000106 t _ZL10setup_gyrohPKN4Menu3argE -0000010a t _ZL8test_gpshPKN4Menu3argE -0000010c W _ZN10RC_ChannelC1EjPK11prog_char_t -00000112 t _ZL12test_currenthPKN4Menu3argE -00000112 t _ZL15adjust_altitudev -00000112 T _ZN11GCS_MAVLINKC1Ej -00000112 T _ZN11GCS_MAVLINKC2Ej -00000118 t _ZL22set_command_with_index8Locationi -00000120 r _ZL18test_menu_commands -00000128 t _ZL22get_command_with_indexi -0000012c t _ZL23Log_Read_Control_Tuningv -00000130 t _ZL14report_compassv -00000144 t _ZL15calc_nav_outputv -0000014c T _ZN11GCS_MAVLINK6updateEv -00000150 t _ZL11update_trigv -00000152 t _ZL11set_next_WPP8Location -00000156 t _ZL12Log_Read_GPSv -0000015c t _ZL10arm_motorsv -00000166 t _ZL11select_logshPKN4Menu3argE -0000016c t _ZL15update_commandsv -00000170 t _ZL8test_maghPKN4Menu3argE -0000017e t _ZL17get_stabilize_yawlf -0000018e T _ZN11GCS_MAVLINK16data_stream_sendEjj -00000196 t _ZL8set_modeh -000001a0 t _ZL9init_homev -000001a8 t _ZL18print_radio_valuesv -000001ae t _ZL13mavlink_delaym -000001b8 t _ZL8test_imuhPKN4Menu3argE -000001c4 t _ZL17update_crosstrackv -000001ce t _ZL13start_new_logv -0000020c b _ZZ18mavlink_parse_charE17m_mavlink_message -00000220 t _ZL7test_wphPKN4Menu3argE -00000228 t _ZL11setup_radiohPKN4Menu3argE -00000264 t _ZL13update_nav_wpv -00000288 t _ZL13calc_rate_navi -000002b8 t _ZL15heli_init_swashv -000002d0 t _ZL11report_heliv -0000031e t _ZL12read_batteryv -00000368 t _ZL15heli_move_swashiiii -00000384 t _ZL14print_log_menuv -0000055e t mavlink_parse_char -00000628 t _ZL14init_ardupilotv -0000071a t _ZL10setup_helihPKN4Menu3argE -00000800 t _Z41__static_initialization_and_destruction_0ii -00000866 T _Z26update_current_flight_modev -000008f4 t _ZL20process_next_commandv -0000097e W _ZN10ParametersC1Ev -00000b3c b _ZL1g -00001148 T _ZN11GCS_MAVLINK13handleMessageEP17__mavlink_message -000015be T _Z20mavlink_send_message17mavlink_channel_thmj -00001ab0 T loop +000000ca t init_barometer() +000000d0 t get_bearing(Location*, Location*) +000000d8 t test_radio(unsigned char, Menu::arg const*) +000000d8 t read_barometer() +000000de t Log_Read_Performance() +000000de t Log_Read_Control_Tuning() +000000de t test_adc(unsigned char, Menu::arg const*) +000000e0 b mavlink_parse_char::m_mavlink_message +000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) +000000e4 t Log_Read_Optflow() +000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&) +000000e6 t setup_flightmodes(unsigned char, Menu::arg const*) +000000e8 t Log_Read_Current() +000000ee t report_batt_monitor() +000000f4 t _mav_finalize_message_chan_send +000000f6 t Log_Read_Cmd() +000000fa t calc_nav_pitch_roll() +00000100 r setup_menu_commands +00000106 t setup_gyro(unsigned char, Menu::arg const*) +0000010a t test_gps(unsigned char, Menu::arg const*) +0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +00000112 t test_current(unsigned char, Menu::arg const*) +00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000118 t set_command_with_index(Location, int) +00000118 T GCS_MAVLINK::_queued_send() +00000120 r test_menu_commands +00000128 t get_command_with_index(int) +00000130 t report_compass() +00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) +0000014e T GCS_MAVLINK::update() +00000150 t update_trig() +00000152 t set_next_WP(Location*) +00000156 t Log_Read_GPS() +00000166 t select_logs(unsigned char, Menu::arg const*) +0000016c t update_commands() +00000170 t test_mag(unsigned char, Menu::arg const*) +00000172 t update_nav_wp() +000001a0 t init_home() +000001a8 t print_radio_values() +000001b8 t test_imu(unsigned char, Menu::arg const*) +000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +000001ca t arm_motors() +000001ca t mavlink_delay(unsigned long) +000001ce t start_new_log() +00000202 t set_mode(unsigned char) +00000220 t test_wp(unsigned char, Menu::arg const*) +00000228 t setup_radio(unsigned char, Menu::arg const*) +000002b8 t heli_init_swash() +000002d0 t report_heli() +000002ea t tuning() +00000330 t calc_nav_rate(int, int, int, int) +00000358 T update_throttle_mode() +00000368 t heli_move_swash(int, int, int, int) +00000384 t print_log_menu() +000003be t read_battery() +0000042a T update_yaw_mode() +000004b2 t mavlink_parse_char +00000556 T update_roll_pitch_mode() +00000632 t init_ardupilot() +0000071a t setup_heli(unsigned char, Menu::arg const*) +00000818 t __static_initialization_and_destruction_0(int, int) +000008e4 t process_next_command() +0000097a W Parameters::Parameters() +000009ad b g +000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*) +000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) +00001af6 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log index 9185b06998..cd38550546 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log @@ -1,94 +1,64 @@ - -%%%% Making all in ArduCopterMega/ %%%% - -make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduCopterMega' -%% ArduCopterMega.cpp -%% ArduCopterMega.o -In file included from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:53: +%% ArduCopter.cpp +%% ArduCopter.o +In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:53: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:68: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions -/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde: In function 'void init_compass()': -/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:458: warning: unused variable 'junkbool' -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)': -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_tail' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_tail' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_coll' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'min_coll' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_pitch' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:435: warning: 'max_roll' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/setup.pde:433: warning: 'temp' may be used uninitialized in this function -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde: At global scope: -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1494: warning: 'void tuning()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:1586: warning: 'void point_at_home_yaw()' defined but not used -autogenerated:31: warning: 'int alt_hold_velocity()' declared 'static' but never defined -autogenerated:83: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined -autogenerated:84: warning: 'void send_message(byte)' declared 'static' but never defined -autogenerated:85: warning: 'void send_message(byte, long int)' declared 'static' but never defined -autogenerated:79: warning: 'void send_message(byte, const char*)' declared 'static' but never defined -autogenerated:88: warning: 'void print_current_waypoints()' declared 'static' but never defined -autogenerated:91: warning: 'void print_attitude()' declared 'static' but never defined -autogenerated:87: warning: 'void print_control_mode()' declared 'static' but never defined -autogenerated:89: warning: 'void print_position()' declared 'static' but never defined -autogenerated:93: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined -autogenerated:94: warning: 'void print_waypoints()' declared 'static' but never defined -autogenerated:67: warning: 'long int convert_to_dec(float)' declared 'static' but never defined -autogenerated:135: warning: 'void Log_Write_Optflow()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:127: warning: 'void decrement_WP_index()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/commands.pde:148: warning: 'Location get_LOITER_home_wp()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/commands_logic.pde:429: warning: 'bool verify_loiter_unlim()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:40: warning: 'void update_servo_switches()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/events.pde:49: warning: 'void low_battery_event()' defined but not used -autogenerated:232: warning: 'void debug_motors()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:194: warning: 'void calc_altitude_smoothing_error()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:267: warning: 'void reset_crosstrack()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:272: warning: 'long int get_altitude_above_home()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/navigation.pde:293: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:155: warning: 'void throttle_failsafe(uint16_t)' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/radio.pde:212: warning: 'void trim_yaw()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)': +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_coll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'min_coll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_pitch' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:446: warning: 'max_roll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:444: warning: 'temp' may be used uninitialized in this function +autogenerated: At global scope: +autogenerated:34: warning: 'int alt_hold_velocity()' declared 'static' but never defined +autogenerated:86: warning: 'void acknowledge(byte, byte, byte)' declared 'static' but never defined +autogenerated:87: warning: 'void send_message(byte)' declared 'static' but never defined +autogenerated:88: warning: 'void send_message(byte, long int)' declared 'static' but never defined +autogenerated:82: warning: 'void send_message(byte, const char*)' declared 'static' but never defined +autogenerated:91: warning: 'void print_current_waypoints()' declared 'static' but never defined +autogenerated:94: warning: 'void print_attitude()' declared 'static' but never defined +autogenerated:90: warning: 'void print_control_mode()' declared 'static' but never defined +autogenerated:92: warning: 'void print_position()' declared 'static' but never defined +autogenerated:96: warning: 'void print_waypoint(Location*, byte)' declared 'static' but never defined +autogenerated:97: warning: 'void print_waypoints()' declared 'static' but never defined +autogenerated:70: warning: 'long int convert_to_dec(float)' declared 'static' but never defined +autogenerated:139: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +autogenerated:150: warning: 'void decrement_WP_index()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands.pde:149: warning: 'Location get_LOITER_home_wp()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:301: warning: 'void do_loiter_turns()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:427: warning: 'bool verify_loiter_unlim()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used +autogenerated:235: warning: 'void debug_motors()' declared 'static' but never defined +autogenerated:250: warning: 'void calc_altitude_smoothing_error()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:159: warning: 'int get_loiter_angle()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:217: warning: 'void reset_crosstrack()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:222: warning: 'long int get_altitude_above_home()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:243: warning: 'long int get_alt_distance(Location*, Location*)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:131: warning: 'void throttle_failsafe(uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/radio.pde:188: warning: 'void trim_yaw()' defined but not used autogenerated:268: warning: 'void readCommands()' declared 'static' but never defined autogenerated:269: warning: 'void parseCommand(char*)' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:78: warning: 'void read_airspeed()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/sensors.pde:83: warning: 'void zero_airspeed()' defined but not used -autogenerated:282: warning: 'void report_gains()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/system.pde:420: warning: 'void set_failsafe(boolean)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used +autogenerated:272: warning: 'long int read_baro_filtered()' declared 'static' but never defined +/root/apm/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/system.pde:465: warning: 'void set_failsafe(boolean)' defined but not used autogenerated:311: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduCopterMega/test.pde:1099: warning: 'void print_motor_out()' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_min' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:279: warning: 'heli_servo_max' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:280: warning: 'heli_servo_out' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:294: warning: 'rate_yaw_flag' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:296: warning: 'did_clear_yaw_control' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:303: warning: 'timer_light' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:322: warning: 'nav_gain_scaler' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:324: warning: 'last_ground_speed' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:339: warning: 'simple_bearing_is_set' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:356: warning: 'distance_error' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:388: warning: 'baro_alt_offset' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:397: warning: 'landing_distance' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:420: warning: 'set_throttle_cruise_flag' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:437: warning: 'next_wp_index' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:447: warning: 'repeat_forever' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:448: warning: 'undo_event' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:454: warning: 'condition_rate' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:473: warning: 'optflow_offset' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:474: warning: 'new_location' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:485: warning: 'imu_health' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:488: warning: 'gcs_messages_sent' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:493: warning: 'GCS_buffer' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:494: warning: 'display_PID' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/ArduCopterMega.pde:517: warning: 'elapsedTime' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/control_modes.pde:46: warning: 'trim_timer' defined but not used -/root/apm/Sketchbook/trunk/ArduCopterMega/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:991: warning: 'void print_motor_out()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_min' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:283: warning: 'heli_servo_max' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:284: warning: 'heli_servo_out' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:443: warning: 'undo_event' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:449: warning: 'condition_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:463: warning: 'simple_WP' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:468: warning: 'optflow_offset' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:469: warning: 'new_location' defined but not used +/root/apm/ardupilot-mega/ArduCopter/heli.pde:6: warning: 'rollPitch_impact_on_collective' defined but not used %% libraries/APM_BMP085/APM_BMP085.o +%% libraries/APM_PI/APM_PI.o %% libraries/APM_RC/APM_RC.o %% libraries/AP_ADC/AP_ADC_ADS7844.o %% libraries/AP_ADC/AP_ADC.o @@ -117,59 +87,50 @@ autogenerated:319: warning: 'void fake_out_gps()' declared 'static' but never de %% libraries/AP_GPS/GPS.o %% libraries/AP_IMU/AP_IMU_Oilpan.o %% libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.o -In file included from /root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: +In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:28: /usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/../SPI/SPI.h:20:1: warning: this is the location of the previous definition -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of | -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of & -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of | -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of & -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_led_always_on(bool)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:221: warning: suggest parentheses around arithmetic in operand of | +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'bool AP_OpticalFlow_ADNS3080::get_frame_rate_auto()': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:257: warning: suggest parentheses around comparison in operand of & +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'void AP_OpticalFlow_ADNS3080::set_shutter_speed_auto(bool)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:361: warning: suggest parentheses around arithmetic in operand of | +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'int AP_OpticalFlow_ADNS3080::print_pixel_data(Stream*)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:441: warning: suggest parentheses around comparison in operand of & +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:456: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'unsigned int AP_OpticalFlow_ADNS3080::set_shutter_speed(unsigned int)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:408: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp: In member function 'virtual bool AP_OpticalFlow_ADNS3080::init(bool)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp:80: warning: control reaches end of non-void function %% libraries/AP_OpticalFlow/AP_OpticalFlow.o -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i' -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': -/root/apm/Sketchbook/trunk/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function -%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: no return statement in function returning non-void +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual void AP_OpticalFlow::get_position(float, float, float, float)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:88: warning: unused variable 'i' +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual byte AP_OpticalFlow::read_register(byte)': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:44: warning: control reaches end of non-void function +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: In member function 'virtual int AP_OpticalFlow::read()': +/root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp:38: warning: control reaches end of non-void function %% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o %% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()': -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp' %% libraries/FastSerial/BetterStream.o %% libraries/FastSerial/FastSerial.o %% libraries/FastSerial/vprintf.o %% libraries/GCS_MAVLink/GCS_MAVLink.o -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions %% libraries/ModeFilter/ModeFilter.o -%% libraries/PID/PID.o %% libraries/RC_Channel/RC_Channel.o +%% libraries/memcheck/memcheck.o %% libraries/FastSerial/ftoa_engine.o %% libraries/FastSerial/ultoa_invert.o %% libraries/SPI/SPI.o @@ -244,157 +205,6 @@ In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wi from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25: /usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." %% arduino/core.a -%% ArduCopterMega.elf -%% ArduCopterMega.eep -%% ArduCopterMega.hex -make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduCopterMega' - -%%%% Making all in ArduPilotMega/ %%%% - -make[1]: Entering directory `/root/apm/Sketchbook/trunk/ArduPilotMega' -%% ArduPilotMega.cpp -%% ArduPilotMega.o -In file included from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:32: -/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined -/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:46: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions -autogenerated: At global scope: -autogenerated:63: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined -autogenerated:64: warning: 'void recalc_climb_rate()' declared 'static' but never defined -autogenerated:65: warning: 'void print_climb_debug_info()' declared 'static' but never defined -autogenerated:126: warning: 'void low_battery_event()' declared 'static' but never defined -/root/apm/Sketchbook/trunk/ArduPilotMega/ArduPilotMega.pde:334: warning: 'landing_distance' defined but not used -%% libraries/APM_BMP085/APM_BMP085.o -%% libraries/APM_RC/APM_RC.o -%% libraries/AP_ADC/AP_ADC_ADS7844.o -%% libraries/AP_ADC/AP_ADC.o -%% libraries/AP_ADC/AP_ADC_HIL.o -%% libraries/AP_Common/AP_Common.o -%% libraries/AP_Common/AP_Loop.o -%% libraries/AP_Common/AP_MetaClass.o -%% libraries/AP_Common/AP_Var.o -%% libraries/AP_Common/AP_Var_menufuncs.o -%% libraries/AP_Common/c++.o -%% libraries/AP_Common/menu.o -%% libraries/AP_Compass/AP_Compass_HIL.o -%% libraries/AP_Compass/AP_Compass_HMC5843.o -%% libraries/AP_Compass/Compass.o -%% libraries/AP_DCM/AP_DCM.o -%% libraries/AP_DCM/AP_DCM_HIL.o -%% libraries/AP_GPS/AP_GPS_406.o -%% libraries/AP_GPS/AP_GPS_Auto.o -%% libraries/AP_GPS/AP_GPS_HIL.o -%% libraries/AP_GPS/AP_GPS_IMU.o -%% libraries/AP_GPS/AP_GPS_MTK16.o -%% libraries/AP_GPS/AP_GPS_MTK.o -%% libraries/AP_GPS/AP_GPS_NMEA.o -%% libraries/AP_GPS/AP_GPS_SIRF.o -%% libraries/AP_GPS/AP_GPS_UBLOX.o -%% libraries/AP_GPS/GPS.o -%% libraries/AP_IMU/AP_IMU_Oilpan.o -%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.o -%% libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.o -%% libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.o -%% libraries/AP_RangeFinder/RangeFinder.o -%% libraries/DataFlash/DataFlash.o -In file included from /root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:35: -/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined -/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp: In member function 'void DataFlash_Class::Init()': -/root/apm/Sketchbook/trunk/libraries/DataFlash/DataFlash.cpp:59: warning: unused variable 'tmp' -%% libraries/FastSerial/BetterStream.o -%% libraries/FastSerial/FastSerial.o -%% libraries/FastSerial/vprintf.o -%% libraries/GCS_MAVLink/GCS_MAVLink.o -In file included from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h:14, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h:9, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.h:83, - from /root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/GCS_MAVLink.cpp:6: -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h: In function 'uint8_t put_bitfield_n_by_index(int32_t, uint8_t, uint8_t, uint8_t, uint8_t*, uint8_t*)': -/root/apm/Sketchbook/trunk/libraries/GCS_MAVLink/include/ardupilotmega/../protocol.h:808: warning: comparison between signed and unsigned integer expressions -%% libraries/ModeFilter/ModeFilter.o -%% libraries/PID/PID.o -%% libraries/RC_Channel/RC_Channel.o -%% libraries/FastSerial/ftoa_engine.o -%% libraries/FastSerial/ultoa_invert.o -%% libraries/SPI/SPI.o -In file included from /usr/local/share/arduino/libraries/SPI/SPI.cpp:12: -/usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined -/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -%% libraries/Wire/Wire.o -%% libraries/Wire/utility/twi.o -cc1: warning: command line option "-Wno-reorder" is valid for C++/ObjC++ but not for C -%% arduino/HardwareSerial.o -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:28: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -%% arduino/main.o -%% arduino/Print.o -%% arduino/Tone.o -/usr/local/share/arduino/hardware/arduino/cores/arduino/Tone.cpp:93: warning: only initialized variables can be placed into program memory area -%% arduino/WMath.o -%% arduino/WString.o -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:26: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:84: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:85: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:86: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:87: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:88: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:89: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:90: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:91: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:93: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:94: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:95: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:100: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:101: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:102: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:103: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:104: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:105: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:106: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:107: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:109: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:110: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:111: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:116: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:117: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:118: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:119: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:120: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:121: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:122: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:123: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:125: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:126: warning: initialization makes integer from pointer without a cast -/usr/local/share/arduino/hardware/arduino/cores/arduino/pins_arduino.c:127: warning: initialization makes integer from pointer without a cast -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/WInterrupts.c:34: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_analog.c:27: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring.c:25: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_digital.c:27: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_pulse.c:25: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -In file included from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_private.h:30, - from /usr/local/share/arduino/hardware/arduino/cores/arduino/wiring_shift.c:25: -/usr/lib/gcc/avr/4.3.5/../../../avr/include/avr/delay.h:36:2: warning: #warning "This file has been moved to ." -%% arduino/core.a -%% ArduPilotMega.elf -%% ArduPilotMega.eep -%% ArduPilotMega.hex -make[1]: Leaving directory `/root/apm/Sketchbook/trunk/ArduPilotMega' +%% ArduCopter.elf +%% ArduCopter.eep +%% ArduCopter.hex diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt index 4590ebd2e6..ae07941c39 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt @@ -1,668 +1,670 @@ -00000001 b _ZL10wp_control -00000001 b _ZL11GPS_enabled -00000001 b _ZL11home_is_set -00000001 b _ZL11motor_armed -00000001 b _ZL11motor_light -00000001 b _ZL12control_mode -00000001 b _ZL12flight_timer -00000001 d _ZL12yaw_tracking -00000001 b _ZL13land_complete -00000001 b _ZL14command_may_ID -00000001 b _ZL14wp_verify_byte -00000001 d _ZL15altitude_sensor -00000001 b _ZL15command_must_ID -00000001 b _ZL15command_yaw_dir -00000001 b _ZL16counter_one_herz -00000001 b _ZL16delta_ms_fiftyhz -00000001 b _ZL16did_ground_start -00000001 b _ZL16invalid_throttle -00000001 b _ZL16motor_auto_armed -00000001 b _ZL16old_control_mode -00000001 b _ZL16slow_loopCounter -00000001 b _ZL16takeoff_complete -00000001 b _ZL17baro_filter_index -00000001 b _ZL17command_may_index -00000001 b _ZL17oldSwitchPosition -00000001 b _ZL18command_must_index -00000001 b _ZL18delta_ms_fast_loop -00000001 d _ZL18ground_start_count -00000001 b _ZL18medium_loopCounter -00000001 b _ZL20command_yaw_relative -00000001 b _ZL20delta_ms_medium_loop -00000001 b _ZL8event_id -00000001 b _ZL8led_mode -00000001 b _ZL9GPS_light -00000001 b _ZL9loop_step -00000001 b _ZL9trim_flag -00000001 b _ZL9yaw_debug -00000001 b _ZZL13dancing_lightvE4step -00000001 b _ZZL17update_motor_ledsvE5blink -00000001 b _ZZL18radio_input_switchvE7bouncer -00000001 d _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE7mav_nav +00000001 b wp_control +00000001 b GPS_enabled +00000001 b home_is_set +00000001 b motor_armed +00000001 b motor_light +00000001 b control_mode +00000001 b simple_timer +00000001 d yaw_tracking +00000001 b land_complete +00000001 b throttle_mode +00000001 b command_may_ID +00000001 b wp_verify_byte +00000001 b xtrack_enabled +00000001 d altitude_sensor +00000001 b command_must_ID +00000001 b command_yaw_dir +00000001 b roll_pitch_mode +00000001 b counter_one_herz +00000001 b delta_ms_fiftyhz +00000001 b did_ground_start +00000001 b in_mavlink_delay +00000001 b invalid_throttle +00000001 b motor_auto_armed +00000001 b old_control_mode +00000001 b slow_loopCounter +00000001 b takeoff_complete +00000001 b command_may_index +00000001 b oldSwitchPosition +00000001 b command_must_index +00000001 b delta_ms_fast_loop +00000001 d ground_start_count +00000001 b medium_loopCounter +00000001 b command_yaw_relative +00000001 b delta_ms_medium_loop +00000001 b event_id +00000001 b led_mode +00000001 b yaw_mode +00000001 b GPS_light +00000001 b alt_timer +00000001 b loop_step +00000001 b trim_flag +00000001 b dancing_light()::step +00000001 b update_motor_leds()::blink +00000001 b radio_input_switch()::bouncer +00000001 b read_control_switch()::switch_debouncer +00000001 d GCS_MAVLINK::handleMessage(__mavlink_message*)::mav_nav 00000001 B mavdelay -00000002 T _Z19mavlink_acknowledge17mavlink_channel_thhh -00000002 b _ZL10climb_rate -00000002 b _ZL11event_delay -00000002 b _ZL11event_value -00000002 b _ZL12event_repeat -00000002 b _ZL12nav_throttle -00000002 b _ZL13gps_fix_count -00000002 b _ZL13velocity_land -00000002 b _ZL14mainLoop_count -00000002 b _ZL14waypoint_speed -00000002 b _ZL16command_yaw_time -00000002 b _ZL16event_undo_value -00000002 b _ZL16loiter_error_max -00000002 b _ZL17command_yaw_speed -00000002 b _ZL18auto_level_counter -00000002 b _ZL18ground_temperature -00000002 b _ZL20heli_manual_override -00000002 b _ZL21superslow_loopCounter -00000002 r _ZL5comma -00000002 b _ZL5g_gps -00000002 b _ZL8G_Dt_max -00000002 b _ZL8airspeed -00000002 b _ZL8baro_alt -00000002 b _ZL9sonar_alt -00000002 T _ZN11GCS_MAVLINK11acknowledgeEhhh -00000002 b _ZZL10arm_motorsvE14arming_counter -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_0 -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_1 -00000002 r _ZZL11setup_framehPKN4Menu3argEE3__c_2 -00000002 r _ZZL7test_wphPKN4Menu3argEE3__c_0 -00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c -00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_0 -00000002 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_1 +00000002 T mavlink_acknowledge(mavlink_channel_t, unsigned char, unsigned char, unsigned char) +00000002 b climb_rate +00000002 b event_delay +00000002 b event_value +00000002 b event_repeat +00000002 b nav_throttle +00000002 b altitude_rate +00000002 b gps_fix_count +00000002 b velocity_land +00000002 b mainLoop_count +00000002 b command_yaw_time +00000002 b event_undo_value +00000002 b command_yaw_speed +00000002 b auto_level_counter +00000002 b ground_temperature +00000002 b heli_manual_override +00000002 b superslow_loopCounter +00000002 r comma +00000002 b g_gps +00000002 b G_Dt_max +00000002 b airspeed +00000002 b baro_alt +00000002 b sonar_alt +00000002 T GCS_MAVLINK::acknowledge(unsigned char, unsigned char, unsigned char) +00000002 b arm_motors()::arming_counter +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r setup_frame(unsigned char, Menu::arg const*)::__c +00000002 r test_wp(unsigned char, Menu::arg const*)::__c +00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c +00000002 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c 00000002 B adc -00000003 r _ZZL10setup_gyrohPKN4Menu3argEE3__c -00000003 r _ZZL11select_logshPKN4Menu3argEE3__c_4 -00000003 r _ZZL11setup_sonarhPKN4Menu3argEE3__c -00000003 r _ZZL13print_enabledhE3__c -00000003 r _ZZL13setup_compasshPKN4Menu3argEE3__c -00000004 d _ZL10cos_roll_x -00000004 b _ZL10land_start -00000004 b _ZL10long_error -00000004 b _ZL10sin_roll_y -00000004 d _ZL11cos_pitch_x -00000004 b _ZL11event_timer -00000004 b _ZL11loiter_time -00000004 b _ZL11nav_bearing -00000004 d _ZL11scaleLongUp -00000004 b _ZL11sin_pitch_y -00000004 b _ZL11wp_distance -00000004 b _ZL12abs_pressure -00000004 b _ZL12current_amps -00000004 b _ZL12original_alt -00000004 b _ZL13bearing_error -00000004 b _ZL13current_total -00000004 b _ZL13nav_loopTimer -00000004 d _ZL13scaleLongDown -00000004 t _ZL13test_failsafehPKN4Menu3argE -00000004 b _ZL14altitude_error -00000004 b _ZL14fast_loopTimer -00000004 b _ZL14perf_mon_timer -00000004 b _ZL14target_bearing -00000004 d _ZL15battery_voltage -00000004 b _ZL15command_yaw_end -00000004 b _ZL15condition_start -00000004 b _ZL15condition_value -00000004 b _ZL15ground_pressure -00000004 b _ZL15loiter_time_max -00000004 b _ZL15target_altitude -00000004 d _ZL16battery_voltage1 -00000004 d _ZL16battery_voltage2 -00000004 d _ZL16battery_voltage3 -00000004 d _ZL16battery_voltage4 -00000004 b _ZL16crosstrack_error -00000004 b _ZL16medium_loopTimer -00000004 b _ZL16wp_totalDistance -00000004 b _ZL17command_yaw_delta -00000004 b _ZL17command_yaw_start -00000004 b _ZL17fiftyhz_loopTimer -00000004 b _ZL18crosstrack_bearing -00000004 b _ZL18fast_loopTimeStamp -00000004 b _ZL19throttle_integrator -00000004 b _ZL20saved_target_bearing -00000004 r _ZL21__menu_name__log_menu -00000004 b _ZL22command_yaw_start_time -00000004 b _ZL22initial_simple_bearing -00000004 d _ZL4G_Dt -00000004 b _ZL4load -00000004 b _ZL5dTnav -00000004 b _ZL7nav_lat -00000004 b _ZL7nav_lon -00000004 b _ZL7nav_yaw -00000004 b _ZL7old_alt -00000004 b _ZL8nav_roll -00000004 d _ZL9cos_yaw_x -00000004 b _ZL9lat_error -00000004 b _ZL9nav_pitch -00000004 b _ZL9sin_yaw_y -00000004 b _ZL9yaw_error -00000004 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_0 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_0 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_10 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_3 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_8 -00000004 r _ZZL11select_logshPKN4Menu3argEE3__c_9 -00000004 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_0 -00000004 b _ZZL13mavlink_delaymE8last_1hz -00000004 b _ZZL13mavlink_delaymE8last_3hz -00000004 b _ZZL13mavlink_delaymE9last_10hz -00000004 b _ZZL13mavlink_delaymE9last_50hz -00000004 r _ZZL13print_enabledhE3__c_0 -00000004 r _ZZL13setup_compasshPKN4Menu3argEE3__c_0 -00000004 r _ZZL14print_log_menuvE3__c_4 -00000004 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c -00000004 r _ZZL20Log_Read_PerformancevE3__c -00000004 r _ZZL8test_adchPKN4Menu3argEE3__c_0 -00000004 V _ZZN10ParametersC1EvE3__c_32 -00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c -00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_1 -00000004 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_2 -00000005 r _ZL22__menu_name__test_menu -00000005 r _ZZL10report_imuvE3__c -00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_5 -00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_6 -00000005 r _ZZL11select_logshPKN4Menu3argEE3__c_7 -00000005 r _ZZL12Log_Read_RawvE3__c -00000005 r _ZZL13Log_Read_ModevE3__c -00000005 r _ZZL14print_log_menuvE3__c_0 -00000005 r _ZZL14print_log_menuvE3__c_3 -00000005 r _ZZL14print_log_menuvE3__c_7 -00000005 r _ZZL14print_log_menuvE3__c_8 -00000005 r _ZZL8test_adchPKN4Menu3argEE3__c -00000005 V _ZZN10ParametersC1EvE3__c_35 -00000005 V _ZZN10ParametersC1EvE3__c_36 -00000005 V _ZZN10ParametersC1EvE3__c_37 -00000005 V _ZZN10ParametersC1EvE3__c_38 -00000005 V _ZZN10ParametersC1EvE3__c_49 -00000005 V _ZZN10ParametersC1EvE3__c_50 -00000005 V _ZZN10ParametersC1EvE3__c_51 -00000005 V _ZZN10ParametersC1EvE3__c_52 -00000005 V _ZZN10ParametersC1EvE3__c_53 -00000005 V _ZZN10ParametersC1EvE3__c_54 -00000005 V _ZZN10ParametersC1EvE3__c_55 -00000005 V _ZZN10ParametersC1EvE3__c_56 -00000005 V _ZZN10RC_ChannelC1EjPK11prog_char_tE3__c_0 -00000005 r _ZZN11GCS_MAVLINKC1EjE3__c -00000005 r _ZZN11GCS_MAVLINKC1EjE3__c_0 -00000005 V _ZZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKiE3__c_2 -00000006 T _Z17mavlink_send_text17mavlink_channel_thPKc -00000006 r _ZL23__menu_name__setup_menu -00000006 r _ZZL10report_gpsvE3__c -00000006 r _ZZL11report_helivE3__c -00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c -00000006 r _ZZL11test_eedumphPKN4Menu3argEE3__c_0 -00000006 r _ZZL11zero_eepromvE3__c_0 -00000006 r _ZZL13Log_Read_ModevE3__c_0 -00000006 r _ZZL14print_log_menuvE3__c_5 -00000006 r _ZZL14print_log_menuvE3__c_6 -00000006 V _ZZN10ParametersC1EvE3__c_33 -00000006 t put_float_by_index -00000006 T setup -00000007 b _ZL10setup_menu -00000007 b _ZL12planner_menu -00000007 b _ZL8log_menu -00000007 b _ZL9main_menu -00000007 b _ZL9test_menu -00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_11 -00000007 r _ZZL11select_logshPKN4Menu3argEE3__c_13 -00000007 r _ZZL12report_framevE3__c -00000007 r _ZZL12report_radiovE3__c -00000007 r _ZZL12report_sonarvE3__c -00000007 r _ZZL13print_enabledhE3__c_1 -00000007 r _ZZL7test_wphPKN4Menu3argEE3__c_2 -00000007 V _ZZN10ParametersC1EvE3__c_57 -00000007 V _ZZN10ParametersC1EvE3__c_58 -00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_6 -00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_7 -00000007 r _ZZN11GCS_MAVLINKC1EjE3__c_8 -00000008 t _ZL11setup_erasehPKN4Menu3argE -00000008 r _ZL25__menu_name__planner_menu -00000008 r _ZZL11select_logshPKN4Menu3argEE3__c_12 -00000008 r _ZZL14print_log_menuvE3__c_10 -00000008 r _ZZL19report_batt_monitorvE3__c_0 -00000008 r _ZZL19report_batt_monitorvE3__c_1 -00000008 r _ZZL7test_wphPKN4Menu3argEE3__c_1 -00000008 V _ZZN10ParametersC1EvE3__c_10 -00000008 V _ZZN10ParametersC1EvE3__c_17 -00000008 V _ZZN10ParametersC1EvE3__c_18 -00000008 V _ZZN10ParametersC1EvE3__c_67 -00000008 V _ZZN10ParametersC1EvE3__c_69 -00000008 r _ZZN11GCS_MAVLINKC1EjE3__c_3 -00000009 r _ZZL11report_gyrovE3__c_0 -00000009 r _ZZL12print_switchhhE3__c -00000009 r _ZZL14print_log_menuvE3__c_11 -00000009 r _ZZL14print_log_menuvE3__c_9 -00000009 r _ZZL14report_compassvE3__c -00000009 V _ZZN10ParametersC1EvE3__c_11 -00000009 V _ZZN10ParametersC1EvE3__c_12 -00000009 V _ZZN10ParametersC1EvE3__c_23 -00000009 V _ZZN10ParametersC1EvE3__c_24 -00000009 V _ZZN10ParametersC1EvE3__c_25 -00000009 V _ZZN10ParametersC1EvE3__c_26 -00000009 V _ZZN10ParametersC1EvE3__c_27 -00000009 V _ZZN10ParametersC1EvE3__c_28 -00000009 V _ZZN10ParametersC1EvE3__c_34 -00000009 V _ZZN10ParametersC1EvE3__c_39 -00000009 V _ZZN10ParametersC1EvE3__c_40 -00000009 V _ZZN10ParametersC1EvE3__c_41 -00000009 V _ZZN10ParametersC1EvE3__c_42 -00000009 V _ZZN10ParametersC1EvE3__c_43 -00000009 V _ZZN10ParametersC1EvE3__c_44 -00000009 V _ZZN10ParametersC1EvE3__c_45 -00000009 V _ZZN10ParametersC1EvE3__c_46 -00000009 V _ZZN10ParametersC1EvE3__c_62 -00000009 V _ZZN10ParametersC1EvE3__c_63 -00000009 V _ZZN10ParametersC1EvE3__c_64 -00000009 V _ZZN10ParametersC1EvE3__c_65 -00000009 V _ZZN10ParametersC1EvE3__c_66 -00000009 V _ZZN10ParametersC1EvE3__c_68 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_1 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_2 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_4 -00000009 r _ZZN11GCS_MAVLINKC1EjE3__c_5 -0000000a r _ZZL10test_relayhPKN4Menu3argEE3__c -0000000a r _ZZL11test_tuninghPKN4Menu3argEE3__c -0000000a r _ZZL13start_new_logvE3__c -0000000a r _ZZL14print_log_menuvE3__c_13 -0000000a r _ZZL16Log_Read_StartupvE3__c -0000000a r _ZZL7test_wphPKN4Menu3argEE3__c -0000000a r _ZZL8test_maghPKN4Menu3argEE3__c_0 -0000000a V _ZZN10ParametersC1EvE3__c_14 -0000000a V _ZZN10ParametersC1EvE3__c_29 -0000000a V _ZZN10ParametersC1EvE3__c_48 -0000000a V _ZZN10ParametersC1EvE3__c_59 -0000000a V _ZZN10ParametersC1EvE3__c_60 -0000000a V _ZZN10ParametersC1EvE3__c_61 -0000000b r _ZZL10test_relayhPKN4Menu3argEE3__c_0 -0000000b r _ZZL19report_batt_monitorvE3__c_2 -0000000b r _ZZL8set_modehE3__c -0000000b V _ZZN10ParametersC1EvE3__c_8 -0000000c t _ZL12process_logshPKN4Menu3argE -0000000c b _ZL15heli_rollFactor -0000000c b _ZL16heli_pitchFactor -0000000c b _ZL5omega -0000000c t _ZL9test_modehPKN4Menu3argE -0000000c T _ZN11GCS_MAVLINK9send_textEhPKc -0000000c V _ZTV3IMU -0000000c r _ZZL12report_framevE3__c_0 -0000000c r _ZZL9test_barohPKN4Menu3argEE3__c -0000000c V _ZZN10ParametersC1EvE3__c_2 -0000000c V _ZZN10ParametersC1EvE3__c_30 -0000000c V _ZZN10ParametersC1EvE3__c_47 -0000000c V _ZZN10ParametersC1EvE3__c_9 -0000000d r _ZZL10verify_RTLvE3__c -0000000d r _ZZL11select_logshPKN4Menu3argEE3__c_2 -0000000d r _ZZL12test_batteryhPKN4Menu3argEE3__c -0000000d r _ZZL14startup_groundvE3__c -0000000d r _ZZL7test_wphPKN4Menu3argEE3__c_3 -0000000d V _ZZN10ParametersC1EvE3__c_16 -0000000d V _ZZN10ParametersC1EvE3__c_19 -0000000d V _ZZN10ParametersC1EvE3__c_21 -0000000d V _ZZN10ParametersC1EvE3__c_3 -0000000d V _ZZN10ParametersC1EvE3__c_31 -0000000d V _ZZN10ParametersC1EvE3__c_5 -0000000d V _ZZN10ParametersC1EvE3__c_6 +00000002 B x_actual_speed +00000002 B x_rate_error +00000002 B y_actual_speed +00000002 B y_rate_error +00000003 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000003 r select_logs(unsigned char, Menu::arg const*)::__c +00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c +00000003 r print_enabled(unsigned char)::__c +00000003 r setup_compass(unsigned char, Menu::arg const*)::__c +00000004 d cos_roll_x +00000004 b land_start +00000004 b long_error +00000004 b sin_roll_y +00000004 d cos_pitch_x +00000004 b event_timer +00000004 b loiter_time +00000004 b nav_bearing +00000004 d scaleLongUp +00000004 b sin_pitch_y +00000004 b wp_distance +00000004 b abs_pressure +00000004 b circle_angle +00000004 b current_amps +00000004 b old_altitude +00000004 b original_alt +00000004 b bearing_error +00000004 b current_total +00000004 b nav_loopTimer +00000004 d scaleLongDown +00000004 t test_failsafe(unsigned char, Menu::arg const*) +00000004 b altitude_error +00000004 b fast_loopTimer +00000004 b perf_mon_timer +00000004 b target_bearing +00000004 d battery_voltage +00000004 b command_yaw_end +00000004 b condition_start +00000004 b condition_value +00000004 b ground_pressure +00000004 b loiter_time_max +00000004 b target_altitude +00000004 d battery_voltage1 +00000004 d battery_voltage2 +00000004 d battery_voltage3 +00000004 d battery_voltage4 +00000004 b medium_loopTimer +00000004 b wp_totalDistance +00000004 b command_yaw_delta +00000004 b command_yaw_start +00000004 b fiftyhz_loopTimer +00000004 b crosstrack_bearing +00000004 b fast_loopTimeStamp +00000004 b throttle_integrator +00000004 b saved_target_bearing +00000004 r __menu_name__log_menu +00000004 b command_yaw_start_time +00000004 b initial_simple_bearing +00000004 d G_Dt +00000004 b dTnav +00000004 b nav_lat +00000004 b nav_lon +00000004 b nav_yaw +00000004 b old_alt +00000004 b auto_yaw +00000004 b nav_roll +00000004 d cos_yaw_x +00000004 b lat_error +00000004 b nav_pitch +00000004 b sin_yaw_y +00000004 b yaw_error +00000004 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r select_logs(unsigned char, Menu::arg const*)::__c +00000004 r setup_sonar(unsigned char, Menu::arg const*)::__c +00000004 b mavlink_delay(unsigned long)::last_1hz +00000004 b mavlink_delay(unsigned long)::last_3hz +00000004 b mavlink_delay(unsigned long)::last_10hz +00000004 b mavlink_delay(unsigned long)::last_50hz +00000004 r print_enabled(unsigned char)::__c +00000004 r setup_compass(unsigned char, Menu::arg const*)::__c +00000004 r print_log_menu()::__c +00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c +00000004 r test_adc(unsigned char, Menu::arg const*)::__c +00000004 V Parameters::Parameters()::__c +00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000004 B tuning_value +00000005 r __menu_name__test_menu +00000005 r report_imu()::__c +00000005 r select_logs(unsigned char, Menu::arg const*)::__c +00000005 r select_logs(unsigned char, Menu::arg const*)::__c +00000005 r select_logs(unsigned char, Menu::arg const*)::__c +00000005 r Log_Read_Raw()::__c +00000005 r Log_Read_Mode()::__c +00000005 r report_tuning()::__c +00000005 r print_log_menu()::__c +00000005 r print_log_menu()::__c +00000005 r print_log_menu()::__c +00000005 r print_log_menu()::__c +00000005 r test_adc(unsigned char, Menu::arg const*)::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V Parameters::Parameters()::__c +00000005 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c +00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000005 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000005 V APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)::__c +00000006 r __menu_name__setup_menu +00000006 r report_gps()::__c +00000006 r report_heli()::__c +00000006 r test_eedump(unsigned char, Menu::arg const*)::__c +00000006 r test_eedump(unsigned char, Menu::arg const*)::__c +00000006 r zero_eeprom()::__c +00000006 r Log_Read_Mode()::__c +00000006 r print_log_menu()::__c +00000006 r print_log_menu()::__c +00000006 V Parameters::Parameters()::__c +00000007 b setup_menu +00000007 b planner_menu +00000007 b log_menu +00000007 b main_menu +00000007 b test_menu +00000007 r select_logs(unsigned char, Menu::arg const*)::__c +00000007 r select_logs(unsigned char, Menu::arg const*)::__c +00000007 r report_frame()::__c +00000007 r report_radio()::__c +00000007 r report_sonar()::__c +00000007 r print_enabled(unsigned char)::__c +00000007 r test_wp(unsigned char, Menu::arg const*)::__c +00000007 V Parameters::Parameters()::__c +00000007 V Parameters::Parameters()::__c +00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000008 t setup_erase(unsigned char, Menu::arg const*) +00000008 r __menu_name__planner_menu +00000008 r select_logs(unsigned char, Menu::arg const*)::__c +00000008 r report_tuning()::__c +00000008 r print_log_menu()::__c +00000008 r report_batt_monitor()::__c +00000008 r report_batt_monitor()::__c +00000008 r test_wp(unsigned char, Menu::arg const*)::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 V Parameters::Parameters()::__c +00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r report_gyro()::__c +00000009 r print_switch(unsigned char, unsigned char)::__c +00000009 r print_log_menu()::__c +00000009 r print_log_menu()::__c +00000009 r report_compass()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 V Parameters::Parameters()::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c +0000000a r test_relay(unsigned char, Menu::arg const*)::__c +0000000a r start_new_log()::__c +0000000a r print_log_menu()::__c +0000000a r Log_Read_Startup()::__c +0000000a r test_wp(unsigned char, Menu::arg const*)::__c +0000000a r test_mag(unsigned char, Menu::arg const*)::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a T setup +0000000b r test_relay(unsigned char, Menu::arg const*)::__c +0000000b r report_batt_monitor()::__c +0000000b V Parameters::Parameters()::__c +0000000c t process_logs(unsigned char, Menu::arg const*) +0000000c b heli_rollFactor +0000000c b heli_pitchFactor +0000000c b omega +0000000c t test_mode(unsigned char, Menu::arg const*) +0000000c T GCS_MAVLINK::send_text(unsigned char, char const*) +0000000c V vtable for IMU +0000000c r report_frame()::__c +0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c V Parameters::Parameters()::__c +0000000c V Parameters::Parameters()::__c +0000000c V Parameters::Parameters()::__c +0000000c V Parameters::Parameters()::__c +0000000d r verify_RTL()::__c +0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r test_tuning(unsigned char, Menu::arg const*)::__c +0000000d r test_battery(unsigned char, Menu::arg const*)::__c +0000000d r startup_ground()::__c +0000000d r test_wp(unsigned char, Menu::arg const*)::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter -0000000e t _GLOBAL__D_Serial -0000000e t _GLOBAL__I_Serial -0000000e V _ZTV10AP_Float16 -0000000e V _ZTV7AP_VarAIfLh6EE -0000000e V _ZTV7AP_VarSI7Matrix3IfEE -0000000e V _ZTV7AP_VarSI7Vector3IfEE -0000000e V _ZTV7AP_VarTIaE -0000000e V _ZTV7AP_VarTIfE -0000000e V _ZTV7AP_VarTIiE -0000000e r _ZZL10erase_logshPKN4Menu3argEE3__c_0 -0000000e r _ZZL10setup_helihPKN4Menu3argEE3__c -0000000e r _ZZL10setup_modehPKN4Menu3argEE3__c -0000000e r _ZZL10test_sonarhPKN4Menu3argEE3__c_0 -0000000e r _ZZL11select_logshPKN4Menu3argEE3__c_1 -0000000e r _ZZL14print_log_menuvE3__c_2 -0000000e r _ZZL18print_radio_valuesvE3__c -0000000e r _ZZL18print_radio_valuesvE3__c_0 -0000000e r _ZZL18print_radio_valuesvE3__c_1 -0000000e r _ZZL18print_radio_valuesvE3__c_2 -0000000e r _ZZL18print_radio_valuesvE3__c_3 -0000000e r _ZZL18print_radio_valuesvE3__c_4 -0000000e r _ZZL18print_radio_valuesvE3__c_5 -0000000e r _ZZL19report_batt_monitorvE3__c_3 -0000000e r _ZZL19report_flight_modesvE3__c -0000000e r _ZZL8dump_loghPKN4Menu3argEE3__c -0000000e V _ZZN10ParametersC1EvE3__c -0000000e V _ZZN10ParametersC1EvE3__c_0 -0000000e V _ZZN10ParametersC1EvE3__c_1 -0000000e V _ZZN10ParametersC1EvE3__c_13 -0000000e V _ZZN10ParametersC1EvE3__c_15 -0000000e V _ZZN10ParametersC1EvE3__c_20 -0000000e V _ZZN10ParametersC1EvE3__c_22 -0000000e V _ZZN10ParametersC1EvE3__c_4 -0000000e V _ZZN10ParametersC1EvE3__c_7 -0000000f b _ZL11current_loc -0000000f b _ZL12next_command -0000000f r _ZL22__menu_name__main_menu -0000000f b _ZL4home -0000000f b _ZL7next_WP -0000000f b _ZL7prev_WP -0000000f b _ZL9guided_WP -0000000f b _ZL9simple_WP -0000000f b _ZL9target_WP -0000000f r _ZZL11report_helivE3__c_5 -0000000f r _ZZL14print_log_menuvE3__c -0000000f r _ZZL14print_log_menuvE3__c_1 -0000000f r _ZZL14report_versionvE3__c -0000000f r _ZZL19report_batt_monitorvE3__c -0000000f r _ZZL8test_imuhPKN4Menu3argEE3__c -0000000f V _ZZN13AP_IMU_OilpanC1EP6AP_ADCjE3__c -00000010 r _ZL21planner_menu_commands -00000010 b _ZL9motor_out -00000010 W _ZNK7AP_VarTIfE13cast_to_floatEv -00000010 r _ZZL10test_sonarhPKN4Menu3argEE3__c -00000010 r _ZZL11report_gyrovE3__c -00000010 r _ZZL11report_helivE3__c_6 -00000010 r _ZZL14report_compassvE3__c_0 +0000000e t global destructors keyed to Serial +0000000e t global constructors keyed to Serial +0000000e V vtable for AP_Float16 +0000000e V vtable for AP_VarA +0000000e V vtable for AP_VarS > +0000000e V vtable for AP_VarS > +0000000e V vtable for AP_VarT +0000000e V vtable for AP_VarT +0000000e V vtable for AP_VarT +0000000e r erase_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_heli(unsigned char, Menu::arg const*)::__c +0000000e r setup_mode(unsigned char, Menu::arg const*)::__c +0000000e r test_sonar(unsigned char, Menu::arg const*)::__c +0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r print_log_menu()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r print_radio_values()::__c +0000000e r report_batt_monitor()::__c +0000000e r report_flight_modes()::__c +0000000e r dump_log(unsigned char, Menu::arg const*)::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000e V Parameters::Parameters()::__c +0000000f b current_loc +0000000f b next_command +0000000f b home +0000000f b next_WP +0000000f b prev_WP +0000000f b guided_WP +0000000f b target_WP +0000000f r report_heli()::__c +0000000f r print_log_menu()::__c +0000000f r print_log_menu()::__c +0000000f r report_version()::__c +0000000f r report_batt_monitor()::__c +0000000f r test_imu(unsigned char, Menu::arg const*)::__c +0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c +00000010 r planner_menu_commands +00000010 b motor_out +00000010 W AP_VarT::cast_to_float() const +00000010 r test_sonar(unsigned char, Menu::arg const*)::__c +00000010 r report_gyro()::__c +00000010 r report_heli()::__c +00000010 r report_compass()::__c 00000010 t mavlink_get_channel_status -00000011 r _ZZL10erase_logshPKN4Menu3argEE3__c -00000011 r _ZZL10setup_helihPKN4Menu3argEE3__c_8 -00000011 r _ZZL11zero_eepromvE3__c -00000011 r _ZZL15update_commandsvE3__c -00000011 r _ZZL17Log_Read_AttitudevE3__c +00000011 r erase_logs(unsigned char, Menu::arg const*)::__c +00000011 r setup_heli(unsigned char, Menu::arg const*)::__c +00000011 r zero_eeprom()::__c +00000011 r update_commands()::__c +00000011 r Log_Read_Attitude()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 -00000012 r _ZL19flight_mode_strings -00000012 W _ZN10AP_Float16D1Ev -00000012 W _ZN7AP_VarAIfLh6EED1Ev -00000012 W _ZN7AP_VarSI7Matrix3IfEED1Ev -00000012 W _ZN7AP_VarSI7Vector3IfEED1Ev -00000012 W _ZN7AP_VarTIaED1Ev -00000012 W _ZN7AP_VarTIfED1Ev -00000012 W _ZN7AP_VarTIiED1Ev -00000012 W _ZNK7AP_VarTIaE9serializeEPvj -00000012 r _ZZL10print_donevE3__c -00000012 r _ZZL10setup_helihPKN4Menu3argEE3__c_12 -00000012 r _ZZL11select_logshPKN4Menu3argEE3__c -00000012 r _ZZL11setup_framehPKN4Menu3argEE3__c_3 -00000012 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c -00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_13 -00000013 r _ZZL10setup_helihPKN4Menu3argEE3__c_6 -00000013 r _ZZL11report_helivE3__c_1 -00000013 r _ZZL11report_helivE3__c_2 -00000013 r _ZZL11report_helivE3__c_3 -00000013 r _ZZL11report_helivE3__c_4 -00000013 r _ZZL13setup_compasshPKN4Menu3argEE3__c_1 -00000013 r _ZZL14change_commandhE3__c -00000013 r _ZZL18setup_batt_monitorhPKN4Menu3argEE3__c_0 -00000014 W _ZN7AP_VarTIaE11unserializeEPvj -00000014 W _ZNK7AP_VarTIaE13cast_to_floatEv -00000014 W _ZNK7AP_VarTIiE13cast_to_floatEv -00000014 r _ZZL10setup_helihPKN4Menu3argEE3__c_1 -00000014 r _ZZL11setup_sonarhPKN4Menu3argEE3__c_1 -00000014 r _ZZL8test_trihPKN4Menu3argEE3__c -00000015 r _ZZL12map_baudrateamE3__c -00000015 r _ZZL14init_ardupilotvE3__c_0 -00000015 r _ZZL15Log_Read_MotorsvE3__c -00000015 r _ZZL15print_hit_entervE3__c -00000015 r _ZZN11GCS_MAVLINK13handleMessageEP17__mavlink_messageE3__c_0 -00000016 r _ZZL10setup_helihPKN4Menu3argEE3__c_0 -00000016 r _ZZL14init_ardupilotvE3__c -00000016 r _ZZN11GCS_MAVLINK6updateEvE3__c +00000012 r flight_mode_strings +00000012 W AP_Float16::~AP_Float16() +00000012 W AP_VarA::~AP_VarA() +00000012 W AP_VarS >::~AP_VarS() +00000012 W AP_VarS >::~AP_VarS() +00000012 W AP_VarT::~AP_VarT() +00000012 W AP_VarT::~AP_VarT() +00000012 W AP_VarT::~AP_VarT() +00000012 W AP_VarT::serialize(void*, unsigned int) const +00000012 r print_done()::__c +00000012 r setup_heli(unsigned char, Menu::arg const*)::__c +00000012 r select_logs(unsigned char, Menu::arg const*)::__c +00000012 r setup_frame(unsigned char, Menu::arg const*)::__c +00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c +00000013 r setup_heli(unsigned char, Menu::arg const*)::__c +00000013 r setup_heli(unsigned char, Menu::arg const*)::__c +00000013 r report_heli()::__c +00000013 r report_heli()::__c +00000013 r report_heli()::__c +00000013 r report_heli()::__c +00000013 r setup_compass(unsigned char, Menu::arg const*)::__c +00000013 r change_command(unsigned char)::__c +00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c +00000014 W AP_VarT::unserialize(void*, unsigned int) +00000014 W AP_VarT::cast_to_float() const +00000014 W AP_VarT::cast_to_float() const +00000014 r setup_heli(unsigned char, Menu::arg const*)::__c +00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c +00000014 r test_tri(unsigned char, Menu::arg const*)::__c +00000015 r map_baudrate(signed char, unsigned long)::__c +00000015 r init_ardupilot()::__c +00000015 r Log_Read_Motors()::__c +00000015 r print_hit_enter()::__c +00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c +00000016 r setup_heli(unsigned char, Menu::arg const*)::__c +00000016 r init_ardupilot()::__c +00000016 r GCS_MAVLINK::update()::__c 00000016 B sonar -00000018 b _ZL11baro_filter -00000018 t _ZL11setup_accelhPKN4Menu3argE -00000018 T _ZN11GCS_MAVLINK12send_messageEhm -00000018 W _ZNK7AP_VarTIiE9serializeEPvj -00000019 r _ZZL10setup_gyrohPKN4Menu3argEE3__c_1 -00000019 r _ZZN11GCS_MAVLINK6updateEvE3__c_0 -0000001a t _ZL10clear_ledsv -0000001a r _ZZL14print_log_menuvE3__c_12 -0000001b r _ZZL10setup_helihPKN4Menu3argEE3__c_2 -0000001b r _ZZL11report_helivE3__c_0 -0000001c W _ZN7AP_VarAIfLh6EE11unserializeEPvj -0000001c W _ZN7AP_VarSI7Matrix3IfEE11unserializeEPvj -0000001c W _ZN7AP_VarSI7Vector3IfEE11unserializeEPvj -0000001c W _ZN7AP_VarTIiE11unserializeEPvj -0000001c W _ZNK7AP_VarAIfLh6EE9serializeEPvj -0000001c W _ZNK7AP_VarSI7Matrix3IfEE9serializeEPvj -0000001c W _ZNK7AP_VarSI7Vector3IfEE9serializeEPvj -0000001c b _ZZ26mavlink_get_channel_statusE16m_mavlink_status -0000001e r _ZZL11report_helivE3__c_7 -0000001e r _ZZL16Log_Read_OptflowvE3__c -0000001f r _ZZL8test_maghPKN4Menu3argEE3__c -00000020 r _ZZL12test_currenthPKN4Menu3argEE3__c -00000021 r _ZZL10setup_helihPKN4Menu3argEE3__c_7 -00000021 r _ZZL14print_log_menuvE3__c_14 -00000021 r _ZZL14report_compassvE3__c_1 -00000021 r _ZZL16Log_Read_CurrentvE3__c -00000022 t _ZL12print_blanksi -00000022 W _ZN10AP_Float16D0Ev -00000022 W _ZN7AP_VarAIfLh6EED0Ev -00000022 W _ZN7AP_VarSI7Matrix3IfEED0Ev -00000022 W _ZN7AP_VarSI7Vector3IfEED0Ev -00000022 W _ZN7AP_VarTIaED0Ev -00000022 W _ZN7AP_VarTIfED0Ev -00000022 W _ZN7AP_VarTIiED0Ev -00000023 r _ZZL10setup_helihPKN4Menu3argEE3__c_4 -00000023 r _ZZL10setup_modehPKN4Menu3argEE3__c_1 -00000023 r _ZZL18print_gyro_offsetsvE3__c -00000024 r _ZZL10setup_helihPKN4Menu3argEE3__c_3 -00000024 r _ZZL19print_accel_offsetsvE3__c -00000025 r _ZZL13setup_factoryhPKN4Menu3argEE3__c_0 -00000026 t _ZL10print_donev -00000026 t _ZL15print_hit_enterv -00000026 t _ZL16Log_Read_Startupv -00000026 r _ZZL19Log_Read_Nav_TuningvE3__c -00000026 B barometer -00000027 r _ZZL9test_xbeehPKN4Menu3argEE3__c -00000028 t _ZL12test_batteryhPKN4Menu3argE -00000028 t _ZL14main_menu_helphPKN4Menu3argE -00000028 t _ZL8help_loghPKN4Menu3argE -00000028 W _ZN7AP_VarTIfE11unserializeEPvj -00000028 W _ZNK7AP_VarTIfE9serializeEPvj -00000028 r _ZZL12Log_Read_CmdvE3__c -00000029 r _ZZL10setup_helihPKN4Menu3argEE3__c_9 -00000029 r _ZZL10setup_modehPKN4Menu3argEE3__c_0 -00000029 r _ZZL8test_gpshPKN4Menu3argEE3__c -0000002a t _ZL11reset_nav_Iv -0000002a t _ZL17setup_declinationhPKN4Menu3argE -0000002b r _ZZL12planner_modehPKN4Menu3argEE3__c -0000002c t _ZL7freeRAMv -0000002e t _ZL12setup_motorshPKN4Menu3argE -0000002e t _ZL13print_dividerv -0000002e t _ZL9send_ratejj -0000002e W _ZN12AP_Var_groupC1EjPK11prog_char_th -0000002f r _ZZL10test_radiohPKN4Menu3argEE3__c -00000030 t _ZL12planner_modehPKN4Menu3argE -00000030 t put_int32_t_by_index -00000032 T _ZN11GCS_MAVLINK4initEP12BetterStream -00000032 r _ZZL10setup_helihPKN4Menu3argEE3__c_5 -00000034 t _ZL14heli_get_servoi -00000034 W _ZNK10AP_Float169serializeEPvj -00000035 r _ZZL14test_radio_pwmhPKN4Menu3argEE3__c -00000036 t _ZL12report_radiov -00000036 r _ZZL12Log_Read_GPSvE3__c -00000037 r _ZZL8print_wpP8LocationhE3__c -00000038 t _ZL20init_throttle_cruisev -00000038 r _ZZL11setup_radiohPKN4Menu3argEE3__c -00000038 r _ZZL13setup_factoryhPKN4Menu3argEE3__c -0000003a t _ZL10report_gpsv -0000003a t _ZL10report_imuv -0000003a t _ZL12comm_send_ch17mavlink_channel_th -0000003a W _ZN3PIDD1Ev -0000003c W _ZN10RC_ChannelD1Ev -0000003d r _ZZL23Log_Read_Control_TuningvE3__c +00000017 r __menu_name__main_menu +00000018 t setup_tune(unsigned char, Menu::arg const*) +00000018 t setup_accel(unsigned char, Menu::arg const*) +00000018 W AP_VarT::serialize(void*, unsigned int) const +00000018 b mavlink_get_channel_status::m_mavlink_status +00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000019 r GCS_MAVLINK::update()::__c +0000001a r print_log_menu()::__c +0000001b r setup_heli(unsigned char, Menu::arg const*)::__c +0000001b r report_heli()::__c +0000001c W AP_VarA::unserialize(void*, unsigned int) +0000001c W AP_VarS >::unserialize(void*, unsigned int) +0000001c W AP_VarS >::unserialize(void*, unsigned int) +0000001c W AP_VarT::unserialize(void*, unsigned int) +0000001c W AP_VarA::serialize(void*, unsigned int) const +0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001e r report_heli()::__c +0000001e r Log_Read_Optflow()::__c +0000001e r Log_Read_Nav_Tuning()::__c +0000001f r test_mag(unsigned char, Menu::arg const*)::__c +00000020 r test_current(unsigned char, Menu::arg const*)::__c +00000020 t byte_swap_4 +00000021 r setup_heli(unsigned char, Menu::arg const*)::__c +00000021 r print_log_menu()::__c +00000021 r report_compass()::__c +00000021 r Log_Read_Current()::__c +00000022 t clear_leds() +00000022 t print_blanks(int) +00000022 t reset_hold_I() +00000022 W AP_Float16::~AP_Float16() +00000022 W AP_VarA::~AP_VarA() +00000022 W AP_VarS >::~AP_VarS() +00000022 W AP_VarS >::~AP_VarS() +00000022 W AP_VarT::~AP_VarT() +00000022 W AP_VarT::~AP_VarT() +00000022 W AP_VarT::~AP_VarT() +00000023 r setup_heli(unsigned char, Menu::arg const*)::__c +00000023 r setup_mode(unsigned char, Menu::arg const*)::__c +00000023 r print_gyro_offsets()::__c +00000024 t startup_ground() +00000024 r setup_heli(unsigned char, Menu::arg const*)::__c +00000024 r init_ardupilot()::__c +00000024 r print_accel_offsets()::__c +00000025 r setup_factory(unsigned char, Menu::arg const*)::__c +00000026 t print_done() +00000026 b mavlink_queue +00000026 t print_hit_enter() +00000026 t Log_Read_Startup() +00000027 r test_xbee(unsigned char, Menu::arg const*)::__c +00000028 t test_battery(unsigned char, Menu::arg const*) +00000028 t main_menu_help(unsigned char, Menu::arg const*) +00000028 t help_log(unsigned char, Menu::arg const*) +00000028 W AP_VarT::unserialize(void*, unsigned int) +00000028 W AP_VarT::serialize(void*, unsigned int) const +00000028 r Log_Read_Cmd()::__c +00000029 r setup_heli(unsigned char, Menu::arg const*)::__c +00000029 r setup_mode(unsigned char, Menu::arg const*)::__c +00000029 r test_gps(unsigned char, Menu::arg const*)::__c +0000002a t setup_declination(unsigned char, Menu::arg const*) +0000002a r Log_Read_Control_Tuning()::__c +0000002b r planner_mode(unsigned char, Menu::arg const*)::__c +0000002e t setup_motors(unsigned char, Menu::arg const*) +0000002e t print_divider() +0000002e t send_rate(unsigned int, unsigned int) +0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) +0000002e r Log_Read_Performance()::__c +0000002f r test_radio(unsigned char, Menu::arg const*)::__c +00000030 t planner_mode(unsigned char, Menu::arg const*) +00000032 T GCS_MAVLINK::init(BetterStream*) +00000032 W APM_PI::~APM_PI() +00000032 r setup_heli(unsigned char, Menu::arg const*)::__c +00000034 t heli_get_servo(int) +00000034 W AP_Float16::serialize(void*, unsigned int) const +00000034 t _mav_put_int8_t_array +00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c +00000036 t report_radio() +00000036 r Log_Read_GPS()::__c +00000037 r print_wp(Location*, unsigned char)::__c +00000038 t init_throttle_cruise() +00000038 r setup_radio(unsigned char, Menu::arg const*)::__c +00000038 r setup_factory(unsigned char, Menu::arg const*)::__c +0000003a t report_gps() +0000003a t report_imu() +0000003c W RC_Channel::~RC_Channel() 0000003d B g_gps_driver -0000003e t _ZL10verify_RTLv -0000003e T _ZN11GCS_MAVLINK9send_textEhPK11prog_char_t -0000003e W _ZN7AP_VarTIaEC1EajPK11prog_char_th -00000040 W _ZN10AP_Float1611unserializeEPvj -00000042 T _Z10output_minv -00000042 t _ZL12report_sonarv -00000042 r _ZZL10setup_helihPKN4Menu3argEE3__c_10 -00000044 W _ZN7AP_VarTIiEC1EijPK11prog_char_th -0000004a t _ZL19read_control_switchv -0000004a W _ZN7AP_VarTIiEC1EP12AP_Var_groupjiPK11prog_char_th -0000004a t mavlink_msg_waypoint_current_send -0000004a t mavlink_update_checksum -0000004c t _ZL10setup_showhPKN4Menu3argE -0000004c t _ZL14update_nav_yawv +0000003e t verify_RTL() +0000003e T GCS_MAVLINK::send_text(unsigned char, prog_char_t const*) +0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) +00000040 W AP_Float16::unserialize(void*, unsigned int) +00000040 t byte_swap_8 +00000040 t crc_accumulate +00000042 T output_min() +00000042 t report_sonar() +00000042 r setup_heli(unsigned char, Menu::arg const*)::__c +00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) +0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) +0000004c t setup_show(unsigned char, Menu::arg const*) +0000004c t update_auto_yaw() 0000004c B imu -0000004e t mavlink_msg_waypoint_ack_send -00000050 t _ZL14report_versionv -00000050 r _ZL17log_menu_commands -00000050 r _ZL18main_menu_commands -00000050 t _ZL9read_AHRSv -00000050 T _ZN11GCS_MAVLINK15_find_parameterEj -00000050 t mavlink_msg_waypoint_request_send -00000052 t _ZL14change_commandh -00000054 t _ZL13print_enabledh -00000054 t _ZL17update_motor_ledsv -00000054 t _ZL19report_flight_modesv -00000055 r _ZZL14main_menu_helphPKN4Menu3argEE3__c -00000055 r _ZZL17setup_flightmodeshPKN4Menu3argEE3__c -00000056 t _ZL10readSwitchv -00000056 t _ZL13dancing_lightv -00000057 r _ZZL8help_loghPKN4Menu3argEE3__c -00000058 t _ZL11test_tuninghPKN4Menu3argE -00000058 t _ZL14startup_groundv -00000058 t _ZL18Log_Write_Attitudev -0000005a t _ZL12report_framev -0000005a t mavlink_msg_statustext_send -0000005c t _ZL12get_num_logsv -0000005c t _ZL9setup_eschPKN4Menu3argE -0000005e t _ZL16update_GPS_lightv -0000005e t _ZL18radio_input_switchv -0000005e T _ZN11GCS_MAVLINK17_count_parametersEv -0000005f r _ZZL10setup_helihPKN4Menu3argEE3__c_11 -00000060 t _ZL12print_switchhh -00000060 W _ZN10AP_Float16C1EP12AP_Var_groupjfPK11prog_char_th -00000064 t _ZL9test_xbeehPKN4Menu3argE -00000068 t _ZL11zero_eepromv -00000068 t _ZL18find_last_log_pagei -0000006a t _ZL20read_num_from_serialv -0000006a W _ZN11GCS_MAVLINKD1Ev -0000006c t _ZL11setup_sonarhPKN4Menu3argE -00000074 t _ZL19output_motors_armedv -00000078 t _ZL18setup_batt_monitorhPKN4Menu3argE -0000007a t _ZL13setup_factoryhPKN4Menu3argE -0000007a t _ZL18get_nav_yaw_offsetii -0000007a t _ZL9test_barohPKN4Menu3argE -0000007e t _ZL11test_rawgpshPKN4Menu3argE +0000004e T mavlink_send_text(mavlink_channel_t, unsigned char, char const*) +00000050 t report_version() +00000050 r log_menu_commands +00000050 r main_menu_commands +00000050 t read_AHRS() +00000050 T GCS_MAVLINK::_find_parameter(unsigned int) +00000052 t change_command(unsigned char) +00000054 t print_enabled(unsigned char) +00000054 t update_motor_leds() +00000054 t report_flight_modes() +00000055 r main_menu_help(unsigned char, Menu::arg const*)::__c +00000055 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000056 t readSwitch() +00000056 t dancing_light() +00000057 r help_log(unsigned char, Menu::arg const*)::__c +00000058 t Log_Write_Attitude() +0000005a t report_frame() +0000005a t read_control_switch() +0000005c t get_num_logs() +0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t update_GPS_light() +0000005e t radio_input_switch() +0000005e T GCS_MAVLINK::_count_parameters() +0000005f r setup_heli(unsigned char, Menu::arg const*)::__c +00000060 t print_switch(unsigned char, unsigned char) +00000060 t _mavlink_send_uart +00000060 B barometer +00000064 t test_xbee(unsigned char, Menu::arg const*) +00000064 t mavlink_msg_param_value_send +00000068 t zero_eeprom() +00000068 t find_last_log_page(int) +0000006a t read_num_from_serial() +0000006a W GCS_MAVLINK::~GCS_MAVLINK() +0000006c t setup_sonar(unsigned char, Menu::arg const*) +00000074 t output_motors_armed() +00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) +0000007a t setup_factory(unsigned char, Menu::arg const*) +0000007a t test_baro(unsigned char, Menu::arg const*) +0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 -00000082 t _ZL6do_RTLv -00000084 t mavlink_send_uart -00000086 t _ZL17Log_Read_Attitudev -00000088 t _ZL12Log_Read_Rawv -0000008c t _ZL11setup_framehPKN4Menu3argE -0000008c t _ZL18print_gyro_offsetsv -0000008c t _ZL19print_accel_offsetsv -00000090 t _ZL11report_gyrov -00000095 r _ZZL14init_ardupilotvE3__c_1 -00000096 t _ZL12map_baudrateam -00000096 t _ZL8print_wpP8Locationh -0000009a t _ZL12init_compassv -0000009a t _ZL14init_barometerv -0000009a t _ZL15Log_Read_Motorsv +00000082 t do_RTL() +00000086 t Log_Read_Attitude() +00000088 t Log_Read_Raw() +0000008c t setup_frame(unsigned char, Menu::arg const*) +0000008c t print_gyro_offsets() +0000008c t print_accel_offsets() +0000008e t dump_log(unsigned char, Menu::arg const*) +00000090 t report_gyro() +00000090 t report_tuning() +00000092 t test_tuning(unsigned char, Menu::arg const*) +00000095 r init_ardupilot()::__c +00000096 t map_baudrate(signed char, unsigned long) +00000096 t print_wp(Location*, unsigned char) +0000009a t init_compass() +0000009a t Log_Read_Motors() 0000009d B gcs 0000009d B hil -0000009e t _ZL10setup_modehPKN4Menu3argE -0000009e t _ZL13Log_Read_Modev -0000009e t _ZL13Log_Write_CmdhP8Location +0000009e t setup_mode(unsigned char, Menu::arg const*) +0000009e t Log_Read_Mode() +0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 -000000a6 t mavlink_msg_param_value_send -000000a8 t _ZL10test_sonarhPKN4Menu3argE -000000ac t _ZL20Log_Read_Performancev -000000ae t _ZL13auto_throttlev -000000b0 t _ZL10read_radiov -000000b0 t _ZL8dump_loghPKN4Menu3argE -000000b2 t _ZL10erase_logshPKN4Menu3argE -000000b4 t _ZL10test_relayhPKN4Menu3argE -000000b4 t _ZL11planner_gcshPKN4Menu3argE -000000b6 t _ZL18get_log_boundarieshRiS_ +000000a8 t test_sonar(unsigned char, Menu::arg const*) +000000b0 t read_radio() +000000b2 t erase_logs(unsigned char, Menu::arg const*) +000000b4 t test_relay(unsigned char, Menu::arg const*) +000000b4 t planner_gcs(unsigned char, Menu::arg const*) +000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass -000000c2 t _ZL11test_eedumphPKN4Menu3argE -000000c2 t _ZL13setup_compasshPKN4Menu3argE -000000c4 t _ZL12get_distanceP8LocationS0_ -000000c4 t _ZL13update_eventsv -000000c4 r _ZZL9setup_eschPKN4Menu3argEE3__c -000000c6 t _ZL8Log_Readii -000000c6 t _ZL8test_trihPKN4Menu3argE +000000be t Log_Read_Nav_Tuning() +000000c2 t test_eedump(unsigned char, Menu::arg const*) +000000c2 t setup_compass(unsigned char, Menu::arg const*) +000000c4 t get_distance(Location*, Location*) +000000c4 t update_events() +000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c +000000c6 t Log_Read(int, int) +000000c6 t test_tri(unsigned char, Menu::arg const*) 000000c7 B dcm -000000c8 t _ZL14read_barometerv -000000ca t _ZL12get_throttlei -000000ce W _ZN3PIDC1EjPK11prog_char_tRKfS4_S4_RKi -000000d0 t _ZL11get_bearingP8LocationS0_ -000000d8 t _ZL10test_radiohPKN4Menu3argE -000000dc t _ZL18read_baro_filteredv -000000dc t _ZL8test_adchPKN4Menu3argE -000000e4 t _ZL14test_radio_pwmhPKN4Menu3argE -000000e4 t _ZL16Log_Read_Optflowv -000000e6 t _ZL17setup_flightmodeshPKN4Menu3argE -000000e6 t _ZL19Log_Read_Nav_Tuningv -000000e6 t mavlink_finalize_message_chan -000000e8 t _ZL16Log_Read_Currentv -000000ec t put_uint64_t_by_index -000000ee t _ZL19report_batt_monitorv -000000f0 r _ZL19setup_menu_commands -000000f2 t _ZL18get_stabilize_rolll -000000f2 t _ZL19get_stabilize_pitchl -000000f6 t _ZL12Log_Read_Cmdv -000000fc T _ZN11GCS_MAVLINK12_queued_sendEv -00000108 t _ZL10setup_gyrohPKN4Menu3argE -0000010a t _ZL8test_gpshPKN4Menu3argE -0000010c W _ZN10RC_ChannelC1EjPK11prog_char_t -00000112 t _ZL12test_currenthPKN4Menu3argE -00000112 t _ZL15adjust_altitudev -00000112 T _ZN11GCS_MAVLINKC1Ej -00000112 T _ZN11GCS_MAVLINKC2Ej -00000118 t _ZL22set_command_with_index8Locationi -00000120 r _ZL18test_menu_commands -00000128 t _ZL22get_command_with_indexi -0000012c t _ZL23Log_Read_Control_Tuningv -00000130 t _ZL14report_compassv -00000144 t _ZL15calc_nav_outputv -0000014c T _ZN11GCS_MAVLINK6updateEv -00000150 t _ZL11update_trigv -00000152 t _ZL11set_next_WPP8Location -00000156 t _ZL12Log_Read_GPSv -0000015c t _ZL10arm_motorsv -00000166 t _ZL11select_logshPKN4Menu3argE -0000016c t _ZL15update_commandsv -00000170 t _ZL8test_maghPKN4Menu3argE -0000017e t _ZL17get_stabilize_yawlf -0000018e T _ZN11GCS_MAVLINK16data_stream_sendEjj -00000196 t _ZL8set_modeh -000001a0 t _ZL9init_homev -000001a8 t _ZL18print_radio_valuesv -000001ae t _ZL13mavlink_delaym -000001b8 t _ZL8test_imuhPKN4Menu3argE -000001c4 t _ZL17update_crosstrackv -000001ce t _ZL13start_new_logv -0000020c b _ZZ18mavlink_parse_charE17m_mavlink_message -0000021c t _ZL7test_wphPKN4Menu3argE -00000228 t _ZL11setup_radiohPKN4Menu3argE -00000264 t _ZL13update_nav_wpv -00000288 t _ZL13calc_rate_navi -000002b8 t _ZL15heli_init_swashv -000002d0 t _ZL11report_heliv -0000031e t _ZL12read_batteryv -00000368 t _ZL15heli_move_swashiiii -00000382 t _ZL14print_log_menuv -0000055e t mavlink_parse_char -00000628 t _ZL14init_ardupilotv -00000718 t _ZL10setup_helihPKN4Menu3argE -00000800 t _Z41__static_initialization_and_destruction_0ii -00000866 T _Z26update_current_flight_modev -000008f4 t _ZL20process_next_commandv -0000097e W _ZN10ParametersC1Ev -00000b3c b _ZL1g -00001148 T _ZN11GCS_MAVLINK13handleMessageEP17__mavlink_message -000015be T _Z20mavlink_send_message17mavlink_channel_thmj -00001aae T loop +000000ca t init_barometer() +000000d0 t get_bearing(Location*, Location*) +000000d8 t test_radio(unsigned char, Menu::arg const*) +000000d8 t read_barometer() +000000dc t test_adc(unsigned char, Menu::arg const*) +000000de t Log_Read_Performance() +000000de t Log_Read_Control_Tuning() +000000e0 b mavlink_parse_char::m_mavlink_message +000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) +000000e4 t Log_Read_Optflow() +000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&) +000000e6 t setup_flightmodes(unsigned char, Menu::arg const*) +000000e8 t Log_Read_Current() +000000ee t report_batt_monitor() +000000f4 t _mav_finalize_message_chan_send +000000f6 t Log_Read_Cmd() +000000fa t calc_nav_pitch_roll() +00000100 r setup_menu_commands +00000108 t setup_gyro(unsigned char, Menu::arg const*) +0000010a t test_gps(unsigned char, Menu::arg const*) +0000010c W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +00000112 t test_current(unsigned char, Menu::arg const*) +00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000118 t set_command_with_index(Location, int) +00000118 T GCS_MAVLINK::_queued_send() +00000120 r test_menu_commands +00000128 t get_command_with_index(int) +00000130 t report_compass() +00000134 T GCS_MAVLINK::send_message(unsigned char, unsigned long) +0000014e T GCS_MAVLINK::update() +00000150 t update_trig() +00000152 t set_next_WP(Location*) +00000156 t Log_Read_GPS() +00000166 t select_logs(unsigned char, Menu::arg const*) +0000016c t update_commands() +00000170 t test_mag(unsigned char, Menu::arg const*) +00000172 t update_nav_wp() +000001a0 t init_home() +000001a8 t print_radio_values() +000001b8 t test_imu(unsigned char, Menu::arg const*) +000001be T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +000001ca t arm_motors() +000001ca t mavlink_delay(unsigned long) +000001ce t start_new_log() +00000202 t set_mode(unsigned char) +0000021c t test_wp(unsigned char, Menu::arg const*) +00000228 t setup_radio(unsigned char, Menu::arg const*) +000002b8 t heli_init_swash() +000002d0 t report_heli() +000002ea t tuning() +00000330 t calc_nav_rate(int, int, int, int) +00000358 T update_throttle_mode() +00000368 t heli_move_swash(int, int, int, int) +00000382 t print_log_menu() +000003be t read_battery() +0000042a T update_yaw_mode() +000004b2 t mavlink_parse_char +00000556 T update_roll_pitch_mode() +00000632 t init_ardupilot() +00000718 t setup_heli(unsigned char, Menu::arg const*) +00000818 t __static_initialization_and_destruction_0(int, int) +000008e4 t process_next_command() +0000097a W Parameters::Parameters() +000009ad b g +000011d8 T GCS_MAVLINK::handleMessage(__mavlink_message*) +000017ac t mavlink_try_send_message(mavlink_channel_t, unsigned char, unsigned int) +00001af4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 14b7ec0c09..6f3cb5743d 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -58,7 +58,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex - ArduCopter 2.0.42 Beta Quad + Quad #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION X_FRAME @@ -69,7 +69,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex - ArduCopter 2.0.42 Beta Tri + Tri #define FRAME_CONFIG TRI_FRAME #define FRAME_ORIENTATION X_FRAME @@ -80,7 +80,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex - ArduCopter 2.0.42 Beta Hexa + Hexa #define FRAME_CONFIG HEXA_FRAME #define FRAME_ORIENTATION X_FRAME @@ -91,7 +91,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex - ArduCopter 2.0.42 Beta Y6 + Y6 #define FRAME_CONFIG Y6_FRAME #define FRAME_ORIENTATION X_FRAME @@ -102,7 +102,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex - ArduCopter 2.0.42 Beta Heli (2560 only) + Heli (2560 only) #define AUTO_RESET_LOITER 0 #define FRAME_CONFIG HELI_FRAME @@ -132,9 +132,8 @@ #define RATE_YAW_D 0.0 // throttle -#define THROTTLE_P 0.075 +#define THROTTLE_P 0.2 #define THROTTLE_I 0.001 -#define THROTTLE_D 0.100 #define THROTTLE_IMAX 100 // navigation @@ -149,7 +148,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex - ArduCopter 2.0.42 Beta Quad Hil + Quad Hil #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION PLUS_FRAME