diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log index 10604a699c..3e86d02fc8 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log @@ -5,13 +5,15 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /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/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)': -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch /root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()': -/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)': +/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle' /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:467: warning: 'max_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function @@ -19,7 +21,9 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function -autogenerated: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined @@ -28,36 +32,39 @@ autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but nev autogenerated:111: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/Log.pde:835: warning: 'void Log_Write_Attitude()' defined but not used autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used -autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined -autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used -autogenerated:246: warning: 'void ReadSCP1000()' declared 'static' but never defined -autogenerated:247: warning: 'void init_barometer()' declared 'static' but never defined -autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined -autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined -autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined -autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used +autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used +autogenerated:250: warning: 'void ReadSCP1000()' declared 'static' but never defined +autogenerated:251: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:252: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:253: warning: 'long int read_barometer()' declared 'static' but never defined +autogenerated:254: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:255: warning: 'void zero_airspeed()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:347: warning: 'old_altitude' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:348: warning: 'old_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'abs_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:368: warning: 'ground_temperature' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'baro_alt' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:389: warning: 'angle_boost' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt index e8146f2219..8c64ea4fd3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt @@ -10,6 +10,7 @@ 00000001 b land_complete 00000001 b throttle_mode 00000001 b command_may_ID +00000001 b mavlink_active 00000001 b wp_verify_byte 00000001 d altitude_sensor 00000001 b command_must_ID @@ -47,8 +48,10 @@ 00000002 b loiter_sum 00000002 b event_delay 00000002 b event_value +00000002 b CH7_wp_index 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle 00000002 b x_rate_error 00000002 b y_rate_error @@ -86,6 +89,7 @@ 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 +00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 d cos_roll_x 00000004 b land_start 00000004 b long_error @@ -124,6 +128,7 @@ 00000004 b fiftyhz_loopTimer 00000004 b old_target_bearing 00000004 b throttle_integrator +00000004 b heli_throttle_scaler 00000004 r __menu_name__log_menu 00000004 b command_yaw_start_time 00000004 b initial_simple_bearing @@ -284,6 +289,8 @@ 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 @@ -416,7 +423,6 @@ 00000014 r test_tri(unsigned char, Menu::arg const*)::__c 00000015 r setup_heli(unsigned char, Menu::arg const*)::__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 T piezo_beep() @@ -427,8 +433,8 @@ 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000019 r Log_Read_Motors()::__c 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001b r setup_heli(unsigned char, Menu::arg const*)::__c 0000001b r report_heli()::__c 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -437,6 +443,7 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r report_heli()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) @@ -446,10 +453,8 @@ 00000021 r print_log_menu()::__c 00000021 r report_compass()::__c 00000021 r Log_Read_Current()::__c -00000021 r Log_Read_Performance()::__c 00000022 t clear_leds() 00000022 t print_blanks(int) -00000022 t reset_hold_I() 00000022 W AP_Float16::~AP_Float16() 00000022 W AP_VarS >::~AP_VarS() 00000022 W AP_VarS >::~AP_VarS() @@ -459,13 +464,13 @@ 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 reset_hold_I() 00000024 r setup_heli(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c 00000024 r print_accel_offsets()::__c 00000026 t print_done() 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() -00000026 r Log_Read_Control_Tuning()::__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*) @@ -476,14 +481,16 @@ 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 t _mav_put_int8_t_array 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 gcs_send_text_P(gcs_severity, prog_char_t const*) 0000002e t gcs_data_stream_send(unsigned int, unsigned int) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) +0000002e r init_ardupilot()::__c +0000002e r Log_Read_Nav_Tuning()::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000030 B imu @@ -496,19 +503,17 @@ 00000034 t _MAV_RETURN_float 00000034 t heli_get_servo(int) 00000034 W AP_Float16::serialize(void*, unsigned int) const -00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000036 t report_radio() +00000036 r Log_Read_Control_Tuning()::__c 00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() 00000038 t send_current_waypoint(mavlink_channel_t) 00000038 r setup_radio(unsigned char, Menu::arg const*)::__c 00000038 r setup_factory(unsigned char, Menu::arg const*)::__c 0000003a t report_gps() 0000003a t report_imu() 0000003a B g_gps_driver -0000003c W RC_Channel::~RC_Channel() 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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) @@ -517,6 +522,7 @@ 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) +00000046 W RC_Channel::~RC_Channel() 00000048 t change_command(unsigned char) 00000048 t update_motor_leds() 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c @@ -549,9 +555,9 @@ 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) +00000068 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 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*) @@ -572,11 +578,11 @@ 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() +00000094 t init_throttle_cruise() 00000096 t print_wp(Location*, unsigned char) +00000098 B gcs0 +00000098 B gcs3 0000009a t planner_gcs(unsigned char, Menu::arg const*) -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() @@ -585,12 +591,13 @@ 000000a4 T __vector_55 000000a6 t send_servo_out(mavlink_channel_t) 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ab B compass +000000ae t Log_Read_Motors() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b4 t read_radio() 000000b6 t get_log_boundaries(unsigned char, int&, int&) +000000b6 t Log_Read_Performance() 000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) @@ -599,7 +606,6 @@ 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) -000000c6 t Log_Read_Performance() 000000c6 t test_tri(unsigned char, Menu::arg const*) 000000d0 t get_bearing(Location*, Location*) 000000d2 t print_switch(unsigned char, unsigned char, bool) @@ -607,29 +613,31 @@ 000000d4 t get_stabilize_pitch(long) 000000d4 t Log_Read(int, int) 000000d8 t test_radio(unsigned char, Menu::arg const*) +000000de t Log_Read_Nav_Tuning() 000000e0 r test_menu_commands 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&) 000000e8 t Log_Read_Current() -000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() +000000f8 t heli_get_angle_boost(int) +000000fa t calc_loiter_pitch_roll() 00000100 r setup_menu_commands +00000102 t Log_Read_Control_Tuning() 00000106 t setup_gyro(unsigned char, Menu::arg const*) 0000010a t mavlink_delay(unsigned long) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 t set_next_WP(Location*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 0000011c t get_command_with_index(int) -0000012c t calc_loiter_pitch_roll() 0000012e t arm_motors() 00000130 t report_compass() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000148 t Log_Read_GPS() 00000156 t update_commands() 0000015c t update_trig() @@ -637,38 +645,38 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) -00000168 T GCS_MAVLINK::update() 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) 00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 00000184 t test_imu(unsigned char, Menu::arg const*) 00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +000001a0 T GCS_MAVLINK::update() 000001a8 t print_radio_values() 000001cc t start_new_log() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e6 t verify_nav_wp() 000001ea t init_home() -00000216 t set_mode(unsigned char) 00000220 t test_wp(unsigned char, Menu::arg const*) +00000226 t set_mode(unsigned char) 00000228 t setup_radio(unsigned char, Menu::arg const*) 0000022a t send_gps_raw(mavlink_channel_t) 00000242 t calc_loiter(int, int) -0000030c t heli_init_swash() -00000312 W Parameters::~Parameters() +00000298 T update_throttle_mode() +00000326 W Parameters::~Parameters() 0000032a t report_heli() -00000330 t tuning() +0000033a t heli_init_swash() +0000036a t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() 0000039c t __static_initialization_and_destruction_0(int, int) +0000039e T update_roll_pitch_mode() 000003a0 t read_battery() 0000045c T update_yaw_mode() -0000046e T update_roll_pitch_mode() 0000052e t heli_move_swash(int, int, int, int) -00000622 t init_ardupilot() +00000600 t init_ardupilot() 0000071a t update_nav_wp() 000007ec t setup_heli(unsigned char, Menu::arg const*) 00000870 t process_next_command() -000009b8 W Parameters::Parameters() -00000a1f b g -0000100a T loop +00000a64 W Parameters::Parameters() +00000b2d b g +000010b6 T loop 00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log index 10604a699c..3e86d02fc8 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log @@ -5,13 +5,15 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /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/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)': -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch /root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()': -/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)': +/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle' /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:467: warning: 'max_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function @@ -19,7 +21,9 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function -autogenerated: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined @@ -28,36 +32,39 @@ autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but nev autogenerated:111: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/Log.pde:835: warning: 'void Log_Write_Attitude()' defined but not used autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used -autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined -autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used -autogenerated:246: warning: 'void ReadSCP1000()' declared 'static' but never defined -autogenerated:247: warning: 'void init_barometer()' declared 'static' but never defined -autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined -autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined -autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined -autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined +autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used +autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used +autogenerated:250: warning: 'void ReadSCP1000()' declared 'static' but never defined +autogenerated:251: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:252: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:253: warning: 'long int read_barometer()' declared 'static' but never defined +autogenerated:254: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:255: warning: 'void zero_airspeed()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used -/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:347: warning: 'old_altitude' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:348: warning: 'old_rate' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'abs_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:368: warning: 'ground_temperature' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'baro_alt' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:389: warning: 'angle_boost' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt index c3ae322200..d90c94c76f 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt @@ -10,6 +10,7 @@ 00000001 b land_complete 00000001 b throttle_mode 00000001 b command_may_ID +00000001 b mavlink_active 00000001 b wp_verify_byte 00000001 d altitude_sensor 00000001 b command_must_ID @@ -47,8 +48,10 @@ 00000002 b loiter_sum 00000002 b event_delay 00000002 b event_value +00000002 b CH7_wp_index 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle 00000002 b x_rate_error 00000002 b y_rate_error @@ -86,6 +89,7 @@ 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 +00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 d cos_roll_x 00000004 b land_start 00000004 b long_error @@ -124,6 +128,7 @@ 00000004 b fiftyhz_loopTimer 00000004 b old_target_bearing 00000004 b throttle_integrator +00000004 b heli_throttle_scaler 00000004 r __menu_name__log_menu 00000004 b command_yaw_start_time 00000004 b initial_simple_bearing @@ -284,6 +289,8 @@ 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 @@ -416,7 +423,6 @@ 00000014 r test_tri(unsigned char, Menu::arg const*)::__c 00000015 r setup_heli(unsigned char, Menu::arg const*)::__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 T piezo_beep() @@ -427,8 +433,8 @@ 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000019 r Log_Read_Motors()::__c 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001b r setup_heli(unsigned char, Menu::arg const*)::__c 0000001b r report_heli()::__c 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -437,6 +443,7 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r report_heli()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) @@ -446,10 +453,8 @@ 00000021 r print_log_menu()::__c 00000021 r report_compass()::__c 00000021 r Log_Read_Current()::__c -00000021 r Log_Read_Performance()::__c 00000022 t clear_leds() 00000022 t print_blanks(int) -00000022 t reset_hold_I() 00000022 W AP_Float16::~AP_Float16() 00000022 W AP_VarS >::~AP_VarS() 00000022 W AP_VarS >::~AP_VarS() @@ -459,13 +464,13 @@ 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 reset_hold_I() 00000024 r setup_heli(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c 00000024 r print_accel_offsets()::__c 00000026 t print_done() 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() -00000026 r Log_Read_Control_Tuning()::__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*) @@ -476,14 +481,16 @@ 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 t _mav_put_int8_t_array 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 gcs_send_text_P(gcs_severity, prog_char_t const*) 0000002e t gcs_data_stream_send(unsigned int, unsigned int) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) +0000002e r init_ardupilot()::__c +0000002e r Log_Read_Nav_Tuning()::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000030 B imu @@ -496,19 +503,17 @@ 00000034 t _MAV_RETURN_float 00000034 t heli_get_servo(int) 00000034 W AP_Float16::serialize(void*, unsigned int) const -00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000036 t report_radio() +00000036 r Log_Read_Control_Tuning()::__c 00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() 00000038 t send_current_waypoint(mavlink_channel_t) 00000038 r setup_radio(unsigned char, Menu::arg const*)::__c 00000038 r setup_factory(unsigned char, Menu::arg const*)::__c 0000003a t report_gps() 0000003a t report_imu() 0000003a B g_gps_driver -0000003c W RC_Channel::~RC_Channel() 0000003e T GCS_MAVLINK::send_text(gcs_severity, 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) @@ -517,6 +522,7 @@ 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) +00000046 W RC_Channel::~RC_Channel() 00000048 t change_command(unsigned char) 00000048 t update_motor_leds() 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c @@ -549,9 +555,9 @@ 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) +00000068 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 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*) @@ -572,11 +578,11 @@ 00000090 t report_tuning() 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() +00000094 t init_throttle_cruise() 00000096 t print_wp(Location*, unsigned char) +00000098 B gcs0 +00000098 B gcs3 0000009a t planner_gcs(unsigned char, Menu::arg const*) -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() 0000009e t Log_Write_Cmd(unsigned char, Location*) @@ -585,12 +591,13 @@ 000000a4 T __vector_55 000000a6 t send_servo_out(mavlink_channel_t) 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ab B compass +000000ae t Log_Read_Motors() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b4 t read_radio() 000000b6 t get_log_boundaries(unsigned char, int&, int&) +000000b6 t Log_Read_Performance() 000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) @@ -599,7 +606,6 @@ 000000c4 t get_distance(Location*, Location*) 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) -000000c6 t Log_Read_Performance() 000000c6 t test_tri(unsigned char, Menu::arg const*) 000000d0 t get_bearing(Location*, Location*) 000000d0 t print_switch(unsigned char, unsigned char, bool) @@ -607,29 +613,31 @@ 000000d4 t get_stabilize_pitch(long) 000000d4 t Log_Read(int, int) 000000d8 t test_radio(unsigned char, Menu::arg const*) +000000de t Log_Read_Nav_Tuning() 000000e0 r test_menu_commands 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&) 000000e8 t Log_Read_Current() -000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() +000000f8 t heli_get_angle_boost(int) +000000fa t calc_loiter_pitch_roll() 00000100 r setup_menu_commands +00000102 t Log_Read_Control_Tuning() 00000108 t setup_gyro(unsigned char, Menu::arg const*) 0000010a t mavlink_delay(unsigned long) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 t set_next_WP(Location*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 0000011c t get_command_with_index(int) -0000012c t calc_loiter_pitch_roll() 0000012e t arm_motors() 00000130 t report_compass() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000148 t Log_Read_GPS() 00000156 t update_commands() 0000015c t update_trig() @@ -637,38 +645,38 @@ 00000160 t send_nav_controller_output(mavlink_channel_t) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) -00000168 T GCS_MAVLINK::update() 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) 00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 00000184 t test_imu(unsigned char, Menu::arg const*) 00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +000001a0 T GCS_MAVLINK::update() 000001a8 t print_radio_values() 000001cc t start_new_log() 000001e4 t verify_nav_wp() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000216 t set_mode(unsigned char) 0000021c t test_wp(unsigned char, Menu::arg const*) +00000226 t set_mode(unsigned char) 00000228 t setup_radio(unsigned char, Menu::arg const*) 0000022a t send_gps_raw(mavlink_channel_t) 00000242 t calc_loiter(int, int) -0000030c t heli_init_swash() -00000312 W Parameters::~Parameters() +00000298 T update_throttle_mode() +00000326 W Parameters::~Parameters() 00000328 t report_heli() -00000330 t tuning() +0000033a t heli_init_swash() +0000036a t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() 0000039c t __static_initialization_and_destruction_0(int, int) +0000039e T update_roll_pitch_mode() 000003a0 t read_battery() 0000045c T update_yaw_mode() -0000046e T update_roll_pitch_mode() 0000052e t heli_move_swash(int, int, int, int) -00000620 t init_ardupilot() +000005fe t init_ardupilot() 0000071a t update_nav_wp() 000007e8 t setup_heli(unsigned char, Menu::arg const*) 00000870 t process_next_command() -000009b8 W Parameters::Parameters() -00000a1f b g -0000100a T loop +00000a64 W Parameters::Parameters() +00000b2d b g +000010b6 T loop 00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log index d420f23d8f..e2ae2c5243 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log @@ -5,17 +5,21 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /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/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()': -/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)': +/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle' /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:467: warning: 'min_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function -autogenerated: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined @@ -23,24 +27,25 @@ autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but ne /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used -autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined -autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used +autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used +autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:252: 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:438: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt index 41607607b2..4f8bcc3fd3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt @@ -10,6 +10,7 @@ 00000001 b land_complete 00000001 b throttle_mode 00000001 b command_may_ID +00000001 b mavlink_active 00000001 b wp_verify_byte 00000001 d altitude_sensor 00000001 b command_must_ID @@ -45,10 +46,13 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value +00000002 b CH7_wp_index 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle 00000002 b x_rate_error 00000002 b y_rate_error @@ -71,6 +75,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b old_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -85,6 +90,7 @@ 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 +00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 d cos_roll_x 00000004 b land_start 00000004 b long_error @@ -125,6 +131,7 @@ 00000004 b fiftyhz_loopTimer 00000004 b old_target_bearing 00000004 b throttle_integrator +00000004 b heli_throttle_scaler 00000004 r __menu_name__log_menu 00000004 b command_yaw_start_time 00000004 b initial_simple_bearing @@ -287,6 +294,8 @@ 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 @@ -418,7 +427,6 @@ 00000014 r test_tri(unsigned char, Menu::arg const*)::__c 00000015 r setup_heli(unsigned char, Menu::arg const*)::__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 T piezo_beep() @@ -429,8 +437,8 @@ 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000019 r Log_Read_Motors()::__c 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001b r setup_heli(unsigned char, Menu::arg const*)::__c 0000001b r report_heli()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) @@ -441,6 +449,7 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r report_heli()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) @@ -450,10 +459,8 @@ 00000021 r print_log_menu()::__c 00000021 r report_compass()::__c 00000021 r Log_Read_Current()::__c -00000021 r Log_Read_Performance()::__c 00000022 t clear_leds() 00000022 t print_blanks(int) -00000022 t reset_hold_I() 00000022 t startup_ground() 00000022 W AP_Float16::~AP_Float16() 00000022 W AP_VarA::~AP_VarA() @@ -465,13 +472,13 @@ 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 reset_hold_I() 00000024 r setup_heli(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c 00000024 r print_accel_offsets()::__c 00000026 t print_done() 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() -00000026 r Log_Read_Control_Tuning()::__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*) @@ -482,14 +489,16 @@ 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 t _mav_put_int8_t_array 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 gcs_send_text_P(gcs_severity, prog_char_t const*) 0000002e t gcs_data_stream_send(unsigned int, unsigned int) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) +0000002e r init_ardupilot()::__c +0000002e r Log_Read_Nav_Tuning()::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000031 r setup_heli(unsigned char, Menu::arg const*)::__c @@ -500,18 +509,16 @@ 00000033 b pending_status 00000034 t heli_get_servo(int) 00000034 W AP_Float16::serialize(void*, unsigned int) const -00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000036 t report_radio() +00000036 r Log_Read_Control_Tuning()::__c 00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() 00000038 t send_current_waypoint(mavlink_channel_t) 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 GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*) 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) @@ -523,6 +530,7 @@ 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) +00000046 W RC_Channel::~RC_Channel() 00000048 t change_command(unsigned char) 00000048 t update_motor_leds() 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c @@ -553,9 +561,9 @@ 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) +00000068 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 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*) @@ -579,12 +587,12 @@ 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() +00000094 t init_throttle_cruise() 00000096 t print_wp(Location*, unsigned char) +00000098 B gcs0 +00000098 B gcs3 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() @@ -593,11 +601,12 @@ 000000a4 T __vector_55 000000a6 t send_servo_out(mavlink_channel_t) 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() +000000ae t Log_Read_Motors() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b4 t read_radio() 000000b6 t get_log_boundaries(unsigned char, int&, int&) +000000b6 t Log_Read_Performance() 000000b7 B compass 000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) @@ -607,7 +616,6 @@ 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t send_radio_in(mavlink_channel_t) -000000c6 t Log_Read_Performance() 000000c6 t test_tri(unsigned char, Menu::arg const*) 000000c7 B dcm 000000ca t init_barometer() @@ -618,30 +626,32 @@ 000000d4 t Log_Read(int, int) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() +000000de t Log_Read_Nav_Tuning() 000000de t test_adc(unsigned char, Menu::arg const*) 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&) 000000e8 t Log_Read_Current() -000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() +000000f8 t heli_get_angle_boost(int) +000000fa t calc_loiter_pitch_roll() 00000100 r test_menu_commands 00000100 r setup_menu_commands +00000102 t Log_Read_Control_Tuning() 00000106 t setup_gyro(unsigned char, Menu::arg const*) 0000010a t mavlink_delay(unsigned long) 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 t set_next_WP(Location*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 0000011c t get_command_with_index(int) -0000012c t calc_loiter_pitch_roll() 00000130 t report_compass() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000148 t Log_Read_GPS() 00000156 t update_commands() 0000015c t update_trig() @@ -650,10 +660,10 @@ 00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) -00000168 T GCS_MAVLINK::update() 0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +000001a0 T GCS_MAVLINK::update() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() 000001be t arm_motors() @@ -661,29 +671,29 @@ 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001e6 t verify_nav_wp() 000001ea t init_home() -00000216 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 00000220 t test_wp(unsigned char, Menu::arg const*) +00000226 t set_mode(unsigned char) 00000228 t setup_radio(unsigned char, Menu::arg const*) 0000022a t send_gps_raw(mavlink_channel_t) 00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -0000030c t heli_init_swash() -00000312 W Parameters::~Parameters() +00000298 T update_throttle_mode() +00000326 W Parameters::~Parameters() 0000032a t report_heli() -00000330 t tuning() +0000033a t heli_init_swash() +0000036a t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() +0000039e T update_roll_pitch_mode() 000003a0 t read_battery() 0000045c T update_yaw_mode() -0000046e T update_roll_pitch_mode() 0000053e t heli_move_swash(int, int, int, int) 000005cc t __static_initialization_and_destruction_0(int, int) -00000620 t init_ardupilot() +000005fe t init_ardupilot() 0000071a t update_nav_wp() 000007ec t setup_heli(unsigned char, Menu::arg const*) 00000870 t process_next_command() -000009b8 W Parameters::Parameters() -00000a1f b g +00000a64 W Parameters::Parameters() +00000b2d b g 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001598 T loop +000016c8 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log index d420f23d8f..e2ae2c5243 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log @@ -5,17 +5,21 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /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/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()': -/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion +/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion /root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()': -/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning +/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)': +/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle' /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:467: warning: 'min_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function -autogenerated: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined @@ -23,24 +27,25 @@ autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but ne /root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used /root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used /root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used -autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used -autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined -autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined -autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined -autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used +autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used +autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined +autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used -autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined +autogenerated:252: 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:438: warning: 'void set_failsafe(boolean)' defined but not used -autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined -autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined +autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used -/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt index 0f00a831cc..5f1c4d5346 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt @@ -10,6 +10,7 @@ 00000001 b land_complete 00000001 b throttle_mode 00000001 b command_may_ID +00000001 b mavlink_active 00000001 b wp_verify_byte 00000001 d altitude_sensor 00000001 b command_must_ID @@ -45,10 +46,13 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value +00000002 b CH7_wp_index 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle 00000002 b x_rate_error 00000002 b y_rate_error @@ -71,6 +75,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b old_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -85,6 +90,7 @@ 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 +00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 d cos_roll_x 00000004 b land_start 00000004 b long_error @@ -125,6 +131,7 @@ 00000004 b fiftyhz_loopTimer 00000004 b old_target_bearing 00000004 b throttle_integrator +00000004 b heli_throttle_scaler 00000004 r __menu_name__log_menu 00000004 b command_yaw_start_time 00000004 b initial_simple_bearing @@ -287,6 +294,8 @@ 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 @@ -418,7 +427,6 @@ 00000014 r test_tri(unsigned char, Menu::arg const*)::__c 00000015 r setup_heli(unsigned char, Menu::arg const*)::__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 T piezo_beep() @@ -429,8 +437,8 @@ 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c +00000019 r Log_Read_Motors()::__c 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001b r setup_heli(unsigned char, Menu::arg const*)::__c 0000001b r report_heli()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) @@ -441,6 +449,7 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r report_heli()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) @@ -450,10 +459,8 @@ 00000021 r print_log_menu()::__c 00000021 r report_compass()::__c 00000021 r Log_Read_Current()::__c -00000021 r Log_Read_Performance()::__c 00000022 t clear_leds() 00000022 t print_blanks(int) -00000022 t reset_hold_I() 00000022 t startup_ground() 00000022 W AP_Float16::~AP_Float16() 00000022 W AP_VarA::~AP_VarA() @@ -465,13 +472,13 @@ 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 reset_hold_I() 00000024 r setup_heli(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c 00000024 r print_accel_offsets()::__c 00000026 t print_done() 00000026 t print_hit_enter() 00000026 t Log_Read_Startup() -00000026 r Log_Read_Control_Tuning()::__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*) @@ -482,14 +489,16 @@ 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 t _mav_put_int8_t_array 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 gcs_send_text_P(gcs_severity, prog_char_t const*) 0000002e t gcs_data_stream_send(unsigned int, unsigned int) 0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char) +0000002e r init_ardupilot()::__c +0000002e r Log_Read_Nav_Tuning()::__c 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000031 r setup_heli(unsigned char, Menu::arg const*)::__c @@ -500,18 +509,16 @@ 00000033 b pending_status 00000034 t heli_get_servo(int) 00000034 W AP_Float16::serialize(void*, unsigned int) const -00000034 t _mav_put_int8_t_array 00000034 t mavlink_msg_statustext_send 00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c 00000036 t report_radio() +00000036 r Log_Read_Control_Tuning()::__c 00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() 00000038 t send_current_waypoint(mavlink_channel_t) 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 GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*) 0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char) @@ -523,6 +530,7 @@ 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) +00000046 W RC_Channel::~RC_Channel() 00000048 t change_command(unsigned char) 00000048 t update_motor_leds() 00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c @@ -553,9 +561,9 @@ 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) +00000068 W GCS_MAVLINK::~GCS_MAVLINK() 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 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*) @@ -579,12 +587,12 @@ 00000090 t report_tuning() 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() +00000094 t init_throttle_cruise() 00000096 t print_wp(Location*, unsigned char) +00000098 B gcs0 +00000098 B gcs3 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() 0000009e t Log_Write_Cmd(unsigned char, Location*) @@ -593,11 +601,12 @@ 000000a4 T __vector_55 000000a6 t send_servo_out(mavlink_channel_t) 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() +000000ae t Log_Read_Motors() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b4 t read_radio() 000000b6 t get_log_boundaries(unsigned char, int&, int&) +000000b6 t Log_Read_Performance() 000000b7 B compass 000000be t update_events() 000000c2 t test_eedump(unsigned char, Menu::arg const*) @@ -607,7 +616,6 @@ 000000c4 t get_distance(Location*, Location*) 000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c 000000c6 t send_radio_in(mavlink_channel_t) -000000c6 t Log_Read_Performance() 000000c6 t test_tri(unsigned char, Menu::arg const*) 000000c7 B dcm 000000ca t init_barometer() @@ -619,29 +627,31 @@ 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_Nav_Tuning() 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&) 000000e8 t Log_Read_Current() -000000ea t Log_Read_Control_Tuning() 000000ee t report_batt_monitor() 000000f6 t Log_Read_Cmd() +000000f8 t heli_get_angle_boost(int) +000000fa t calc_loiter_pitch_roll() 00000100 r test_menu_commands 00000100 r setup_menu_commands +00000102 t Log_Read_Control_Tuning() 00000108 t setup_gyro(unsigned char, Menu::arg const*) 0000010a t mavlink_delay(unsigned long) 0000010a t send_raw_imu2(mavlink_channel_t) 0000010a t test_gps(unsigned char, Menu::arg const*) 0000010c t test_current(unsigned char, Menu::arg const*) -0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) +00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 t set_next_WP(Location*) 00000112 t send_extended_status1(mavlink_channel_t, unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) -00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000118 t set_command_with_index(Location, int) 0000011c t get_command_with_index(int) -0000012c t calc_loiter_pitch_roll() 00000130 t report_compass() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) 00000148 t Log_Read_GPS() 00000156 t update_commands() 0000015c t update_trig() @@ -650,10 +660,10 @@ 00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000166 t select_logs(unsigned char, Menu::arg const*) 00000166 t send_vfr_hud(mavlink_channel_t) -00000168 T GCS_MAVLINK::update() 0000016c t test_imu(unsigned char, Menu::arg const*) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +000001a0 T GCS_MAVLINK::update() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() 000001be t arm_motors() @@ -661,29 +671,29 @@ 000001e4 t verify_nav_wp() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) 000001ea t init_home() -00000216 t set_mode(unsigned char) 0000021a t send_raw_imu1(mavlink_channel_t) 0000021c t test_wp(unsigned char, Menu::arg const*) +00000226 t set_mode(unsigned char) 00000228 t setup_radio(unsigned char, Menu::arg const*) 0000022a t send_gps_raw(mavlink_channel_t) 00000242 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -0000030c t heli_init_swash() -00000312 W Parameters::~Parameters() +00000298 T update_throttle_mode() +00000326 W Parameters::~Parameters() 00000328 t report_heli() -00000330 t tuning() +0000033a t heli_init_swash() +0000036a t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() +0000039e T update_roll_pitch_mode() 000003a0 t read_battery() 0000045c T update_yaw_mode() -0000046e T update_roll_pitch_mode() 0000053e t heli_move_swash(int, int, int, int) 000005cc t __static_initialization_and_destruction_0(int, int) -0000061e t init_ardupilot() +000005fc t init_ardupilot() 0000071a t update_nav_wp() 000007e8 t setup_heli(unsigned char, Menu::arg const*) 00000870 t process_next_command() -000009b8 W Parameters::Parameters() -00000a1f b g +00000a64 W Parameters::Parameters() +00000b2d b g 000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001598 T loop +000016c8 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index c2dccc3239..e338f2b167 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -95,7 +95,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 V2.0.49 Beta Heli (2560 only) + ArduCopter V2.0.50 Beta Heli (2560 only) #define AUTO_RESET_LOITER 0 #define FRAME_CONFIG HELI_FRAME @@ -137,7 +137,7 @@ #define NAV_LOITER_IMAX 10 - 111 + 112 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex @@ -157,7 +157,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex - ArduCopter V2.0.49 Beta Heli Hil + ArduCopter V2.0.50 Beta Heli Hil #define HIL_MODE HIL_MODE_ATTITUDE @@ -203,6 +203,6 @@ - 111 + 112 diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index 04b288c7e4..ca7ab87b26 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1,36 +1,545 @@ From https://code.google.com/p/ardupilot-mega - 8a21477..b0bfa54 APM_Camera -> origin/APM_Camera - 6f44fff..076459c master -> origin/master -Updating 6f44fff..076459c + b0bfa54..8d3fb35 APM_Camera -> origin/APM_Camera + cd1bcd6..34c9a18 master -> origin/master +Updating cd1bcd6..34c9a18 Fast-forward - ArduCopter/control_modes.pde | 16 + + .gitignore | 4 +- + ArduBoat/ArduBoat.cpp | 7 +- + ArduBoat/ArduBoat.pde | 2 +- + ArduBoat/BoatGeneric.h | 39 +- + ArduBoat/ControllerBoat.h | 157 +- + ArduCopter/APM_Config.h | 7 +- + ArduCopter/ArduCopter.pde | 64 +- + ArduCopter/Attitude.pde | 54 +- + ArduCopter/CMakeLists.txt | 165 - + ArduCopter/GCS.h | 7 +- + ArduCopter/GCS_Mavlink.pde | 23 +- + ArduCopter/Log.pde | 261 +- + ArduCopter/Parameters.h | 12 +- + ArduCopter/config.h | 45 +- + ArduCopter/control_modes.pde | 8 +- ArduCopter/defines.h | 1 + - ArduCopter/system.pde | 4 + - ArduPlane/ArduPlane.pde | 10 +- - ArduPlane/Parameters.h | 3 + - ArduPlane/config.h | 8 + - Tools/ArduTracker/tags |148411 -------------------- - Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 2 + - Tools/ArdupilotMegaPlanner/Log.cs | 174 +- - Tools/ArdupilotMegaPlanner/MainV2.cs | 9 +- + ArduCopter/heli.pde | 25 + + ArduCopter/motors.pde | 4 +- + ArduCopter/navigation.pde | 42 +- + ArduCopter/radio.pde | 14 +- + ArduCopter/system.pde | 36 +- + ArduPlane/.gitignore | 1 - + ArduPlane/ArduPlane.pde | 27 +- + ArduPlane/CMakeLists.txt | 168 - + ArduPlane/GCS.h | 7 +- + ArduPlane/GCS_Mavlink.pde | 464 +++- + ArduPlane/Log.pde | 10 +- + ArduPlane/Mavlink_compat.h | 172 + + ArduPlane/Parameters.h | 12 +- + ArduPlane/commands.pde | 65 +- + ArduPlane/commands_logic.pde | 152 +- + ArduPlane/commands_process.pde | 183 +- + ArduPlane/config.h | 5 + + ArduPlane/defines.h | 3 +- + ArduPlane/navigation.pde | 2 +- + ArduPlane/system.pde | 21 +- + ArduPlane/test.pde | 6 +- + ArduRover/ArduRover.cpp | 6 +- + ArduRover/ArduRover.pde | 1 + + ArduRover/CarStampede.h | 31 +- + ArduRover/ControllerCar.h | 158 +- + ArduRover/ControllerTank.h | 176 +- + ArduRover/TankGeneric.h | 16 +- + CMakeLists.txt | 9 +- + Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 9 + + Tools/ArdupilotMegaPlanner/Camera.Designer.cs | 421 +++ + Tools/ArdupilotMegaPlanner/Camera.cs | 139 + + Tools/ArdupilotMegaPlanner/Camera.resx | 120 + + Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 12 +- + Tools/ArdupilotMegaPlanner/CurrentState.cs | 81 +- + .../GCSViews/Configuration.Designer.cs | 137 +- + .../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 47 +- + .../GCSViews/Configuration.resx | 2088 +++++------- + Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 12 +- + .../GCSViews/FlightData.Designer.cs | 155 +- + Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 164 +- + .../ArdupilotMegaPlanner/GCSViews/FlightData.resx | 604 ++-- + .../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 4 +- + Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 18 +- + Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 7 + + Tools/ArdupilotMegaPlanner/Joystick.cs | 50 +- + .../ArdupilotMegaPlanner/JoystickSetup.Designer.cs | 276 ++- + Tools/ArdupilotMegaPlanner/JoystickSetup.cs | 125 +- + Tools/ArdupilotMegaPlanner/JoystickSetup.resx | 763 ++++- + Tools/ArdupilotMegaPlanner/MAVLink.cs | 11 +- + Tools/ArdupilotMegaPlanner/MainV2.cs | 87 +- + Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 9 +- + Tools/ArdupilotMegaPlanner/Program.cs | 1 + .../Properties/AssemblyInfo.cs | 2 +- + Tools/ArdupilotMegaPlanner/SerialOutput.cs | 13 +- + Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 4 +- + Tools/ArdupilotMegaPlanner/Updater/Updater.csproj | 2 +- .../bin/Release/ArdupilotMegaPlanner.application | 2 +- - .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2194944 bytes + .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194944 -> 2188288 bytes + .../bin/Release/GCSViews/Configuration.resx | 2088 +++++------- + .../bin/Release/GCSViews/FlightData.resx | 604 ++-- + .../bin/Release/JoystickSetup.resx | 763 ++++- Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes .../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes .../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes - apo/ControllerQuad.h | 51 +- - apo/QuadArducopter.h | 10 +- - libraries/APO/AP_ArmingMechanism.cpp | 57 + - libraries/APO/AP_ArmingMechanism.h | 67 + - libraries/APO/AP_BatteryMonitor.cpp | 2 + - libraries/APO/AP_BatteryMonitor.h | 58 +- - libraries/APO/AP_Guide.h | 1 + - libraries/APO/AP_HardwareAbstractionLayer.h | 13 + - libraries/APO/AP_Navigator.cpp | 20 +- - libraries/Desktop/support/FastSerial.cpp | 283 +- - 27 files changed, 517 insertions(+), 148687 deletions(-) - delete mode 100644 Tools/ArduTracker/tags - create mode 100644 libraries/APO/AP_ArmingMechanism.cpp - create mode 100644 libraries/APO/AP_ArmingMechanism.h + Tools/scripts/format.sh | 13 + + apo/ControllerPlane.h | 329 +- + apo/ControllerQuad.h | 414 +-- + apo/PlaneEasystar.h | 18 +- + apo/QuadArducopter.h | 17 +- + apo/apo.pde | 5 +- + libraries/APM_BMP085/APM_BMP085.h | 2 +- + libraries/APM_PI/APM_PI.cpp | 8 +- + libraries/APO/APO.h | 6 +- + libraries/APO/APO_DefaultSetup.h | 321 +- + libraries/APO/AP_ArmingMechanism.cpp | 14 +- + libraries/APO/AP_ArmingMechanism.h | 10 +- + libraries/APO/AP_Autopilot.cpp | 461 ++-- + libraries/APO/AP_Autopilot.h | 195 +- + libraries/APO/AP_BatteryMonitor.h | 1 - + libraries/APO/AP_CommLink.cpp | 1280 ++++---- + libraries/APO/AP_CommLink.h | 126 +- + libraries/APO/AP_Controller.cpp | 111 +- + libraries/APO/AP_Controller.h | 402 ++- + libraries/APO/AP_Guide.cpp | 429 ++- + libraries/APO/AP_Guide.h | 203 +- + libraries/APO/AP_HardwareAbstractionLayer.cpp | 1 + + libraries/APO/AP_HardwareAbstractionLayer.h | 258 +- + libraries/APO/AP_MavlinkCommand.cpp | 304 +- + libraries/APO/AP_MavlinkCommand.h | 654 ++-- + libraries/APO/AP_Navigator.cpp | 298 +- + libraries/APO/AP_Navigator.h | 358 +- + libraries/APO/AP_RcChannel.cpp | 125 +- + libraries/APO/AP_RcChannel.h | 103 +- + libraries/APO/AP_Var_keys.h | 21 +- + libraries/APO/constants.h | 1 + + libraries/APO/examples/MavlinkTest/MavlinkTest.pde | 64 +- + libraries/APO/examples/ServoManual/ServoManual.pde | 144 +- + libraries/APO/examples/ServoSweep/ServoSweep.pde | 184 +- + libraries/AP_Common/AP_Common.h | 20 +- + libraries/AP_Common/AP_Test.h | 4 +- + libraries/AP_Common/AP_Var.cpp | 80 +- + libraries/AP_Common/AP_Var.h | 12 +- + libraries/AP_Common/c++.cpp | 22 +- + libraries/AP_Common/examples/menu/menu.pde | 22 +- + libraries/AP_Common/include/menu.h | 186 +- + libraries/AP_Common/menu.cpp | 198 +- + libraries/AP_DCM/AP_DCM_HIL.cpp | 12 +- + libraries/AP_GPS/AP_GPS_406.cpp | 72 +- + libraries/AP_GPS/AP_GPS_406.h | 8 +- + libraries/AP_GPS/AP_GPS_Auto.cpp | 316 +- + libraries/AP_GPS/AP_GPS_Auto.h | 58 +- + libraries/AP_GPS/AP_GPS_HIL.cpp | 18 +- + libraries/AP_GPS/AP_GPS_HIL.h | 10 +- + libraries/AP_GPS/AP_GPS_IMU.cpp | 294 +- + libraries/AP_GPS/AP_GPS_IMU.h | 68 +- + libraries/AP_GPS/AP_GPS_MTK.cpp | 226 +- + libraries/AP_GPS/AP_GPS_MTK.h | 74 +- + libraries/AP_GPS/AP_GPS_MTK16.cpp | 240 +- + libraries/AP_GPS/AP_GPS_MTK16.h | 78 +- + libraries/AP_GPS/AP_GPS_NMEA.cpp | 528 ++-- + libraries/AP_GPS/AP_GPS_NMEA.h | 118 +- + libraries/AP_GPS/AP_GPS_None.h | 8 +- + libraries/AP_GPS/AP_GPS_SIRF.cpp | 280 +- + libraries/AP_GPS/AP_GPS_SIRF.h | 130 +- + libraries/AP_GPS/AP_GPS_Shim.h | 38 +- + libraries/AP_GPS/AP_GPS_UBLOX.cpp | 292 +- + libraries/AP_GPS/AP_GPS_UBLOX.h | 184 +- + libraries/AP_GPS/GPS.cpp | 50 +- + libraries/AP_GPS/GPS.h | 330 +- + .../AP_GPS/examples/GPS_406_test/GPS_406_test.pde | 62 +- + .../examples/GPS_AUTO_test/GPS_AUTO_test.pde | 42 +- + .../AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde | 60 +- + .../examples/GPS_NMEA_test/GPS_NMEA_test.pde | 81 +- + .../examples/GPS_UBLOX_test/GPS_UBLOX_test.pde | 60 +- + libraries/Desktop/Desktop.mk | 2 +- + libraries/Desktop/Makefile.desktop | 3 + + libraries/GCS_MAVLink/GCS_MAVLink.cpp | 6 +- + libraries/GCS_MAVLink/GCS_MAVLink.h | 18 +- + .../include/ardupilotmega/ardupilotmega.h | 74 +- + .../include/ardupilotmega/mavlink_msg_ap_adc.h | 254 ++ + .../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++ + .../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++ + .../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++ + .../ardupilotmega/mavlink_msg_mount_control.h | 254 ++ + .../ardupilotmega/mavlink_msg_mount_status.h | 232 ++ + .../GCS_MAVLink/include/ardupilotmega/testsuite.h | 340 ++ + .../GCS_MAVLink/include/ardupilotmega/version.h | 2 +- + libraries/GCS_MAVLink/include/bittest.c | 39 - + libraries/GCS_MAVLink/include/common/common.h | 52 +- + .../mavlink_msg_attitude_controller_output.h | 169 - + .../include/common/mavlink_msg_attitude_new.h | 268 -- + .../include/common/mavlink_msg_auth_key.h | 6 +- + .../common/mavlink_msg_change_operator_control.h | 6 +- + .../include/common/mavlink_msg_debug_vect.h | 6 +- + .../include/common/mavlink_msg_full_state.h | 428 --- + .../include/common/mavlink_msg_gps_status.h | 30 +- + .../include/common/mavlink_msg_named_value_float.h | 6 +- + .../include/common/mavlink_msg_named_value_int.h | 6 +- + .../common/mavlink_msg_object_detection_event.h | 6 +- + .../common/mavlink_msg_param_request_read.h | 6 +- + .../include/common/mavlink_msg_param_set.h | 6 +- + .../include/common/mavlink_msg_param_value.h | 6 +- + .../mavlink_msg_position_controller_output.h | 169 - + .../mavlink_msg_request_dynamic_gyro_calibration.h | 177 - + .../mavlink_msg_request_static_calibration.h | 138 - + .../common/mavlink_msg_set_roll_pitch_yaw.h | 184 - + .../common/mavlink_msg_set_roll_pitch_yaw_speed.h | 184 - + .../include/common/mavlink_msg_statustext.h | 6 +- + .../mavlink_msg_waypoint_set_global_reference.h | 294 -- + libraries/GCS_MAVLink/include/common/testsuite.h | 30 +- + libraries/GCS_MAVLink/include/common/version.h | 2 +- + libraries/GCS_MAVLink/include/documentation.dox | 41 - + libraries/GCS_MAVLink/include/mavlink_helpers.h | 8 +- + libraries/GCS_MAVLink/include/minimal/mavlink.h | 11 - + .../include/minimal/mavlink_msg_heartbeat.h | 132 - + libraries/GCS_MAVLink/include/minimal/minimal.h | 45 - + libraries/GCS_MAVLink/include/pixhawk/mavlink.h | 11 - + .../include/pixhawk/mavlink_msg_attitude_control.h | 257 -- + .../include/pixhawk/mavlink_msg_aux_status.h | 204 - + .../include/pixhawk/mavlink_msg_brief_feature.h | 249 -- + .../include/pixhawk/mavlink_msg_control_status.h | 203 - + .../mavlink_msg_data_transmission_handshake.h | 174 - + .../include/pixhawk/mavlink_msg_debug_vect.h | 156 - + .../pixhawk/mavlink_msg_encapsulated_data.h | 124 - + .../pixhawk/mavlink_msg_encapsulated_image.h | 76 - + .../include/pixhawk/mavlink_msg_get_image_ack.h | 104 - + .../include/pixhawk/mavlink_msg_image_available.h | 586 --- + .../pixhawk/mavlink_msg_image_trigger_control.h | 101 - + .../include/pixhawk/mavlink_msg_image_triggered.h | 352 -- + .../include/pixhawk/mavlink_msg_manual_control.h | 191 - + .../include/pixhawk/mavlink_msg_marker.h | 236 -- + .../include/pixhawk/mavlink_msg_pattern_detected.h | 160 - + .../pixhawk/mavlink_msg_point_of_interest.h | 241 -- + .../mavlink_msg_point_of_interest_connection.h | 307 -- + .../mavlink_msg_position_control_offset_set.h | 206 - + .../mavlink_msg_position_control_setpoint.h | 192 - + .../mavlink_msg_position_control_setpoint_set.h | 226 -- + .../include/pixhawk/mavlink_msg_raw_aux.h | 226 -- + .../pixhawk/mavlink_msg_request_data_stream.h | 118 - + .../mavlink_msg_request_dynamic_gyro_calibration.h | 123 - + .../mavlink_msg_request_static_calibration.h | 90 - + .../include/pixhawk/mavlink_msg_set_altitude.h | 78 - + .../include/pixhawk/mavlink_msg_set_cam_shutter.h | 197 - + .../include/pixhawk/mavlink_msg_watchdog_command.h | 158 - + .../pixhawk/mavlink_msg_watchdog_heartbeat.h | 124 - + .../pixhawk/mavlink_msg_watchdog_process_info.h | 186 - + .../pixhawk/mavlink_msg_watchdog_process_status.h | 200 - + libraries/GCS_MAVLink/include/pixhawk/pixhawk.h | 79 - + libraries/GCS_MAVLink/include/protocol.h | 37 +- + libraries/GCS_MAVLink/include/slugs/mavlink.h | 11 - + .../include/slugs/mavlink_msg_air_data.h | 148 - + .../include/slugs/mavlink_msg_cpu_load.h | 138 - + .../include/slugs/mavlink_msg_ctrl_srfc_pt.h | 121 - + .../include/slugs/mavlink_msg_data_log.h | 216 -- + .../include/slugs/mavlink_msg_diagnostic.h | 210 -- + .../include/slugs/mavlink_msg_filtered_data.h | 216 -- + .../include/slugs/mavlink_msg_gps_date_time.h | 203 - + .../include/slugs/mavlink_msg_mid_lvl_cmds.h | 167 - + .../GCS_MAVLink/include/slugs/mavlink_msg_pid.h | 130 - + .../include/slugs/mavlink_msg_pilot_console.h | 145 - + .../include/slugs/mavlink_msg_pwm_commands.h | 235 -- + .../include/slugs/mavlink_msg_sensor_bias.h | 216 -- + .../include/slugs/mavlink_msg_slugs_action.h | 138 - + .../include/slugs/mavlink_msg_slugs_navigation.h | 272 -- + libraries/GCS_MAVLink/include/slugs/slugs.h | 56 - + libraries/GCS_MAVLink/include/ualberta/mavlink.h | 11 - + .../include/ualberta/mavlink_msg_nav_filter_bias.h | 242 -- + .../ualberta/mavlink_msg_radio_calibration.h | 204 - + .../mavlink_msg_request_radio_calibration.h | 59 - + .../ualberta/mavlink_msg_request_rc_channels.h | 101 - + .../ualberta/mavlink_msg_ualberta_sys_status.h | 135 - + libraries/GCS_MAVLink/include/ualberta/ualberta.h | 79 - + .../include_v1.0/ardupilotmega/ardupilotmega.h | 122 + + .../include_v1.0/ardupilotmega/mavlink.h | 27 + + .../ardupilotmega/mavlink_msg_ap_adc.h | 254 ++ + .../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++ + .../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++ + .../ardupilotmega/mavlink_msg_meminfo.h | 166 + + .../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++ + .../ardupilotmega/mavlink_msg_mount_control.h | 254 ++ + .../ardupilotmega/mavlink_msg_mount_status.h | 232 ++ + .../ardupilotmega/mavlink_msg_sensor_offsets.h | 386 ++ + .../ardupilotmega/mavlink_msg_set_mag_offsets.h | 232 ++ + .../include_v1.0/ardupilotmega/testsuite.h | 538 +++ + .../include_v1.0/ardupilotmega/version.h | 12 + + libraries/GCS_MAVLink/include_v1.0/checksum.h | 89 + + libraries/GCS_MAVLink/include_v1.0/common/common.h | 429 +++ + .../GCS_MAVLink/include_v1.0/common/mavlink.h | 27 + + .../include_v1.0/common/mavlink_msg_attitude.h | 276 ++ + .../common/mavlink_msg_attitude_quaternion.h | 298 ++ + .../include_v1.0/common/mavlink_msg_auth_key.h | 144 + + .../common/mavlink_msg_change_operator_control.h | 204 + + .../mavlink_msg_change_operator_control_ack.h | 188 + + .../include_v1.0/common/mavlink_msg_command_ack.h | 166 + + .../include_v1.0/common/mavlink_msg_command_long.h | 364 ++ + .../include_v1.0/common/mavlink_msg_data_stream.h | 188 + + .../include_v1.0/common/mavlink_msg_debug.h | 188 + + .../include_v1.0/common/mavlink_msg_debug_vect.h | 226 ++ + .../common/mavlink_msg_extended_message.h | 188 + + .../common/mavlink_msg_global_position_int.h | 320 ++ + .../mavlink_msg_global_position_setpoint_int.h | 232 ++ + .../mavlink_msg_global_vision_position_estimate.h | 276 ++ + .../common/mavlink_msg_gps_global_origin.h | 188 + + .../include_v1.0/common/mavlink_msg_gps_raw_int.h | 342 ++ + .../include_v1.0/common/mavlink_msg_gps_status.h | 252 ++ + .../include_v1.0/common/mavlink_msg_heartbeat.h | 251 ++ + .../include_v1.0/common/mavlink_msg_hil_controls.h | 364 ++ + .../common/mavlink_msg_hil_rc_inputs_raw.h | 430 +++ + .../include_v1.0/common/mavlink_msg_hil_state.h | 474 +++ + .../common/mavlink_msg_local_position_ned.h | 276 ++ + .../common/mavlink_msg_local_position_setpoint.h | 232 ++ + .../common/mavlink_msg_manual_control.h | 320 ++ + .../include_v1.0/common/mavlink_msg_memory_vect.h | 204 + + .../include_v1.0/common/mavlink_msg_mission_ack.h | 188 + + .../common/mavlink_msg_mission_clear_all.h | 166 + + .../common/mavlink_msg_mission_count.h | 188 + + .../common/mavlink_msg_mission_current.h | 144 + + .../include_v1.0/common/mavlink_msg_mission_item.h | 430 +++ + .../common/mavlink_msg_mission_item_reached.h | 144 + + .../common/mavlink_msg_mission_request.h | 188 + + .../common/mavlink_msg_mission_request_list.h | 166 + + .../mavlink_msg_mission_request_partial_list.h | 210 ++ + .../common/mavlink_msg_mission_set_current.h | 188 + + .../mavlink_msg_mission_write_partial_list.h | 210 ++ + .../common/mavlink_msg_named_value_float.h | 182 + + .../common/mavlink_msg_named_value_int.h | 182 + + .../common/mavlink_msg_nav_controller_output.h | 298 ++ + .../include_v1.0/common/mavlink_msg_optical_flow.h | 254 ++ + .../common/mavlink_msg_param_request_list.h | 166 + + .../common/mavlink_msg_param_request_read.h | 204 + + .../include_v1.0/common/mavlink_msg_param_set.h | 226 ++ + .../include_v1.0/common/mavlink_msg_param_value.h | 226 ++ + .../include_v1.0/common/mavlink_msg_ping.h | 210 ++ + .../include_v1.0/common/mavlink_msg_raw_imu.h | 342 ++ + .../include_v1.0/common/mavlink_msg_raw_pressure.h | 232 ++ + .../common/mavlink_msg_rc_channels_override.h | 342 ++ + .../common/mavlink_msg_rc_channels_raw.h | 364 ++ + .../common/mavlink_msg_rc_channels_scaled.h | 364 ++ + .../common/mavlink_msg_request_data_stream.h | 232 ++ + ...link_msg_roll_pitch_yaw_speed_thrust_setpoint.h | 232 ++ + .../mavlink_msg_roll_pitch_yaw_thrust_setpoint.h | 232 ++ + .../common/mavlink_msg_safety_allowed_area.h | 276 ++ + .../common/mavlink_msg_safety_set_allowed_area.h | 320 ++ + .../include_v1.0/common/mavlink_msg_scaled_imu.h | 342 ++ + .../common/mavlink_msg_scaled_pressure.h | 210 ++ + .../common/mavlink_msg_servo_output_raw.h | 342 ++ + .../mavlink_msg_set_global_position_setpoint_int.h | 232 ++ + .../common/mavlink_msg_set_gps_global_origin.h | 210 ++ + .../mavlink_msg_set_local_position_setpoint.h | 276 ++ + .../include_v1.0/common/mavlink_msg_set_mode.h | 188 + + .../mavlink_msg_set_roll_pitch_yaw_speed_thrust.h | 254 ++ + .../common/mavlink_msg_set_roll_pitch_yaw_thrust.h | 254 ++ + .../common/mavlink_msg_state_correction.h | 320 ++ + .../include_v1.0/common/mavlink_msg_statustext.h | 160 + + .../include_v1.0/common/mavlink_msg_sys_status.h | 408 ++ + .../include_v1.0/common/mavlink_msg_system_time.h | 166 + + .../include_v1.0/common/mavlink_msg_vfr_hud.h | 254 ++ + .../common}/mavlink_msg_vicon_position_estimate.h | 198 +- + .../common}/mavlink_msg_vision_position_estimate.h | 198 +- + .../common}/mavlink_msg_vision_speed_estimate.h | 148 +- + .../GCS_MAVLink/include_v1.0/common/testsuite.h | 3908 ++++++++++++++++++++ + .../GCS_MAVLink/include_v1.0/common/version.h | 12 + + .../GCS_MAVLink/include_v1.0/mavlink_helpers.h | 488 +++ + libraries/GCS_MAVLink/include_v1.0/mavlink_types.h | 182 + + libraries/GCS_MAVLink/include_v1.0/protocol.h | 319 ++ + .../message_definitions/ardupilotmega.xml | 132 + + libraries/GCS_MAVLink/message_definitions/test.xml | 31 + + .../message_definitions_v1.0/ardupilotmega.xml | 177 + + .../message_definitions_v1.0/common.xml | 1536 ++++++++ + .../message_definitions_v1.0/minimal.xml | 16 + + .../message_definitions_v1.0/pixhawk.xml | 193 + + .../GCS_MAVLink/message_definitions_v1.0/slugs.xml | 144 + + .../GCS_MAVLink/message_definitions_v1.0/test.xml | 31 + + .../message_definitions_v1.0/ualberta.xml | 54 + + libraries/RC_Channel/RC_Channel.cpp | 2 +- + libraries/RC_Channel/RC_Channel.h | 8 +- + libraries/RC_Channel/RC_Channel_aux.cpp | 2 +- + libraries/RC_Channel/RC_Channel_aux.h | 1 + + 355 files changed, 43388 insertions(+), 22115 deletions(-) + delete mode 100644 ArduCopter/CMakeLists.txt + delete mode 100644 ArduPlane/.gitignore + delete mode 100644 ArduPlane/CMakeLists.txt + create mode 100644 ArduPlane/Mavlink_compat.h + create mode 100644 Tools/ArdupilotMegaPlanner/Camera.Designer.cs + create mode 100644 Tools/ArdupilotMegaPlanner/Camera.cs + create mode 100644 Tools/ArdupilotMegaPlanner/Camera.resx + create mode 100755 Tools/scripts/format.sh + create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h + create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_configure.h + create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_control.h + create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_configure.h + create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_control.h + create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_status.h + delete mode 100644 libraries/GCS_MAVLink/include/bittest.c + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_controller_output.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_new.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_position_controller_output.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_static_calibration.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h + delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_global_reference.h + delete mode 100644 libraries/GCS_MAVLink/include/documentation.dox + delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink.h + delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h + delete mode 100644 libraries/GCS_MAVLink/include/minimal/minimal.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_attitude_control.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_aux_status.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_brief_feature.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_control_status.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_data_transmission_handshake.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_debug_vect.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_data.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_image.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_get_image_ack.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_trigger_control.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_manual_control.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_marker.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_pattern_detected.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest_connection.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_offset_set.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_raw_aux.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_data_stream.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_static_calibration.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_altitude.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_cam_shutter.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_command.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_info.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_status.h + delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/pixhawk.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_filtered_data.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pid.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pilot_console.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pwm_commands.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h + delete mode 100644 libraries/GCS_MAVLink/include/slugs/slugs.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_nav_filter_bias.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_radio_calibration.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_rc_channels.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h + delete mode 100644 libraries/GCS_MAVLink/include/ualberta/ualberta.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_ap_adc.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_configure.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_control.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_configure.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_control.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_status.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/checksum.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/common.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_partial_list.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_write_partial_list.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h + rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vicon_position_estimate.h (54%) + rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_position_estimate.h (54%) + rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_speed_estimate.h (57%) + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/testsuite.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/version.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_helpers.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_types.h + create mode 100644 libraries/GCS_MAVLink/include_v1.0/protocol.h + create mode 100644 libraries/GCS_MAVLink/message_definitions/test.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/common.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/test.xml + create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml