From 178b8c0d19f7d00adbd59ab71cba48d814a0cdc0 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sat, 19 Nov 2011 07:47:33 +0800 Subject: [PATCH 01/63] fix ap hil --- .../Firmware/APHIL-1280.build.log | 92 ++++++++++--------- .../Firmware/APHIL-1280.size.txt | 10 +- .../Firmware/APHIL-2560.build.log | 92 ++++++++++--------- .../Firmware/APHIL-2560.size.txt | 10 +- 4 files changed, 108 insertions(+), 96 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log index f7c809ef2b..6ed3a9f501 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log @@ -13,58 +13,62 @@ autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'sta autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'byte get_num_logs()' defined but not used autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined -autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduPlane/Log.pde:749: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:750: warning: 'void Log_Write_Control_Tuning()' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:751: warning: 'void Log_Write_Raw()' defined but not used -autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined -autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined -autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined -autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined -autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined -autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined -autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined -autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined -autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined -autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined -autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined -autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined +autogenerated:53: warning: 'int find_last()' declared 'static' but never defined +autogenerated:54: warning: 'int find_last_log_page(uint16_t)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduPlane/Log.pde:843: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:839: warning: 'void Log_Write_Performance()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Control_Tuning()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Raw()' defined but not used +autogenerated:65: warning: 'void Log_Read_Current()' declared 'static' but never defined +autogenerated:66: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined +autogenerated:67: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined +autogenerated:68: warning: 'void Log_Read_Performance()' declared 'static' but never defined +autogenerated:69: warning: 'void Log_Read_Cmd()' declared 'static' but never defined +autogenerated:70: warning: 'void Log_Read_Startup()' declared 'static' but never defined +autogenerated:71: warning: 'void Log_Read_Attitude()' declared 'static' but never defined +autogenerated:72: warning: 'void Log_Read_Mode()' declared 'static' but never defined +autogenerated:73: warning: 'void Log_Read_GPS()' declared 'static' but never defined +autogenerated:74: warning: 'void Log_Read_Raw()' declared 'static' but never defined +autogenerated:75: warning: 'void Log_Read(int, int)' declared 'static' but never defined +autogenerated:76: warning: 'int Log_Read_Process(int, int)' declared 'static' but never defined +autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used -autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined -autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined -autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined -autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined -autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined -autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined -autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined -autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined -autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined -autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined -autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined -autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined -autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined -autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined -autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined -autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined -autogenerated:180: warning: 'void print_done()' declared 'static' but never defined -autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined -autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined -autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined -autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined -autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined -autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined -autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined -autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined -autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined -autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined +autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined +autogenerated:166: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:167: warning: 'long int read_barometer()' declared 'static' but never defined +autogenerated:168: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:169: warning: 'void zero_airspeed()' declared 'static' but never defined +autogenerated:171: warning: 'void report_batt_monitor()' declared 'static' but never defined +autogenerated:172: warning: 'void report_radio()' declared 'static' but never defined +autogenerated:173: warning: 'void report_gains()' declared 'static' but never defined +autogenerated:174: warning: 'void report_xtrack()' declared 'static' but never defined +autogenerated:175: warning: 'void report_throttle()' declared 'static' but never defined +autogenerated:176: warning: 'void report_imu()' declared 'static' but never defined +autogenerated:177: warning: 'void report_compass()' declared 'static' but never defined +autogenerated:178: warning: 'void report_flight_modes()' declared 'static' but never defined +autogenerated:179: warning: 'void print_PID(PID*)' declared 'static' but never defined +autogenerated:180: warning: 'void print_radio_values()' declared 'static' but never defined +autogenerated:181: warning: 'void print_switch(byte, byte)' declared 'static' but never defined +autogenerated:182: warning: 'void print_done()' declared 'static' but never defined +autogenerated:183: warning: 'void print_blanks(int)' declared 'static' but never defined +autogenerated:184: warning: 'void print_divider()' declared 'static' but never defined +autogenerated:185: warning: 'int8_t radio_input_switch()' declared 'static' but never defined +autogenerated:186: warning: 'void zero_eeprom()' declared 'static' but never defined +autogenerated:187: warning: 'void print_enabled(bool)' declared 'static' but never defined +autogenerated:188: warning: 'void print_accel_offsets()' declared 'static' but never defined +autogenerated:189: warning: 'void print_gyro_offsets()' declared 'static' but never defined +autogenerated:190: warning: 'void run_cli()' declared 'static' but never defined +autogenerated:200: warning: 'void print_hit_enter()' declared 'static' but never defined +autogenerated:201: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used /root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt index 3c5d76aeb2..fbeed9d9de 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt @@ -199,6 +199,7 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -290,6 +291,7 @@ 0000001c W AP_VarT::unserialize(void*, unsigned int) 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001e t update_commands() 0000001e r startup_ground()::__c 00000020 t gcs_send_message(ap_message) 00000020 t byte_swap_4 @@ -429,9 +431,9 @@ 000002d4 t handle_process_do_command() 000002e4 t read_radio() 00000320 t __static_initialization_and_destruction_0(int, int) -0000033a W Parameters::~Parameters() +00000344 W Parameters::~Parameters() 00000494 t init_ardupilot() -00000920 W Parameters::Parameters() -0000092b b g +00000936 W Parameters::Parameters() +00000938 b g 0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001c82 T loop +00001c76 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log index f7c809ef2b..6ed3a9f501 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log @@ -13,58 +13,62 @@ autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'sta autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'byte get_num_logs()' defined but not used autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined -autogenerated:53: warning: 'int find_last_log_page(int)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduPlane/Log.pde:749: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:750: warning: 'void Log_Write_Control_Tuning()' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:751: warning: 'void Log_Write_Raw()' defined but not used -autogenerated:64: warning: 'void Log_Read_Current()' declared 'static' but never defined -autogenerated:65: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined -autogenerated:66: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined -autogenerated:67: warning: 'void Log_Read_Performance()' declared 'static' but never defined -autogenerated:68: warning: 'void Log_Read_Cmd()' declared 'static' but never defined -autogenerated:69: warning: 'void Log_Read_Startup()' declared 'static' but never defined -autogenerated:70: warning: 'void Log_Read_Attitude()' declared 'static' but never defined -autogenerated:71: warning: 'void Log_Read_Mode()' declared 'static' but never defined -autogenerated:72: warning: 'void Log_Read_GPS()' declared 'static' but never defined -autogenerated:73: warning: 'void Log_Read_Raw()' declared 'static' but never defined -autogenerated:74: warning: 'void Log_Read(int, int)' declared 'static' but never defined -autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined +autogenerated:53: warning: 'int find_last()' declared 'static' but never defined +autogenerated:54: warning: 'int find_last_log_page(uint16_t)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduPlane/Log.pde:843: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:839: warning: 'void Log_Write_Performance()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Control_Tuning()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Raw()' defined but not used +autogenerated:65: warning: 'void Log_Read_Current()' declared 'static' but never defined +autogenerated:66: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined +autogenerated:67: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined +autogenerated:68: warning: 'void Log_Read_Performance()' declared 'static' but never defined +autogenerated:69: warning: 'void Log_Read_Cmd()' declared 'static' but never defined +autogenerated:70: warning: 'void Log_Read_Startup()' declared 'static' but never defined +autogenerated:71: warning: 'void Log_Read_Attitude()' declared 'static' but never defined +autogenerated:72: warning: 'void Log_Read_Mode()' declared 'static' but never defined +autogenerated:73: warning: 'void Log_Read_GPS()' declared 'static' but never defined +autogenerated:74: warning: 'void Log_Read_Raw()' declared 'static' but never defined +autogenerated:75: warning: 'void Log_Read(int, int)' declared 'static' but never defined +autogenerated:76: warning: 'int Log_Read_Process(int, int)' declared 'static' but never defined +autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used -autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined -autogenerated:164: warning: 'void init_barometer()' declared 'static' but never defined -autogenerated:165: warning: 'long int read_barometer()' declared 'static' but never defined -autogenerated:166: warning: 'void read_airspeed()' declared 'static' but never defined -autogenerated:167: warning: 'void zero_airspeed()' declared 'static' but never defined -autogenerated:169: warning: 'void report_batt_monitor()' declared 'static' but never defined -autogenerated:170: warning: 'void report_radio()' declared 'static' but never defined -autogenerated:171: warning: 'void report_gains()' declared 'static' but never defined -autogenerated:172: warning: 'void report_xtrack()' declared 'static' but never defined -autogenerated:173: warning: 'void report_throttle()' declared 'static' but never defined -autogenerated:174: warning: 'void report_imu()' declared 'static' but never defined -autogenerated:175: warning: 'void report_compass()' declared 'static' but never defined -autogenerated:176: warning: 'void report_flight_modes()' declared 'static' but never defined -autogenerated:177: warning: 'void print_PID(PID*)' declared 'static' but never defined -autogenerated:178: warning: 'void print_radio_values()' declared 'static' but never defined -autogenerated:179: warning: 'void print_switch(byte, byte)' declared 'static' but never defined -autogenerated:180: warning: 'void print_done()' declared 'static' but never defined -autogenerated:181: warning: 'void print_blanks(int)' declared 'static' but never defined -autogenerated:182: warning: 'void print_divider()' declared 'static' but never defined -autogenerated:183: warning: 'int8_t radio_input_switch()' declared 'static' but never defined -autogenerated:184: warning: 'void zero_eeprom()' declared 'static' but never defined -autogenerated:185: warning: 'void print_enabled(bool)' declared 'static' but never defined -autogenerated:186: warning: 'void print_accel_offsets()' declared 'static' but never defined -autogenerated:187: warning: 'void print_gyro_offsets()' declared 'static' but never defined -autogenerated:188: warning: 'void run_cli()' declared 'static' but never defined -autogenerated:198: warning: 'void print_hit_enter()' declared 'static' but never defined -autogenerated:199: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined +autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined +autogenerated:166: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:167: warning: 'long int read_barometer()' declared 'static' but never defined +autogenerated:168: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:169: warning: 'void zero_airspeed()' declared 'static' but never defined +autogenerated:171: warning: 'void report_batt_monitor()' declared 'static' but never defined +autogenerated:172: warning: 'void report_radio()' declared 'static' but never defined +autogenerated:173: warning: 'void report_gains()' declared 'static' but never defined +autogenerated:174: warning: 'void report_xtrack()' declared 'static' but never defined +autogenerated:175: warning: 'void report_throttle()' declared 'static' but never defined +autogenerated:176: warning: 'void report_imu()' declared 'static' but never defined +autogenerated:177: warning: 'void report_compass()' declared 'static' but never defined +autogenerated:178: warning: 'void report_flight_modes()' declared 'static' but never defined +autogenerated:179: warning: 'void print_PID(PID*)' declared 'static' but never defined +autogenerated:180: warning: 'void print_radio_values()' declared 'static' but never defined +autogenerated:181: warning: 'void print_switch(byte, byte)' declared 'static' but never defined +autogenerated:182: warning: 'void print_done()' declared 'static' but never defined +autogenerated:183: warning: 'void print_blanks(int)' declared 'static' but never defined +autogenerated:184: warning: 'void print_divider()' declared 'static' but never defined +autogenerated:185: warning: 'int8_t radio_input_switch()' declared 'static' but never defined +autogenerated:186: warning: 'void zero_eeprom()' declared 'static' but never defined +autogenerated:187: warning: 'void print_enabled(bool)' declared 'static' but never defined +autogenerated:188: warning: 'void print_accel_offsets()' declared 'static' but never defined +autogenerated:189: warning: 'void print_gyro_offsets()' declared 'static' but never defined +autogenerated:190: warning: 'void run_cli()' declared 'static' but never defined +autogenerated:200: warning: 'void print_hit_enter()' declared 'static' but never defined +autogenerated:201: warning: 'void test_wp_print(Location*, byte)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:194: warning: 'comma' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:196: warning: 'flight_mode_strings' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:746: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used /root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt index 8f46e490aa..16c1744827 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt @@ -199,6 +199,7 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -290,6 +291,7 @@ 0000001c W AP_VarT::unserialize(void*, unsigned int) 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001e t update_commands() 0000001e r startup_ground()::__c 00000020 t gcs_send_message(ap_message) 00000020 t byte_swap_4 @@ -429,9 +431,9 @@ 000002d4 t handle_process_do_command() 000002e4 t read_radio() 00000320 t __static_initialization_and_destruction_0(int, int) -0000033a W Parameters::~Parameters() +00000344 W Parameters::~Parameters() 00000492 t init_ardupilot() -00000920 W Parameters::Parameters() -0000092b b g +00000936 W Parameters::Parameters() +00000938 b g 0000178a T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001c82 T loop +00001c76 T loop From 791fd194a48e45fd8634bd4b5a4ca9c592e5fc3b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 10:56:15 -0800 Subject: [PATCH 02/63] added logging of raw baro --- ArduCopter/Log.pde | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 38e55858b5..9a95726fe4 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -20,8 +20,8 @@ static int8_t select_logs(uint8_t argc, const Menu::arg *argv); // This is the help function // PSTR is an AVR macro to read strings from flash memory // printf_P is a version of print_f that reads from flash memory -static int8_t help_log(uint8_t argc, const Menu::arg *argv) -{ +//static int8_t help_log(uint8_t argc, const Menu::arg *argv) +/*{ Serial.printf_P(PSTR("\n" "Commands:\n" " dump " @@ -30,7 +30,7 @@ static int8_t help_log(uint8_t argc, const Menu::arg *argv) " disable | all\n" "\n")); return 0; -} +}*/ // Creates a constant array of structs representing menu options // and stores them in Flash memory, not RAM. @@ -40,8 +40,7 @@ const struct Menu::command log_menu_commands[] PROGMEM = { {"dump", dump_log}, {"erase", erase_logs}, {"enable", select_logs}, - {"disable", select_logs}, - {"help", help_log} + {"disable", select_logs} }; // A Macro to create the Menu @@ -698,15 +697,16 @@ static void Log_Write_Control_Tuning() DataFlash.WriteInt(angle_boost); //8 DataFlash.WriteInt(manual_boost); //9 DataFlash.WriteInt(climb_rate); //10 -//#if HIL_MODE == HIL_MODE_ATTITUDE -// DataFlash.WriteInt(0); //10 -//#else -// DataFlash.WriteInt((int)(barometer.RawPress - barometer._offset_press));//10 -//#endif - DataFlash.WriteInt(g.rc_3.servo_out); //11 - DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); //12 - DataFlash.WriteInt(g.pi_throttle.get_integrator()); //13 +#if HIL_MODE == HIL_MODE_ATTITUDE + DataFlash.WriteInt(0); //11 +#else + DataFlash.WriteInt((int)(barometer.RawPress - barometer._offset_press));//11 +#endif + + DataFlash.WriteInt(g.rc_3.servo_out); //12 + DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); //13 + DataFlash.WriteInt(g.pi_throttle.get_integrator()); //14 DataFlash.WriteByte(END_BYTE); } @@ -718,7 +718,7 @@ static void Log_Read_Control_Tuning() Serial.printf_P(PSTR("CTUN, ")); - for(int8_t i = 1; i < 13; i++ ){ + for(int8_t i = 1; i < 14; i++ ){ temp = DataFlash.ReadInt(); Serial.printf("%d, ", temp); } From 35524f6da76c4e9d3587541dc33adc632cf365fa Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 11:08:03 -0800 Subject: [PATCH 03/63] Added optimizations for radian calls to remove a division. added a protection for entering AP modes without Home being set by GPS lock. --- ArduCopter/defines.h | 2 ++ ArduCopter/navigation.pde | 15 +++++++++++---- ArduCopter/system.pde | 7 +++++++ 3 files changed, 20 insertions(+), 4 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 5d9f3525e6..c881148463 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -332,6 +332,8 @@ enum gcs_severity { #define B_LED_PIN 36 #define C_LED_PIN 35 +// RADIANS +#define RADX100 0.000174533 // EEPROM addresses #define EEPROM_MAX_ADDR 4096 diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index d1201d8c09..83907da578 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -67,7 +67,8 @@ static void calc_loiter(int x_error, int y_error) int y_target_speed = g.pi_loiter_lat.get_pi(y_error, dTnav); // find the rates: - float temp = radians((float)g_gps->ground_course/100.0); + //float temp = radians((float)g_gps->ground_course/100.0); + float temp = g_gps->ground_course * RADX100; #ifdef OPTFLOW_ENABLED // calc the cos of the error to tell how fast we are moving towards the target in cm @@ -172,7 +173,8 @@ static void calc_nav_rate(int max_speed) } // XXX target_angle should be the original desired target angle! - float temp = radians((target_bearing - g_gps->ground_course)/100.0); + //float temp = radians((target_bearing - g_gps->ground_course)/100.0); + float temp = (target_bearing - g_gps->ground_course) * RADX100; // push us towards the original track update_crosstrack(); @@ -209,7 +211,10 @@ static void update_crosstrack(void) // Crosstrack Error // ---------------- if (cross_track_test() < 5000) { // If we are too far off or too close we don't do track following - crosstrack_error = sin(radians((target_bearing - original_target_bearing) / 100)) * wp_distance; // Meters we are off track line + float temp = (target_bearing - original_target_bearing) * RADX100; + //radians((target_bearing - original_target_bearing) / 100) + crosstrack_error = sin(temp) * wp_distance; // Meters we are off track line + crosstrack_error = constrain(crosstrack_error * 4, -1200, 1200); } } @@ -225,7 +230,9 @@ static int32_t cross_track_test() // nav_roll, nav_pitch static void calc_nav_pitch_roll() { - float temp = radians((float)(9000 - (dcm.yaw_sensor - original_target_bearing))/100.0); + float temp = (9000l - (dcm.yaw_sensor - original_target_bearing)) * RADX100; + //t: 1.5465, t1: -10.9451, t2: 1.5359, t3: 1.5465 + float _cos_yaw_x = cos(temp); float _sin_yaw_y = sin(temp); diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index ed0a530e6d..277bfcbd4e 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -359,6 +359,13 @@ static void set_mode(byte mode) return; } + // if we don't have GPS lock + if(home_is_set == false){ + // our max mode should be + if (mode > ALT_HOLD) + mode = STABILIZE; + } + old_control_mode = control_mode; control_mode = mode; From 579096cd2eb589e35d6bcc60d0906e5246d3a04d Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 13:58:41 -0800 Subject: [PATCH 04/63] return to prev climb rate calc --- ArduCopter/ArduCopter.pde | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 4d02571c90..c7387f8ec1 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1244,13 +1244,20 @@ static void update_altitude() #else // This is real life + + // read in Actual Baro Altitude + baro_alt = (baro_alt + read_barometer()) >> 1; + // calc the vertical accel rate + #if CLIMB_RATE_BARO = 1 int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale baro_rate = (temp_baro_alt - old_baro_alt) * 10; old_baro_alt = temp_baro_alt; - // read in Actual Baro Altitude - baro_alt = (baro_alt + read_barometer()) >> 1; + #else + baro_rate = (baro_alt - old_baro_alt) * 10; + old_baro_alt = baro_alt; + #endif // sonar_alt is calculaed in a faster loop and filtered with a mode filter #endif From e4f2ad1809f9885c5bf0b4fabe2588cd69dbf90a Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 13:58:53 -0800 Subject: [PATCH 05/63] remove PI_crosstrack --- ArduCopter/Attitude.pde | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 3850e7dc39..3aa78a1ba2 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -133,7 +133,6 @@ static void reset_hold_I(void) { g.pi_loiter_lat.reset_I(); g.pi_loiter_lon.reset_I(); - g.pi_crosstrack.reset_I(); } // Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc. From 9bc4328724af7a7da1b42380f61a6e2b734ec564 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 13:59:15 -0800 Subject: [PATCH 06/63] Added crosstrack gain and lowered alt hold rate gain --- ArduCopter/config.h | 20 +++----------------- 1 file changed, 3 insertions(+), 17 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a3a4a6d6e8..e1f0b07ffb 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -519,7 +519,7 @@ // RATE control #ifndef THROTTLE_P -# define THROTTLE_P 1.0 // +# define THROTTLE_P 0.6 // #endif #ifndef THROTTLE_I # define THROTTLE_I 0.0 // @@ -532,24 +532,10 @@ ////////////////////////////////////////////////////////////////////////////// // Crosstrack compensation // -#ifndef XTRACK_ENTRY_ANGLE -# define XTRACK_ENTRY_ANGLE 30 // deg +#ifndef CROSSTRACK_GAIN +# define CROSSTRACK_GAIN 4 #endif -#ifndef XTRACK_P -# define XTRACK_P 2 // trying a lower val -#endif -#ifndef XTRACK_I -# define XTRACK_I 0.00 //with 4m error, 12.5s windup -#endif -#ifndef XTRACK_D -# define XTRACK_D 0.00 // upped with filter -#endif -#ifndef XTRACK_IMAX -# define XTRACK_IMAX 10 -#endif - - ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// From 39d0df4cef80391cfc259a98f8bf45a33ab0b644 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 13:59:37 -0800 Subject: [PATCH 07/63] added param for crosstrack gain defaulted to 4 --- ArduCopter/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 83907da578..7b41ed13e3 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -215,7 +215,7 @@ static void update_crosstrack(void) //radians((target_bearing - original_target_bearing) / 100) crosstrack_error = sin(temp) * wp_distance; // Meters we are off track line - crosstrack_error = constrain(crosstrack_error * 4, -1200, 1200); + crosstrack_error = constrain(crosstrack_error * g.crosstrack_gain, -1200, 1200); } } From d1c161ecd03645cac2af720ee6c6fb662f59624f Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:00:23 -0800 Subject: [PATCH 08/63] Upped version added new logging params added crosstrack gain re-ordered param inits --- ArduCopter/Parameters.h | 50 +++++++++++++++++------------------------ 1 file changed, 20 insertions(+), 30 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 860ee957dc..78a8b6c36b 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -17,7 +17,7 @@ public: // The increment will prevent old parameters from being used incorrectly // by newer code. // - static const uint16_t k_format_version = 112; + static const uint16_t k_format_version = 113; // The parameter software_type is set up solely for ground station use // and identifies the software type (eg ArduPilotMega versus ArduCopterMega) @@ -55,7 +55,8 @@ public: // Misc // - k_param_log_bitmask, + k_param_log_bitmask = 20, + k_param_log_last_filenumber, #if FRAME_CONFIG == HELI_FRAME // @@ -107,8 +108,8 @@ public: // // 160: Navigation parameters // - k_param_crosstrack_entry_angle = 160, - k_param_RTL_altitude, + k_param_RTL_altitude = 160, + k_param_crosstrack_gain, // // 180: Radio settings @@ -171,7 +172,6 @@ public: k_param_pi_nav_lon, k_param_pi_alt_hold, k_param_pi_throttle, - k_param_pi_crosstrack, k_param_pi_acro_roll, k_param_pi_acro_pitch, @@ -189,9 +189,14 @@ public: AP_Int8 serial3_baud; - // Crosstrack navigation - // - AP_Int16 crosstrack_entry_angle; + AP_Int16 RTL_altitude; + AP_Int8 sonar_enabled; + AP_Int8 battery_monitoring; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current + AP_Int16 pack_capacity; // Battery pack capacity less reserve + AP_Int8 compass_enabled; + AP_Int8 optflow_enabled; + AP_Float input_voltage; + AP_Float low_voltage; // Waypoints // @@ -202,6 +207,7 @@ public: AP_Int8 waypoint_radius; AP_Int16 loiter_radius; AP_Int16 waypoint_speed_max; + AP_Float crosstrack_gain; // Throttle // @@ -222,30 +228,16 @@ public: AP_Int8 flight_mode6; AP_Int8 simple_modes; - // Radio settings - // - //AP_Var_group pwm_roll; - //AP_Var_group pwm_pitch; - //AP_Var_group pwm_throttle; - //AP_Var_group pwm_yaw; - // Misc // AP_Int16 log_bitmask; - AP_Int16 RTL_altitude; + AP_Int16 log_last_filenumber; - AP_Int8 sonar_enabled; - AP_Int8 battery_monitoring; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current - AP_Int16 pack_capacity; // Battery pack capacity less reserve - AP_Int8 compass_enabled; AP_Int8 esc_calibrate; AP_Int8 radio_tuning; - AP_Int8 frame_orientation; AP_Float top_bottom_ratio; - AP_Int8 optflow_enabled; - AP_Float input_voltage; - AP_Float low_voltage; + #if FRAME_CONFIG == HELI_FRAME // Heli @@ -272,6 +264,7 @@ public: RC_Channel rc_8; RC_Channel rc_camera_pitch; RC_Channel rc_camera_roll; + AP_Float camera_pitch_gain; AP_Float camera_roll_gain; @@ -292,7 +285,6 @@ public: APM_PI pi_alt_hold; APM_PI pi_throttle; - APM_PI pi_crosstrack; APM_PI pi_acro_roll; APM_PI pi_acro_pitch; @@ -310,9 +302,7 @@ public: sysid_my_gcs (255, k_param_sysid_my_gcs, PSTR("SYSID_MYGCS")), serial3_baud (SERIAL3_BAUD/1000, k_param_serial3_baud, PSTR("SERIAL3_BAUD")), - //crosstrack_gain (XTRACK_GAIN * 100, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")), - crosstrack_entry_angle (XTRACK_ENTRY_ANGLE * 100, k_param_crosstrack_entry_angle, PSTR("XTRK_ANGLE_CD")), - + RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")), sonar_enabled (DISABLED, k_param_sonar, PSTR("SONAR_ENABLE")), battery_monitoring (DISABLED, k_param_battery_monitoring, PSTR("BATT_MONITOR")), pack_capacity (HIGH_DISCHARGE, k_param_pack_capacity, PSTR("BATT_CAPACITY")), @@ -328,6 +318,7 @@ public: waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")), loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")), waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")), + crosstrack_gain (CROSSTRACK_GAIN, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")), throttle_min (0, k_param_throttle_min, PSTR("THR_MIN")), throttle_max (1000, k_param_throttle_max, PSTR("THR_MAX")), @@ -345,7 +336,7 @@ public: simple_modes (0, k_param_simple_modes, PSTR("SIMPLE")), log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")), - RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")), + log_last_filenumber (0, k_param_log_last_filenumber, PSTR("LOG_LASTFILE")), esc_calibrate (0, k_param_esc_calibrate, PSTR("ESC")), radio_tuning (0, k_param_radio_tuning, PSTR("TUNE")), frame_orientation (FRAME_ORIENTATION, k_param_frame_orientation, PSTR("FRAME")), @@ -408,7 +399,6 @@ public: pi_alt_hold (k_param_pi_alt_hold, PSTR("THR_ALT_"), THR_HOLD_P, THR_HOLD_I, THR_HOLD_IMAX), pi_throttle (k_param_pi_throttle, PSTR("THR_RATE_"), THROTTLE_P, THROTTLE_I, THROTTLE_IMAX), - pi_crosstrack (k_param_pi_crosstrack, PSTR("XTRACK_"), XTRACK_P, XTRACK_I, XTRACK_IMAX), pi_acro_roll (k_param_pi_acro_roll, PSTR("ACRO_RLL_"), ACRO_ROLL_P, ACRO_ROLL_I, ACRO_ROLL_IMAX * 100), pi_acro_pitch (k_param_pi_acro_pitch, PSTR("ACRO_PIT_"), ACRO_PITCH_P, ACRO_PITCH_I, ACRO_PITCH_IMAX * 100), From d02b4342ae76beab7bc6cf2f687db6d90539f0d5 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:00:42 -0800 Subject: [PATCH 09/63] removed some unused code, made output min by default --- ArduCopter/radio.pde | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index a5d3e1af28..937193d8c5 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -54,11 +54,6 @@ static void init_rc_in() static void init_rc_out() { - #if ARM_AT_STARTUP == 1 - motor_armed = 1; - #endif - - APM_RC.Init(); // APM Radio initialization init_motors_out(); @@ -78,9 +73,7 @@ static void init_rc_out() if(g.esc_calibrate == 1) return; - if(g.rc_3.radio_min <= 1200){ - output_min(); - } + output_min(); for(byte i = 0; i < 5; i++){ delay(20); From 8e509b63a75daf97cbade8eb531a606cfdb0ee01 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:00:55 -0800 Subject: [PATCH 10/63] shortened strings for mem --- ArduCopter/setup.pde | 52 ++++++++++++++++++++++---------------------- 1 file changed, 26 insertions(+), 26 deletions(-) diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 44781070af..fa2166e2db 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -72,9 +72,9 @@ setup_mode(uint8_t argc, const Menu::arg *argv) if(g.rc_1.radio_min >= 1300){ delay(1000); - Serial.printf_P(PSTR("\n!Warning, your radio is not configured!")); + Serial.printf_P(PSTR("\n!Warning, radio not configured!")); delay(1000); - Serial.printf_P(PSTR("\n Type 'radio' to configure now.\n\n")); + Serial.printf_P(PSTR("\n Type 'radio' now.\n\n")); } // Run the setup menu. When the menu exits, we will return to the main menu. @@ -122,7 +122,7 @@ setup_factory(uint8_t argc, const Menu::arg *argv) { int c; - Serial.printf_P(PSTR("\n'Y' + Enter to factory reset, any other key to abort:\n")); + Serial.printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n")); do { c = Serial.read(); @@ -192,7 +192,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv) g.rc_8.radio_trim = 1500; - Serial.printf_P(PSTR("\nMove all controls to each extreme. Hit Enter to save: ")); + Serial.printf_P(PSTR("\nMove all controls to extremes. Enter to save: ")); while(1){ delay(20); @@ -233,14 +233,14 @@ setup_radio(uint8_t argc, const Menu::arg *argv) static int8_t setup_esc(uint8_t argc, const Menu::arg *argv) { - Serial.printf_P(PSTR("\nESC Calibration:\n" + /*Serial.printf_P(PSTR("\nESC Calibration:\n" "-1 Unplug USB and battery\n" "-2 Move CLI/FLY switch to FLY mode\n" "-3 Move throttle to max, connect battery\n" "-4 After two long beeps, throttle to 0, then test\n\n" " Press Enter to cancel.\n")); - - + */ + Serial.printf_P(PSTR("See wiki:\n")); g.esc_calibrate.set_and_save(1); while(1){ @@ -288,7 +288,7 @@ setup_frame(uint8_t argc, const Menu::arg *argv) } else if (!strcmp_P(argv[1].str, PSTR("v"))) { g.frame_orientation.set_and_save(V_FRAME); }else{ - Serial.printf_P(PSTR("\nOptions:[x,+,v]\n")); + Serial.printf_P(PSTR("\nOp:[x,+,v]\n")); report_frame(); return 0; } @@ -304,7 +304,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv) byte _oldSwitchPosition = 0; byte mode = 0; - Serial.printf_P(PSTR("\nMove mode switch to edit, aileron: select modes, rudder: Simple on/off\n")); + Serial.printf_P(PSTR("\nMode switch to edit, aileron: select modes, rudder: Simple on/off\n")); print_hit_enter(); while(1){ @@ -406,7 +406,7 @@ setup_compass(uint8_t argc, const Menu::arg *argv) g.compass_enabled.set_and_save(false); }else{ - Serial.printf_P(PSTR("\nOptions:[on,off]\n")); + Serial.printf_P(PSTR("\nOp:[on,off]\n")); report_compass(); return 0; } @@ -426,7 +426,7 @@ setup_batt_monitor(uint8_t argc, const Menu::arg *argv) g.battery_monitoring.set_and_save(argv[1].i); } else { - Serial.printf_P(PSTR("\nOptions: off, 1-4")); + Serial.printf_P(PSTR("\nOp: off, 1-4")); } report_batt_monitor(); @@ -443,7 +443,7 @@ setup_sonar(uint8_t argc, const Menu::arg *argv) g.sonar_enabled.set_and_save(false); }else{ - Serial.printf_P(PSTR("\nOptions:[on, off]\n")); + Serial.printf_P(PSTR("\nOp:[on, off]\n")); report_sonar(); return 0; } @@ -494,7 +494,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv) // read radio although we don't use it yet read_radio(); - + // allow swash plate to move output_motors_armed(); @@ -691,7 +691,7 @@ setup_gyro(uint8_t argc, const Menu::arg *argv) g.heli_ext_gyro_gain.save(); }else{ - Serial.printf_P(PSTR("\nOptions:[on, off] gain\n")); + Serial.printf_P(PSTR("\nOp:[on, off] gain\n")); } report_gyro(); @@ -783,7 +783,7 @@ setup_optflow(uint8_t argc, const Menu::arg *argv) g.optflow_enabled = false; }else{ - Serial.printf_P(PSTR("\nOptions:[on, off]\n")); + Serial.printf_P(PSTR("\nOp:[on, off]\n")); report_optflow(); return 0; } @@ -801,12 +801,12 @@ setup_optflow(uint8_t argc, const Menu::arg *argv) static void report_batt_monitor() { - Serial.printf_P(PSTR("\nBatt Mointor\n")); + Serial.printf_P(PSTR("\nBatt Mon:\n")); print_divider(); if(g.battery_monitoring == 0) print_enabled(false); - if(g.battery_monitoring == 1) Serial.printf_P(PSTR("3 cells")); - if(g.battery_monitoring == 2) Serial.printf_P(PSTR("4 cells")); - if(g.battery_monitoring == 3) Serial.printf_P(PSTR("batt volts")); + if(g.battery_monitoring == 1) Serial.printf_P(PSTR("3c")); + if(g.battery_monitoring == 2) Serial.printf_P(PSTR("4c")); + if(g.battery_monitoring == 3) Serial.printf_P(PSTR("volts")); if(g.battery_monitoring == 4) Serial.printf_P(PSTR("volts and cur")); print_blanks(2); } @@ -897,7 +897,7 @@ static void report_compass() Vector3f offsets = compass.get_offsets(); // mag offsets - Serial.printf_P(PSTR("Mag offsets: %4.4f, %4.4f, %4.4f"), + Serial.printf_P(PSTR("Mag off: %4.4f, %4.4f, %4.4f"), offsets.x, offsets.y, offsets.z); @@ -964,7 +964,7 @@ static void report_heli() static void report_gyro() { - Serial.printf_P(PSTR("External Gyro:\n")); + Serial.printf_P(PSTR("Gyro:\n")); print_divider(); print_enabled( g.heli_ext_gyro_enabled ); @@ -1018,7 +1018,7 @@ print_switch(byte p, byte m, bool b) static void print_done() { - Serial.printf_P(PSTR("\nSaved Settings\n\n")); + Serial.printf_P(PSTR("\nSaved\n")); } @@ -1038,7 +1038,7 @@ static void zero_eeprom(void) static void print_accel_offsets(void) { - Serial.printf_P(PSTR("Accel offsets: %4.2f, %4.2f, %4.2f\n"), + Serial.printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\n"), (float)imu.ax(), (float)imu.ay(), (float)imu.az()); @@ -1047,7 +1047,7 @@ print_accel_offsets(void) static void print_gyro_offsets(void) { - Serial.printf_P(PSTR("Gyro offsets: %4.2f, %4.2f, %4.2f\n"), + Serial.printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"), (float)imu.gx(), (float)imu.gy(), (float)imu.gz()); @@ -1147,7 +1147,7 @@ static void print_wp(struct Location *cmd, byte index) float t1 = (float)cmd->lat / t7; float t2 = (float)cmd->lng / t7; - Serial.printf_P(PSTR("scommand #: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"), + Serial.printf_P(PSTR("cmd#: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"), (int)index, (int)cmd->id, (int)cmd->options, @@ -1167,7 +1167,7 @@ static void report_gps() static void report_version() { - Serial.printf_P(PSTR("FW Version %d\n"),(int)g.format_version.get()); + Serial.printf_P(PSTR("FW Ver: %d\n"),(int)g.format_version.get()); print_divider(); print_blanks(2); } From 8e1f311c366aa577c570fcda0154ca15bea906e2 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:01:47 -0800 Subject: [PATCH 11/63] s shortened strings, logging defines updated --- ArduCopter/system.pde | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 277bfcbd4e..5d3fa52c67 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -217,12 +217,10 @@ static void init_ardupilot() #ifdef USERHOOK_INIT USERHOOK_INIT #endif - // Logging: - // -------- - // DataFlash log initialization -#if LOGGING_ENABLED == ENABLED + + #if LOGGING_ENABLED == ENABLED DataFlash.Init(); -#endif + #endif #if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED // If the switch is in 'menu' mode, run the main menu. @@ -237,20 +235,21 @@ static void init_ardupilot() run_cli(); } #else - Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n")); + Serial.printf_P(PSTR("\nPress ENTER 3 times for CLI\n\n")); #endif // CLI_ENABLED if(g.esc_calibrate == 1){ init_esc(); } - // Logging: - // -------- + #if LOGGING_ENABLED == ENABLED if(g.log_bitmask != 0){ // TODO - Here we will check on the length of the last log // We don't want to create a bunch of little logs due to powering on and off + Serial.printf("start_new_log"); start_new_log(); } + #endif GPS_enabled = false; From eef04a5a5401868e41bc5fd4f07b3c9b2a2729e8 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:02:00 -0800 Subject: [PATCH 12/63] removed some tests --- ArduCopter/test.pde | 63 ++++++++++++++++++++++++--------------------- 1 file changed, 33 insertions(+), 30 deletions(-) diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index e214f5d770..5a5b3e2568 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -4,13 +4,13 @@ // These are function definitions so the Menu can be constructed before the functions // are defined below. Order matters to the compiler. -static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv); +//static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv); static int8_t test_radio(uint8_t argc, const Menu::arg *argv); //static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv); //static int8_t test_stabilize(uint8_t argc, const Menu::arg *argv); static int8_t test_gps(uint8_t argc, const Menu::arg *argv); -static int8_t test_tri(uint8_t argc, const Menu::arg *argv); -static int8_t test_adc(uint8_t argc, const Menu::arg *argv); +//static int8_t test_tri(uint8_t argc, const Menu::arg *argv); +//static int8_t test_adc(uint8_t argc, const Menu::arg *argv); static int8_t test_imu(uint8_t argc, const Menu::arg *argv); //static int8_t test_dcm(uint8_t argc, const Menu::arg *argv); //static int8_t test_omega(uint8_t argc, const Menu::arg *argv); @@ -21,7 +21,7 @@ static int8_t test_battery(uint8_t argc, const Menu::arg *argv); //static int8_t test_reverse(uint8_t argc, const Menu::arg *argv); static int8_t test_tuning(uint8_t argc, const Menu::arg *argv); static int8_t test_current(uint8_t argc, const Menu::arg *argv); -static int8_t test_relay(uint8_t argc, const Menu::arg *argv); +//static int8_t test_relay(uint8_t argc, const Menu::arg *argv); static int8_t test_wp(uint8_t argc, const Menu::arg *argv); static int8_t test_baro(uint8_t argc, const Menu::arg *argv); //static int8_t test_mag(uint8_t argc, const Menu::arg *argv); @@ -54,22 +54,22 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv); // User enters the string in the console to call the functions on the right. // See class Menu in AP_Coommon for implementation details const struct Menu::command test_menu_commands[] PROGMEM = { - {"pwm", test_radio_pwm}, +// {"pwm", test_radio_pwm}, {"radio", test_radio}, // {"failsafe", test_failsafe}, // {"stabilize", test_stabilize}, {"gps", test_gps}, #if HIL_MODE != HIL_MODE_ATTITUDE - {"adc", test_adc}, +// {"adc", test_adc}, #endif {"imu", test_imu}, //{"dcm", test_dcm}, //{"omega", test_omega}, {"battery", test_battery}, {"tune", test_tuning}, - {"tri", test_tri}, + //{"tri", test_tri}, {"current", test_current}, - {"relay", test_relay}, +// {"relay", test_relay}, {"wp", test_wp}, //{"nav", test_nav}, #if HIL_MODE != HIL_MODE_ATTITUDE @@ -82,7 +82,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = { #endif //{"xbee", test_xbee}, {"eedump", test_eedump}, - {"rawgps", test_rawgps}, +// {"rawgps", test_rawgps}, // {"mission", test_mission}, //{"reverse", test_reverse}, //{"wp", test_wp_nav}, @@ -114,8 +114,8 @@ test_eedump(uint8_t argc, const Menu::arg *argv) return(0); } -static int8_t -test_radio_pwm(uint8_t argc, const Menu::arg *argv) +/*static int8_t +//test_radio_pwm(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); delay(1000); @@ -144,10 +144,10 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv) return (0); } } -} +}*/ -static int8_t -test_tri(uint8_t argc, const Menu::arg *argv) +/*static int8_t +//test_tri(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); delay(1000); @@ -171,11 +171,11 @@ test_tri(uint8_t argc, const Menu::arg *argv) return (0); } } -} +}*/ /* static int8_t -test_nav(uint8_t argc, const Menu::arg *argv) +//test_nav(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); delay(1000); @@ -248,7 +248,7 @@ test_radio(uint8_t argc, const Menu::arg *argv) /* static int8_t -test_failsafe(uint8_t argc, const Menu::arg *argv) +//test_failsafe(uint8_t argc, const Menu::arg *argv) { #if THROTTLE_FAILSAFE @@ -303,7 +303,7 @@ test_failsafe(uint8_t argc, const Menu::arg *argv) */ /*static int8_t -test_stabilize(uint8_t argc, const Menu::arg *argv) +//test_stabilize(uint8_t argc, const Menu::arg *argv) { static byte ts_num; @@ -390,9 +390,10 @@ test_stabilize(uint8_t argc, const Menu::arg *argv) } } */ -#if HIL_MODE != HIL_MODE_ATTITUDE + +/*#if HIL_MODE != HIL_MODE_ATTITUDE static int8_t -test_adc(uint8_t argc, const Menu::arg *argv) +//test_adc(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); Serial.printf_P(PSTR("ADC\n")); @@ -410,6 +411,7 @@ test_adc(uint8_t argc, const Menu::arg *argv) } } #endif +*/ static int8_t test_imu(uint8_t argc, const Menu::arg *argv) @@ -709,8 +711,9 @@ test_current(uint8_t argc, const Menu::arg *argv) } } +/* static int8_t -test_relay(uint8_t argc, const Menu::arg *argv) +//test_relay(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); delay(1000); @@ -731,7 +734,7 @@ test_relay(uint8_t argc, const Menu::arg *argv) } } } - +*/ static int8_t test_wp(uint8_t argc, const Menu::arg *argv) { @@ -754,7 +757,7 @@ test_wp(uint8_t argc, const Menu::arg *argv) return (0); } -static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) { +//static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) { /* print_hit_enter(); delay(1000); @@ -774,10 +777,10 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv) { } } */ - } + //} /*static int8_t -test_xbee(uint8_t argc, const Menu::arg *argv) +//test_xbee(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); delay(1000); @@ -823,7 +826,7 @@ test_baro(uint8_t argc, const Menu::arg *argv) /* static int8_t -test_mag(uint8_t argc, const Menu::arg *argv) +//test_mag(uint8_t argc, const Menu::arg *argv) { if(g.compass_enabled) { //Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION); @@ -854,7 +857,7 @@ test_mag(uint8_t argc, const Menu::arg *argv) */ /* static int8_t -test_reverse(uint8_t argc, const Menu::arg *argv) +//test_reverse(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); delay(1000); @@ -952,7 +955,7 @@ test_optflow(uint8_t argc, const Menu::arg *argv) /* static int8_t -test_mission(uint8_t argc, const Menu::arg *argv) +//test_mission(uint8_t argc, const Menu::arg *argv) { //write out a basic mission to the EEPROM @@ -1017,7 +1020,7 @@ static void print_hit_enter() } /* -static void fake_out_gps() +//static void fake_out_gps() { static float rads; g_gps->new_data = true; @@ -1040,7 +1043,7 @@ static void fake_out_gps() */ /* -static void print_motor_out(){ +//static void print_motor_out(){ Serial.printf("out: R: %d, L: %d F: %d B: %d\n", (motor_out[CH_1] - g.rc_3.radio_min), (motor_out[CH_2] - g.rc_3.radio_min), From 7ffa2c4347b6674208e924df7e5633b6b9cd2cc7 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:02:45 -0800 Subject: [PATCH 13/63] shortened strings --- ArduPlane/Log.pde | 91 ++++++++++++++++++++++++----------------------- 1 file changed, 46 insertions(+), 45 deletions(-) diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 78576d053c..fee3d4d745 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -5,9 +5,9 @@ // Code to Write and Read packets from DataFlash log memory // Code to interact with the user to dump or erase logs -#define HEAD_BYTE1 0xA3 // Decimal 163 -#define HEAD_BYTE2 0x95 // Decimal 149 -#define END_BYTE 0xBA // Decimal 186 +#define HEAD_BYTE1 0xA3 // Decimal 163 +#define HEAD_BYTE2 0x95 // Decimal 149 +#define END_BYTE 0xBA // Decimal 186 // These are function definitions so the Menu can be constructed before the functions @@ -19,17 +19,17 @@ static int8_t select_logs(uint8_t argc, const Menu::arg *argv); // This is the help function // PSTR is an AVR macro to read strings from flash memory // printf_P is a version of print_f that reads from flash memory -static int8_t help_log(uint8_t argc, const Menu::arg *argv) -{ +//static int8_t help_log(uint8_t argc, const Menu::arg *argv) +/*{ Serial.printf_P(PSTR("\n" "Commands:\n" - " dump dump log \n" - " erase erase all logs\n" - " enable |all enable logging or everything\n" - " disable |all disable logging or everything\n" + " dump " + " erase (all logs)\n" + " enable | all\n" + " disable | all\n" "\n")); return 0; -} +}*/ // Creates a constant array of structs representing menu options // and stores them in Flash memory, not RAM. @@ -39,8 +39,7 @@ static const struct Menu::command log_menu_commands[] PROGMEM = { {"dump", dump_log}, {"erase", erase_logs}, {"enable", select_logs}, - {"disable", select_logs}, - {"help", help_log} + {"disable", select_logs} }; // A Macro to create the Menu @@ -58,6 +57,7 @@ print_log_menu(void) //Serial.print("num logs: "); Serial.println(num_logs, DEC); Serial.printf_P(PSTR("logs enabled: ")); + if (0 == g.log_bitmask) { Serial.printf_P(PSTR("none")); }else{ @@ -78,18 +78,18 @@ print_log_menu(void) PLOG(CUR); #undef PLOG } + Serial.println(); if (num_logs == 0) { - Serial.printf_P(PSTR("\nNo logs available for download\n")); + Serial.printf_P(PSTR("\nNo logs\nType 'dump 0'.\n\n")); }else{ + Serial.printf_P(PSTR("\n%d logs\n"), num_logs); - Serial.printf_P(PSTR("\n%d logs available for download\n"), num_logs); for(int i=num_logs;i>=1;i--) { temp = g.log_last_filenumber-i+1; get_log_boundaries(temp, log_start, log_end); - Serial.printf_P(PSTR("Log number %d, start page %d, end page %d\n"), - temp, log_start, log_end); + Serial.printf_P(PSTR("Log %d, start %d, end %d\n"), temp, log_start, log_end); } Serial.println(); } @@ -137,7 +137,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv) DataFlash.StartWrite(j); // We need this step to clean FileNumbers } g.log_last_filenumber.set_and_save(0); - + Serial.printf_P(PSTR("\nLog erased.\n")); return 0; } @@ -189,7 +189,7 @@ static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { log_menu.run(); - return 0; + return 0; } @@ -202,10 +202,10 @@ static byte get_num_logs(void) uint16_t first; if(g.log_last_filenumber < 1) return 0; - + DataFlash.StartRead(1); if(DataFlash.GetFileNumber() == 0XFFFF) return 0; - + lastpage = find_last(); DataFlash.StartRead(lastpage); last = DataFlash.GetFileNumber(); @@ -215,18 +215,18 @@ static byte get_num_logs(void) DataFlash.StartRead(1); first = DataFlash.GetFileNumber(); } - if(last == first) + if(last == first) { return 1; } else { return (last - first + 1); } } - + // This function starts a new log file in the DataFlash static void start_new_log() { -uint16_t last_page; + uint16_t last_page; if(g.log_last_filenumber < 1) { last_page = 0; @@ -246,7 +246,7 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page) if(num == 1) { DataFlash.StartRead(DF_LAST_PAGE); - if(DataFlash.GetFileNumber() == 0xFFFF) + if(DataFlash.GetFileNumber() == 0xFFFF) { start_page = 1; end_page = find_last_log_page((uint16_t)log_num); @@ -254,7 +254,7 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page) end_page = find_last_log_page((uint16_t)log_num); start_page = end_page + 1; } - + } else { end_page = find_last_log_page((uint16_t)log_num); if(log_num==1) @@ -268,13 +268,13 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page) } if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1; } - + // This function finds the last page of the last file // It also cleans up in the situation where a file was initiated, but no pages written static int find_last(void) { int16_t num; - do + do { num = find_last_log_page(g.log_last_filenumber); if (num == -1) g.log_last_filenumber.set_and_save(g.log_last_filenumber - 1); @@ -296,18 +296,18 @@ static int find_last_log_page(uint16_t log_number) int16_t look_page_filepage; int16_t check; bool XLflag = false; - + // First see if the logs are empty DataFlash.StartRead(1); if(DataFlash.GetFileNumber() == 0XFFFF) { return 0; } - + // Next, see if logs wrap the top of the dataflash DataFlash.StartRead(DF_LAST_PAGE); if(DataFlash.GetFileNumber() == 0xFFFF) { - // This case is that we have not wrapped the top of the dataflash + // This case is that we have not wrapped the top of the dataflash top_page = DF_LAST_PAGE; bottom_page = 1; while((top_page - bottom_page) > 1) { @@ -315,11 +315,11 @@ static int find_last_log_page(uint16_t log_number) DataFlash.StartRead(look_page); if(DataFlash.GetFileNumber() > log_number) top_page = look_page; - else + else bottom_page = look_page; } return bottom_page; - + } else { // The else case is that the logs do wrap the top of the dataflash bottom_page = 1; @@ -330,17 +330,17 @@ static int find_last_log_page(uint16_t log_number) DataFlash.StartRead(top_page); top_page_file = DataFlash.GetFileNumber(); top_page_filepage = DataFlash.GetFilePage(); - + // Check is we have exactly filled the dataflash but not wrapped. If so we can exit quickly. if(top_page_file == log_number && bottom_page_file != log_number) { return top_page_file; } - + // Check if the top is 1 file higher than we want. If so we can exit quickly. if(top_page_file == log_number+1) { return top_page - top_page_filepage; } - + // Check if the file has partially overwritten itself if(top_page_filepage >= DF_LAST_PAGE) { XLflag = true; @@ -363,13 +363,13 @@ static int find_last_log_page(uint16_t log_number) { top_page = look_page; top_page_filepage = DataFlash.GetFilePage(); - } else { + } else { bottom_page = look_page; } } return bottom_page; } - + // Step down through the files to find the one we want bottom_page = top_page; @@ -383,22 +383,22 @@ static int find_last_log_page(uint16_t log_number) bottom_page_file = DataFlash.GetFileNumber(); bottom_page_filepage = DataFlash.GetFilePage(); } while (bottom_page_file != log_number && bottom_page != 1); - + // Deal with stepping down too far due to overwriting a file while((top_page - bottom_page) > 1) { look_page = (top_page + bottom_page) / 2; DataFlash.StartRead(look_page); if(DataFlash.GetFileNumber() < log_number) top_page = look_page; - else + else bottom_page = look_page; } - + // The -1 return is for the case where a very short power up increments the log - // number counter but no log file is actually created. This happens if power is + // number counter but no log file is actually created. This happens if power is // removed before the first page is written to flash. if(bottom_page ==1 && DataFlash.GetFileNumber() != log_number) return -1; - + return bottom_page; } } @@ -724,14 +724,14 @@ static void Log_Read_Raw() static void Log_Read(int start_page, int end_page) { int packet_count = 0; - + #ifdef AIRFRAME_NAME Serial.printf_P(PSTR((AIRFRAME_NAME) #endif Serial.printf_P(PSTR("\n" THISFIRMWARE "\nFree RAM: %u\n"), memcheck_available_memory()); - + if(start_page > end_page) { packet_count = Log_Read_Process(start_page, DF_LAST_PAGE); @@ -739,7 +739,7 @@ static void Log_Read(int start_page, int end_page) } else { packet_count = Log_Read_Process(start_page, end_page); } - + Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count); } @@ -754,6 +754,7 @@ static int Log_Read_Process(int start_page, int end_page) DataFlash.StartRead(start_page); while (page < end_page && page != -1){ data = DataFlash.ReadByte(); + switch(log_step) // This is a state machine to read the packets { case 0: From f345c4c9879e296de11aee9855243c2affe7e45e Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:03:08 -0800 Subject: [PATCH 14/63] Checking for climb rate --- Tools/autotest/common.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 0888533f73..3296f23332 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -63,12 +63,18 @@ def current_location(mav): mav.messages['VFR_HUD'].alt) def wait_altitude(mav, alt_min, alt_max, timeout=30): + climb_rate = 0 + previous_alt = 0 '''wait for a given altitude range''' tstart = time.time() print("Waiting for altitude between %u and %u" % (alt_min, alt_max)) while time.time() < tstart + timeout: m = mav.recv_match(type='VFR_HUD', blocking=True) - print("Altitude %u" % m.alt) + climb_rate = m.alt - previous_alt + previous_alt = m.alt + print("Altitude %u, rate: %u" % (m.alt, climb_rate)) + if abs(climb_rate) > 0: + tstart = time.time(); if m.alt >= alt_min and m.alt <= alt_max: return True print("Failed to attain altitude range") From 2d5ee0f7e26844a49717f2f0e75bf60777744da4 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:03:26 -0800 Subject: [PATCH 15/63] Switched to Mission 2 --- Tools/autotest/arducopter.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 548baf9311..b523e70148 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -326,19 +326,19 @@ def fly_ArduCopter(viewerip=None): failed = True print("# Upload mission1") - if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission1.txt")): + if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission2.txt")): failed = True # this grabs our mission count print("# store mission1 locally") - if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission1.txt")): + if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "mission2.txt")): failed = True - print("# Fly mission 1") + print("# Fly mission 2") if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10): failed = True else: - print("Flew mission1 OK") + print("Flew mission2 OK") print("# Land") if not land(mavproxy, mav): From b6adfdb62f7e6150910b38b8f9e38a37f0177f87 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:42:57 -0800 Subject: [PATCH 16/63] missed == --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index c7387f8ec1..09b3f64b50 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1249,7 +1249,7 @@ static void update_altitude() baro_alt = (baro_alt + read_barometer()) >> 1; // calc the vertical accel rate - #if CLIMB_RATE_BARO = 1 + #if CLIMB_RATE_BARO == 1 int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale baro_rate = (temp_baro_alt - old_baro_alt) * 10; old_baro_alt = temp_baro_alt; From 9e04d4c45b9865419b228935eefab6057fe1924f Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 14:59:48 -0800 Subject: [PATCH 17/63] longer timeout --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b523e70148..0a69efde32 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -175,7 +175,7 @@ def fly_mission(mavproxy, mav, height_accuracy=-1, target_altitude=None): mavproxy.send('switch 4\n') # auto mode wait_mode(mav, 'AUTO') #wait_altitude(mav, 30, 40) - ret = wait_waypoint(mav, 0, num_wp, timeout=90) + ret = wait_waypoint(mav, 0, num_wp, timeout=500) print("test: MISSION COMPLETE: passed=%s" % ret) # wait here until ready mavproxy.send('switch 5\n') From b3716d988f049ab6c0b938307fb7eb9a32e7c02f Mon Sep 17 00:00:00 2001 From: analoguedevices Date: Sat, 19 Nov 2011 23:43:47 +0000 Subject: [PATCH 18/63] Rev version number --- ArduPlane/ArduPlane.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 8c1927950c..1e35110235 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduPlane V2.251" +#define THISFIRMWARE "ArduPlane V2.26" /* Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi From 202c0663cd56c607aec1f03243a6d13fc1c35ec5 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sun, 20 Nov 2011 07:46:05 +0800 Subject: [PATCH 19/63] firmware build --- .../Firmware/AP-1280.build.log | 15 +++++- .../Firmware/AP-1280.size.txt | 54 +++++++++---------- .../Firmware/AP-2560.build.log | 15 +++++- .../Firmware/AP-2560.size.txt | 54 +++++++++---------- .../Firmware/AP-trunk-1280.build.log | 15 +++++- .../Firmware/AP-trunk-1280.size.txt | 54 +++++++++---------- .../Firmware/AP-trunk-2560.build.log | 15 +++++- .../Firmware/AP-trunk-2560.size.txt | 54 +++++++++---------- .../Firmware/APHIL-1280.build.log | 12 ++--- .../Firmware/APHIL-1280.size.txt | 2 +- .../Firmware/APHIL-2560.build.log | 12 ++--- .../Firmware/APHIL-2560.size.txt | 2 +- .../Firmware/firmware2.xml | 26 ++++----- Tools/ArdupilotMegaPlanner/Firmware/git.log | 45 +++++++--------- 14 files changed, 205 insertions(+), 170 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.build.log index 04aff58873..f9e9bb49a7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.build.log @@ -3,10 +3,21 @@ In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition +/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)': +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check' +/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope: /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used -autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined +autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used -autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined +autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.size.txt index 9b8f40b39e..0d2952bfa6 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.size.txt @@ -219,6 +219,7 @@ 0000000a r init_home()::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r verify_nav_wp()::__c +0000000a r print_log_menu()::__c 0000000a r report_compass()::__c 0000000a r report_throttle()::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c @@ -283,6 +284,7 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -343,6 +345,7 @@ 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 b rc_override 00000010 r planner_menu_commands +00000010 r __menu_name__main_menu 00000010 T GCS_MAVLINK::send_message(ap_message) 00000010 W AP_VarT::cast_to_float() const 00000010 W AP_VarT::cast_to_float() const @@ -351,7 +354,6 @@ 00000010 r Log_Read_Startup()::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c -00000011 r __menu_name__main_menu 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c @@ -420,10 +422,11 @@ 00000019 r handle_process_do_command()::__c 00000019 r handle_process_condition_command()::__c 00000019 r do_jump()::__c +0000001a r print_log_menu()::__c +0000001a r Log_Read_Process(int, int)::__c 0000001a r failsafe_short_on_event()::__c 0000001a r do_jump()::__c 0000001a r do_jump()::__c -0000001a r Log_Read(int, int)::__c 0000001b r failsafe_short_off_event()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -433,25 +436,25 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c r Log_Read_Current()::__c -0000001c r Log_Read(int, int)::__c +0000001c r Log_Read_Process(int, int)::__c 0000001c r Log_Read(int, int)::__c 0000001d r setup_radio(unsigned char, Menu::arg const*)::__c 0000001d r startup_ground()::__c 0000001d r report_batt_monitor()::__c +0000001e t update_commands() 0000001e r flight_mode_strings 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r startup_ground()::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r init_ardupilot()::__c +0000001f r print_log_menu()::__c +0000001f r Log_Read(int, int)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r report_xtrack()::__c 00000020 r init_barometer()::__c -00000020 r Log_Read(int, int)::__c 00000020 t byte_swap_4 -00000021 r print_log_menu()::__c -00000021 r print_log_menu()::__c 00000021 r verify_loiter_time()::__c 00000021 r process_next_command()::__c 00000022 t print_blanks(int) @@ -478,12 +481,11 @@ 00000026 t print_done() 00000026 t print_hit_enter() 00000026 r init_ardupilot()::__c +00000026 r init_ardupilot()::__c 00000026 r print_PID(PID*)::__c 00000027 r change_command(unsigned char)::__c -00000027 r init_ardupilot()::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t main_menu_help(unsigned char, Menu::arg const*) -00000028 t help_log(unsigned char, Menu::arg const*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const @@ -504,8 +506,6 @@ 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000030 t test_mode(unsigned char, Menu::arg const*) -00000030 r print_log_menu()::__c -00000031 r start_new_log(unsigned char)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000033 b pending_status @@ -516,10 +516,10 @@ 00000035 r Log_Read_Nav_Tuning()::__c 00000035 r verify_condition_command()::__c 00000036 t report_radio() +00000036 t find_last() 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000038 t send_current_waypoint(mavlink_channel_t) -00000038 b barometer 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c @@ -530,11 +530,13 @@ 0000003a W PID::~PID() 0000003c t verify_RTL() 0000003c t Log_Write_Mode(unsigned char) +0000003c b barometer 0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003d B g_gps_driver 0000003e T 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 r log_menu_commands 00000040 b adc 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 t byte_swap_8 @@ -552,7 +554,6 @@ 0000004c t Log_Read_Mode() 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -566,7 +567,6 @@ 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005b r setup_erase(unsigned char, Menu::arg const*)::__c 0000005c t readSwitch() -0000005c t get_num_logs() 0000005e T GCS_MAVLINK::_count_parameters() 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000062 t print_switch(unsigned char, unsigned char) @@ -575,7 +575,6 @@ 00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 W RC_Channel_aux::~RC_Channel_aux() 00000068 t zero_eeprom() -00000068 t find_last_log_page(int) 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 0000006a t demo_servos(unsigned char) 0000006a t startup_IMU_ground() @@ -609,6 +608,7 @@ 0000009c t print_PID(PID*) 0000009c B gcs0 0000009c B gcs3 +0000009e t get_num_logs() 000000a0 t report_xtrack() 000000a2 t verify_nav_wp() 000000a4 t Log_Read_Cmd() @@ -619,15 +619,16 @@ 000000ac t Log_Read_Performance() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t Log_Read_Startup() -000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 b compass 000000bc t Log_Read_Control_Tuning() 000000be t update_events() 000000c0 t report_throttle() 000000c0 t calc_bearing_error() +000000c4 t Log_Read(int, int) 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t zero_airspeed() 000000c6 t startup_ground() +000000c6 t get_log_boundaries(unsigned char, int&, int&) 000000c7 B dcm 000000ca t send_radio_out(mavlink_channel_t) 000000ca t test_modeswitch(unsigned char, Menu::arg const*) @@ -635,15 +636,15 @@ 000000ce t send_radio_in(mavlink_channel_t) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c -000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000d0 t get_bearing(Location*, Location*) 000000d4 t trim_radio() 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e7 r init_ardupilot()::__c -000000ec t dump_log(unsigned char, Menu::arg const*) 000000f0 t throttle_slew_limit() 000000f2 t test_adc(unsigned char, Menu::arg const*) +000000f6 t erase_logs(unsigned char, Menu::arg const*) 000000fa t Log_Read_Current() +000000fc t dump_log(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t calc_nav_pitch() @@ -658,7 +659,6 @@ 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000114 t read_barometer() -00000116 t erase_logs(unsigned char, Menu::arg const*) 00000118 t test_gps(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*) 00000130 t test_dipswitches(unsigned char, Menu::arg const*) @@ -674,6 +674,7 @@ 00000152 t verify_condition_command() 0000015a t test_airspeed(unsigned char, Menu::arg const*) 0000015e t set_guided_WP() +0000015e t Log_Read_Process(int, int) 0000015e t handle_process_nav_cmd() 0000015e t test_gyro(unsigned char, Menu::arg const*) 0000016c t navigate() @@ -682,12 +683,11 @@ 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) 0000017c t send_location(mavlink_channel_t) 0000017e t Log_Read_Nav_Tuning() -00000180 t send_extended_status1(mavlink_channel_t, unsigned int) +0000017e t send_extended_status1(mavlink_channel_t, unsigned int) 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000192 T init_home() 00000192 t test_imu(unsigned char, Menu::arg const*) 0000019c t do_jump() -000001ae t start_new_log(unsigned char) 000001b2 t update_crosstrack() 000001b2 t set_mode(unsigned char) 000001bc t set_next_WP(Location*) @@ -700,7 +700,6 @@ 000001ea t init_barometer() 00000202 t test_failsafe(unsigned char, Menu::arg const*) 00000208 t calc_throttle() -00000216 t Log_Read(int, int) 0000021a t send_raw_imu1(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t) 0000022c t process_next_command() @@ -710,16 +709,17 @@ 0000024c t update_loiter() 0000025c t setup_radio(unsigned char, Menu::arg const*) 00000268 t send_raw_imu3(mavlink_channel_t) +00000268 t find_last_log_page(unsigned int) 000002d4 t handle_process_do_command() 000002e4 t read_radio() 0000031e t test_mag(unsigned char, Menu::arg const*) -0000033a W Parameters::~Parameters() +00000344 W Parameters::~Parameters() 000003e6 t read_battery() -0000044c t print_log_menu() +00000462 t print_log_menu() 000004de t set_servos() 0000059c t __static_initialization_and_destruction_0(int, int) -0000064a t init_ardupilot() -00000920 W Parameters::Parameters() -0000092b b g +00000694 t init_ardupilot() +00000936 W Parameters::Parameters() +00000938 b g 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001cbe T loop +00001caa T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.build.log index 04aff58873..f9e9bb49a7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.build.log @@ -3,10 +3,21 @@ In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition +/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)': +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check' +/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope: /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used -autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined +autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used -autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined +autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.size.txt index 0fa674eeaf..7f638d6508 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.size.txt @@ -219,6 +219,7 @@ 0000000a r init_home()::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r verify_nav_wp()::__c +0000000a r print_log_menu()::__c 0000000a r report_compass()::__c 0000000a r report_throttle()::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c @@ -283,6 +284,7 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -343,6 +345,7 @@ 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 b rc_override 00000010 r planner_menu_commands +00000010 r __menu_name__main_menu 00000010 T GCS_MAVLINK::send_message(ap_message) 00000010 W AP_VarT::cast_to_float() const 00000010 W AP_VarT::cast_to_float() const @@ -351,7 +354,6 @@ 00000010 r Log_Read_Startup()::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c -00000011 r __menu_name__main_menu 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c @@ -420,10 +422,11 @@ 00000019 r handle_process_do_command()::__c 00000019 r handle_process_condition_command()::__c 00000019 r do_jump()::__c +0000001a r print_log_menu()::__c +0000001a r Log_Read_Process(int, int)::__c 0000001a r failsafe_short_on_event()::__c 0000001a r do_jump()::__c 0000001a r do_jump()::__c -0000001a r Log_Read(int, int)::__c 0000001b r failsafe_short_off_event()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -433,25 +436,25 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c r Log_Read_Current()::__c -0000001c r Log_Read(int, int)::__c +0000001c r Log_Read_Process(int, int)::__c 0000001c r Log_Read(int, int)::__c 0000001d r setup_radio(unsigned char, Menu::arg const*)::__c 0000001d r startup_ground()::__c 0000001d r report_batt_monitor()::__c +0000001e t update_commands() 0000001e r flight_mode_strings 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r startup_ground()::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r init_ardupilot()::__c +0000001f r print_log_menu()::__c +0000001f r Log_Read(int, int)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r report_xtrack()::__c 00000020 r init_barometer()::__c -00000020 r Log_Read(int, int)::__c 00000020 t byte_swap_4 -00000021 r print_log_menu()::__c -00000021 r print_log_menu()::__c 00000021 r verify_loiter_time()::__c 00000021 r process_next_command()::__c 00000022 t print_blanks(int) @@ -478,12 +481,11 @@ 00000026 t print_done() 00000026 t print_hit_enter() 00000026 r init_ardupilot()::__c +00000026 r init_ardupilot()::__c 00000026 r print_PID(PID*)::__c 00000027 r change_command(unsigned char)::__c -00000027 r init_ardupilot()::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t main_menu_help(unsigned char, Menu::arg const*) -00000028 t help_log(unsigned char, Menu::arg const*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const @@ -504,8 +506,6 @@ 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000030 t test_mode(unsigned char, Menu::arg const*) -00000030 r print_log_menu()::__c -00000031 r start_new_log(unsigned char)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000033 b pending_status @@ -516,10 +516,10 @@ 00000035 r Log_Read_Nav_Tuning()::__c 00000035 r verify_condition_command()::__c 00000036 t report_radio() +00000036 t find_last() 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000038 t send_current_waypoint(mavlink_channel_t) -00000038 b barometer 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c @@ -530,11 +530,13 @@ 0000003a W PID::~PID() 0000003c t verify_RTL() 0000003c t Log_Write_Mode(unsigned char) +0000003c b barometer 0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003d B g_gps_driver 0000003e T 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 r log_menu_commands 00000040 b adc 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 t byte_swap_8 @@ -552,7 +554,6 @@ 0000004c t Log_Read_Mode() 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -566,7 +567,6 @@ 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005b r setup_erase(unsigned char, Menu::arg const*)::__c 0000005c t readSwitch() -0000005c t get_num_logs() 0000005e T GCS_MAVLINK::_count_parameters() 00000060 t print_switch(unsigned char, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) @@ -575,7 +575,6 @@ 00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 W RC_Channel_aux::~RC_Channel_aux() 00000068 t zero_eeprom() -00000068 t find_last_log_page(int) 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 0000006a t demo_servos(unsigned char) 0000006a t startup_IMU_ground() @@ -609,6 +608,7 @@ 0000009c t print_PID(PID*) 0000009c B gcs0 0000009c B gcs3 +0000009e t get_num_logs() 000000a0 t report_xtrack() 000000a2 t verify_nav_wp() 000000a4 t Log_Read_Cmd() @@ -619,31 +619,32 @@ 000000ac t Log_Read_Performance() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t Log_Read_Startup() -000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 b compass 000000bc t Log_Read_Control_Tuning() 000000be t update_events() 000000c0 t report_throttle() 000000c0 t calc_bearing_error() +000000c0 t Log_Read(int, int) 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t zero_airspeed() 000000c6 t startup_ground() 000000c7 B dcm 000000c8 t test_modeswitch(unsigned char, Menu::arg const*) +000000c8 t get_log_boundaries(unsigned char, int&, int&) 000000ca t send_radio_out(mavlink_channel_t) 000000ca t control_failsafe(unsigned int) 000000ce t send_radio_in(mavlink_channel_t) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c -000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000d0 t get_bearing(Location*, Location*) 000000d4 t trim_radio() 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e7 r init_ardupilot()::__c -000000ec t dump_log(unsigned char, Menu::arg const*) 000000f0 t throttle_slew_limit() 000000f0 t test_adc(unsigned char, Menu::arg const*) +000000f4 t erase_logs(unsigned char, Menu::arg const*) 000000fa t Log_Read_Current() +000000fc t dump_log(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t calc_nav_pitch() @@ -657,7 +658,6 @@ 00000112 t report_batt_monitor() 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) -00000114 t erase_logs(unsigned char, Menu::arg const*) 00000114 t read_barometer() 00000118 t test_gps(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*) @@ -673,6 +673,7 @@ 00000152 t report_gains() 00000152 t verify_condition_command() 00000158 t test_airspeed(unsigned char, Menu::arg const*) +0000015a t Log_Read_Process(int, int) 0000015e t set_guided_WP() 0000015e t handle_process_nav_cmd() 0000015e t test_gyro(unsigned char, Menu::arg const*) @@ -682,12 +683,11 @@ 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) 0000017c t send_location(mavlink_channel_t) 0000017e t Log_Read_Nav_Tuning() -00000180 t send_extended_status1(mavlink_channel_t, unsigned int) +0000017e t send_extended_status1(mavlink_channel_t, unsigned int) 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000190 T init_home() 00000192 t test_imu(unsigned char, Menu::arg const*) 0000019a t do_jump() -000001ae t start_new_log(unsigned char) 000001b2 t update_crosstrack() 000001b2 t set_mode(unsigned char) 000001bc t set_next_WP(Location*) @@ -700,7 +700,6 @@ 000001ea t init_barometer() 000001fe t test_failsafe(unsigned char, Menu::arg const*) 00000208 t calc_throttle() -00000210 t Log_Read(int, int) 0000021a t send_raw_imu1(mavlink_channel_t) 00000228 t test_wp(unsigned char, Menu::arg const*) 0000022a t send_gps_raw(mavlink_channel_t) @@ -710,16 +709,17 @@ 0000024c t update_loiter() 0000025c t setup_radio(unsigned char, Menu::arg const*) 00000268 t send_raw_imu3(mavlink_channel_t) +00000268 t find_last_log_page(unsigned int) 000002d4 t handle_process_do_command() 000002e4 t read_radio() 0000031e t test_mag(unsigned char, Menu::arg const*) -0000033a W Parameters::~Parameters() +00000344 W Parameters::~Parameters() 000003e6 t read_battery() -00000436 t print_log_menu() +0000044c t print_log_menu() 000004de t set_servos() 0000059c t __static_initialization_and_destruction_0(int, int) -00000648 t init_ardupilot() -00000920 W Parameters::Parameters() -0000092b b g +00000692 t init_ardupilot() +00000936 W Parameters::Parameters() +00000938 b g 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001cbe T loop +00001caa T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.build.log index 04aff58873..f9e9bb49a7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.build.log @@ -3,10 +3,21 @@ In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition +/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)': +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check' +/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope: /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used -autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined +autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used -autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined +autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.size.txt index 9b8f40b39e..0d2952bfa6 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.size.txt @@ -219,6 +219,7 @@ 0000000a r init_home()::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r verify_nav_wp()::__c +0000000a r print_log_menu()::__c 0000000a r report_compass()::__c 0000000a r report_throttle()::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c @@ -283,6 +284,7 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -343,6 +345,7 @@ 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 b rc_override 00000010 r planner_menu_commands +00000010 r __menu_name__main_menu 00000010 T GCS_MAVLINK::send_message(ap_message) 00000010 W AP_VarT::cast_to_float() const 00000010 W AP_VarT::cast_to_float() const @@ -351,7 +354,6 @@ 00000010 r Log_Read_Startup()::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c -00000011 r __menu_name__main_menu 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c @@ -420,10 +422,11 @@ 00000019 r handle_process_do_command()::__c 00000019 r handle_process_condition_command()::__c 00000019 r do_jump()::__c +0000001a r print_log_menu()::__c +0000001a r Log_Read_Process(int, int)::__c 0000001a r failsafe_short_on_event()::__c 0000001a r do_jump()::__c 0000001a r do_jump()::__c -0000001a r Log_Read(int, int)::__c 0000001b r failsafe_short_off_event()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -433,25 +436,25 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c r Log_Read_Current()::__c -0000001c r Log_Read(int, int)::__c +0000001c r Log_Read_Process(int, int)::__c 0000001c r Log_Read(int, int)::__c 0000001d r setup_radio(unsigned char, Menu::arg const*)::__c 0000001d r startup_ground()::__c 0000001d r report_batt_monitor()::__c +0000001e t update_commands() 0000001e r flight_mode_strings 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r startup_ground()::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r init_ardupilot()::__c +0000001f r print_log_menu()::__c +0000001f r Log_Read(int, int)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r report_xtrack()::__c 00000020 r init_barometer()::__c -00000020 r Log_Read(int, int)::__c 00000020 t byte_swap_4 -00000021 r print_log_menu()::__c -00000021 r print_log_menu()::__c 00000021 r verify_loiter_time()::__c 00000021 r process_next_command()::__c 00000022 t print_blanks(int) @@ -478,12 +481,11 @@ 00000026 t print_done() 00000026 t print_hit_enter() 00000026 r init_ardupilot()::__c +00000026 r init_ardupilot()::__c 00000026 r print_PID(PID*)::__c 00000027 r change_command(unsigned char)::__c -00000027 r init_ardupilot()::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t main_menu_help(unsigned char, Menu::arg const*) -00000028 t help_log(unsigned char, Menu::arg const*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const @@ -504,8 +506,6 @@ 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000030 t test_mode(unsigned char, Menu::arg const*) -00000030 r print_log_menu()::__c -00000031 r start_new_log(unsigned char)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000033 b pending_status @@ -516,10 +516,10 @@ 00000035 r Log_Read_Nav_Tuning()::__c 00000035 r verify_condition_command()::__c 00000036 t report_radio() +00000036 t find_last() 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000038 t send_current_waypoint(mavlink_channel_t) -00000038 b barometer 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c @@ -530,11 +530,13 @@ 0000003a W PID::~PID() 0000003c t verify_RTL() 0000003c t Log_Write_Mode(unsigned char) +0000003c b barometer 0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003d B g_gps_driver 0000003e T 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 r log_menu_commands 00000040 b adc 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 t byte_swap_8 @@ -552,7 +554,6 @@ 0000004c t Log_Read_Mode() 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -566,7 +567,6 @@ 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005b r setup_erase(unsigned char, Menu::arg const*)::__c 0000005c t readSwitch() -0000005c t get_num_logs() 0000005e T GCS_MAVLINK::_count_parameters() 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) 00000062 t print_switch(unsigned char, unsigned char) @@ -575,7 +575,6 @@ 00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 W RC_Channel_aux::~RC_Channel_aux() 00000068 t zero_eeprom() -00000068 t find_last_log_page(int) 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 0000006a t demo_servos(unsigned char) 0000006a t startup_IMU_ground() @@ -609,6 +608,7 @@ 0000009c t print_PID(PID*) 0000009c B gcs0 0000009c B gcs3 +0000009e t get_num_logs() 000000a0 t report_xtrack() 000000a2 t verify_nav_wp() 000000a4 t Log_Read_Cmd() @@ -619,15 +619,16 @@ 000000ac t Log_Read_Performance() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t Log_Read_Startup() -000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 b compass 000000bc t Log_Read_Control_Tuning() 000000be t update_events() 000000c0 t report_throttle() 000000c0 t calc_bearing_error() +000000c4 t Log_Read(int, int) 000000c6 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t zero_airspeed() 000000c6 t startup_ground() +000000c6 t get_log_boundaries(unsigned char, int&, int&) 000000c7 B dcm 000000ca t send_radio_out(mavlink_channel_t) 000000ca t test_modeswitch(unsigned char, Menu::arg const*) @@ -635,15 +636,15 @@ 000000ce t send_radio_in(mavlink_channel_t) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c -000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000d0 t get_bearing(Location*, Location*) 000000d4 t trim_radio() 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e7 r init_ardupilot()::__c -000000ec t dump_log(unsigned char, Menu::arg const*) 000000f0 t throttle_slew_limit() 000000f2 t test_adc(unsigned char, Menu::arg const*) +000000f6 t erase_logs(unsigned char, Menu::arg const*) 000000fa t Log_Read_Current() +000000fc t dump_log(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t calc_nav_pitch() @@ -658,7 +659,6 @@ 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000114 t read_barometer() -00000116 t erase_logs(unsigned char, Menu::arg const*) 00000118 t test_gps(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*) 00000130 t test_dipswitches(unsigned char, Menu::arg const*) @@ -674,6 +674,7 @@ 00000152 t verify_condition_command() 0000015a t test_airspeed(unsigned char, Menu::arg const*) 0000015e t set_guided_WP() +0000015e t Log_Read_Process(int, int) 0000015e t handle_process_nav_cmd() 0000015e t test_gyro(unsigned char, Menu::arg const*) 0000016c t navigate() @@ -682,12 +683,11 @@ 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) 0000017c t send_location(mavlink_channel_t) 0000017e t Log_Read_Nav_Tuning() -00000180 t send_extended_status1(mavlink_channel_t, unsigned int) +0000017e t send_extended_status1(mavlink_channel_t, unsigned int) 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000192 T init_home() 00000192 t test_imu(unsigned char, Menu::arg const*) 0000019c t do_jump() -000001ae t start_new_log(unsigned char) 000001b2 t update_crosstrack() 000001b2 t set_mode(unsigned char) 000001bc t set_next_WP(Location*) @@ -700,7 +700,6 @@ 000001ea t init_barometer() 00000202 t test_failsafe(unsigned char, Menu::arg const*) 00000208 t calc_throttle() -00000216 t Log_Read(int, int) 0000021a t send_raw_imu1(mavlink_channel_t) 0000022a t send_gps_raw(mavlink_channel_t) 0000022c t process_next_command() @@ -710,16 +709,17 @@ 0000024c t update_loiter() 0000025c t setup_radio(unsigned char, Menu::arg const*) 00000268 t send_raw_imu3(mavlink_channel_t) +00000268 t find_last_log_page(unsigned int) 000002d4 t handle_process_do_command() 000002e4 t read_radio() 0000031e t test_mag(unsigned char, Menu::arg const*) -0000033a W Parameters::~Parameters() +00000344 W Parameters::~Parameters() 000003e6 t read_battery() -0000044c t print_log_menu() +00000462 t print_log_menu() 000004de t set_servos() 0000059c t __static_initialization_and_destruction_0(int, int) -0000064a t init_ardupilot() -00000920 W Parameters::Parameters() -0000092b b g +00000694 t init_ardupilot() +00000936 W Parameters::Parameters() +00000938 b g 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001cbe T loop +00001caa T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.build.log index 04aff58873..f9e9bb49a7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.build.log @@ -3,10 +3,21 @@ In file included from /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:32: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition +/root/apm/ardupilot-mega/ArduPlane/Log.pde: In function 'int find_last_log_page(uint16_t)': +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:335: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:340: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:352: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:362: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:385: warning: comparison between signed and unsigned integer expressions +/root/apm/ardupilot-mega/ArduPlane/Log.pde:295: warning: unused variable 'look_page_file' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:296: warning: unused variable 'look_page_filepage' +/root/apm/ardupilot-mega/ArduPlane/Log.pde:297: warning: unused variable 'check' +/root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde: At global scope: /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used -autogenerated:87: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined +autogenerated:89: warning: 'void add_altitude_data(long unsigned int, long int)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/commands.pde:128: warning: 'void increment_cmd_index()' defined but not used -autogenerated:144: warning: 'void low_battery_event()' declared 'static' but never defined +autogenerated:146: warning: 'void low_battery_event()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:270: warning: 'command_index' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.size.txt index 0fa674eeaf..7f638d6508 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.size.txt @@ -219,6 +219,7 @@ 0000000a r init_home()::__c 0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r verify_nav_wp()::__c +0000000a r print_log_menu()::__c 0000000a r report_compass()::__c 0000000a r report_throttle()::__c 0000000a r test_mag(unsigned char, Menu::arg const*)::__c @@ -283,6 +284,7 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -343,6 +345,7 @@ 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 b rc_override 00000010 r planner_menu_commands +00000010 r __menu_name__main_menu 00000010 T GCS_MAVLINK::send_message(ap_message) 00000010 W AP_VarT::cast_to_float() const 00000010 W AP_VarT::cast_to_float() const @@ -351,7 +354,6 @@ 00000010 r Log_Read_Startup()::__c 00000010 r test_wp(unsigned char, Menu::arg const*)::__c 00000010 r dump_log(unsigned char, Menu::arg const*)::__c -00000011 r __menu_name__main_menu 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c 00000011 r test_airspeed(unsigned char, Menu::arg const*)::__c @@ -420,10 +422,11 @@ 00000019 r handle_process_do_command()::__c 00000019 r handle_process_condition_command()::__c 00000019 r do_jump()::__c +0000001a r print_log_menu()::__c +0000001a r Log_Read_Process(int, int)::__c 0000001a r failsafe_short_on_event()::__c 0000001a r do_jump()::__c 0000001a r do_jump()::__c -0000001a r Log_Read(int, int)::__c 0000001b r failsafe_short_off_event()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -433,25 +436,25 @@ 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c r Log_Read_Current()::__c -0000001c r Log_Read(int, int)::__c +0000001c r Log_Read_Process(int, int)::__c 0000001c r Log_Read(int, int)::__c 0000001d r setup_radio(unsigned char, Menu::arg const*)::__c 0000001d r startup_ground()::__c 0000001d r report_batt_monitor()::__c +0000001e t update_commands() 0000001e r flight_mode_strings 0000001e r test_failsafe(unsigned char, Menu::arg const*)::__c 0000001e r startup_ground()::__c 0000001f r setup_compass(unsigned char, Menu::arg const*)::__c 0000001f r init_ardupilot()::__c +0000001f r print_log_menu()::__c +0000001f r Log_Read(int, int)::__c 0000001f r test_mag(unsigned char, Menu::arg const*)::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 r report_xtrack()::__c 00000020 r init_barometer()::__c -00000020 r Log_Read(int, int)::__c 00000020 t byte_swap_4 -00000021 r print_log_menu()::__c -00000021 r print_log_menu()::__c 00000021 r verify_loiter_time()::__c 00000021 r process_next_command()::__c 00000022 t print_blanks(int) @@ -478,12 +481,11 @@ 00000026 t print_done() 00000026 t print_hit_enter() 00000026 r init_ardupilot()::__c +00000026 r init_ardupilot()::__c 00000026 r print_PID(PID*)::__c 00000027 r change_command(unsigned char)::__c -00000027 r init_ardupilot()::__c 00000027 r test_xbee(unsigned char, Menu::arg const*)::__c 00000028 t main_menu_help(unsigned char, Menu::arg const*) -00000028 t help_log(unsigned char, Menu::arg const*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const @@ -504,8 +506,6 @@ 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) 00000030 t test_mode(unsigned char, Menu::arg const*) -00000030 r print_log_menu()::__c -00000031 r start_new_log(unsigned char)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000033 b pending_status @@ -516,10 +516,10 @@ 00000035 r Log_Read_Nav_Tuning()::__c 00000035 r verify_condition_command()::__c 00000036 t report_radio() +00000036 t find_last() 00000036 r test_failsafe(unsigned char, Menu::arg const*)::__c 00000037 r setup_factory(unsigned char, Menu::arg const*)::__c 00000038 t send_current_waypoint(mavlink_channel_t) -00000038 b barometer 00000038 r test_dipswitches(unsigned char, Menu::arg const*)::__c 00000038 r dump_log(unsigned char, Menu::arg const*)::__c 00000039 r setup_radio(unsigned char, Menu::arg const*)::__c @@ -530,11 +530,13 @@ 0000003a W PID::~PID() 0000003c t verify_RTL() 0000003c t Log_Write_Mode(unsigned char) +0000003c b barometer 0000003c r test_wp_print(Location*, unsigned char)::__c 0000003c r test_mag(unsigned char, Menu::arg const*)::__c 0000003d B g_gps_driver 0000003e T 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 r log_menu_commands 00000040 b adc 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 t byte_swap_8 @@ -552,7 +554,6 @@ 0000004c t Log_Read_Mode() 0000004e t setup_batt_monitor(unsigned char, Menu::arg const*) 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -566,7 +567,6 @@ 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005b r setup_erase(unsigned char, Menu::arg const*)::__c 0000005c t readSwitch() -0000005c t get_num_logs() 0000005e T GCS_MAVLINK::_count_parameters() 00000060 t print_switch(unsigned char, unsigned char) 00000060 W AP_Float16::AP_Float16(AP_Var_group*, unsigned int, float, prog_char_t const*, unsigned char) @@ -575,7 +575,6 @@ 00000064 t test_xbee(unsigned char, Menu::arg const*) 00000064 W RC_Channel_aux::~RC_Channel_aux() 00000068 t zero_eeprom() -00000068 t find_last_log_page(int) 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 0000006a t demo_servos(unsigned char) 0000006a t startup_IMU_ground() @@ -609,6 +608,7 @@ 0000009c t print_PID(PID*) 0000009c B gcs0 0000009c B gcs3 +0000009e t get_num_logs() 000000a0 t report_xtrack() 000000a2 t verify_nav_wp() 000000a4 t Log_Read_Cmd() @@ -619,31 +619,32 @@ 000000ac t Log_Read_Performance() 000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b0 t Log_Read_Startup() -000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 b compass 000000bc t Log_Read_Control_Tuning() 000000be t update_events() 000000c0 t report_throttle() 000000c0 t calc_bearing_error() +000000c0 t Log_Read(int, int) 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c6 t zero_airspeed() 000000c6 t startup_ground() 000000c7 B dcm 000000c8 t test_modeswitch(unsigned char, Menu::arg const*) +000000c8 t get_log_boundaries(unsigned char, int&, int&) 000000ca t send_radio_out(mavlink_channel_t) 000000ca t control_failsafe(unsigned int) 000000ce t send_radio_in(mavlink_channel_t) 000000ce W PID::PID(unsigned int, prog_char_t const*, float const&, float const&, float const&, int const&) 000000ce r setup_mode(unsigned char, Menu::arg const*)::__c -000000ce r help_log(unsigned char, Menu::arg const*)::__c 000000d0 t get_bearing(Location*, Location*) 000000d4 t trim_radio() 000000e4 t test_radio_pwm(unsigned char, Menu::arg const*) 000000e7 r init_ardupilot()::__c -000000ec t dump_log(unsigned char, Menu::arg const*) 000000f0 t throttle_slew_limit() 000000f0 t test_adc(unsigned char, Menu::arg const*) +000000f4 t erase_logs(unsigned char, Menu::arg const*) 000000fa t Log_Read_Current() +000000fc t dump_log(unsigned char, Menu::arg const*) 00000102 t setup_compass(unsigned char, Menu::arg const*) 00000106 t test_current(unsigned char, Menu::arg const*) 00000106 t calc_nav_pitch() @@ -657,7 +658,6 @@ 00000112 t report_batt_monitor() 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) 00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int) -00000114 t erase_logs(unsigned char, Menu::arg const*) 00000114 t read_barometer() 00000118 t test_gps(unsigned char, Menu::arg const*) 00000120 t test_pressure(unsigned char, Menu::arg const*) @@ -673,6 +673,7 @@ 00000152 t report_gains() 00000152 t verify_condition_command() 00000158 t test_airspeed(unsigned char, Menu::arg const*) +0000015a t Log_Read_Process(int, int) 0000015e t set_guided_WP() 0000015e t handle_process_nav_cmd() 0000015e t test_gyro(unsigned char, Menu::arg const*) @@ -682,12 +683,11 @@ 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) 0000017c t send_location(mavlink_channel_t) 0000017e t Log_Read_Nav_Tuning() -00000180 t send_extended_status1(mavlink_channel_t, unsigned int) +0000017e t send_extended_status1(mavlink_channel_t, unsigned int) 0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 00000190 T init_home() 00000192 t test_imu(unsigned char, Menu::arg const*) 0000019a t do_jump() -000001ae t start_new_log(unsigned char) 000001b2 t update_crosstrack() 000001b2 t set_mode(unsigned char) 000001bc t set_next_WP(Location*) @@ -700,7 +700,6 @@ 000001ea t init_barometer() 000001fe t test_failsafe(unsigned char, Menu::arg const*) 00000208 t calc_throttle() -00000210 t Log_Read(int, int) 0000021a t send_raw_imu1(mavlink_channel_t) 00000228 t test_wp(unsigned char, Menu::arg const*) 0000022a t send_gps_raw(mavlink_channel_t) @@ -710,16 +709,17 @@ 0000024c t update_loiter() 0000025c t setup_radio(unsigned char, Menu::arg const*) 00000268 t send_raw_imu3(mavlink_channel_t) +00000268 t find_last_log_page(unsigned int) 000002d4 t handle_process_do_command() 000002e4 t read_radio() 0000031e t test_mag(unsigned char, Menu::arg const*) -0000033a W Parameters::~Parameters() +00000344 W Parameters::~Parameters() 000003e6 t read_battery() -00000436 t print_log_menu() +0000044c t print_log_menu() 000004de t set_servos() 0000059c t __static_initialization_and_destruction_0(int, int) -00000648 t init_ardupilot() -00000920 W Parameters::Parameters() -0000092b b g +00000692 t init_ardupilot() +00000936 W Parameters::Parameters() +00000938 b g 0000149a T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001cbe T loop +00001caa T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log index 6ed3a9f501..7b0ec8fe96 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.build.log @@ -13,14 +13,14 @@ autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'sta autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'byte get_num_logs()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:842: warning: 'byte get_num_logs()' defined but not used autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined autogenerated:53: warning: 'int find_last()' declared 'static' but never defined autogenerated:54: warning: 'int find_last_log_page(uint16_t)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduPlane/Log.pde:843: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:839: warning: 'void Log_Write_Performance()' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Control_Tuning()' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Raw()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'void Log_Write_Performance()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Control_Tuning()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:846: warning: 'void Log_Write_Raw()' defined but not used autogenerated:65: warning: 'void Log_Read_Current()' declared 'static' but never defined autogenerated:66: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined autogenerated:67: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined @@ -68,7 +68,7 @@ autogenerated:201: warning: 'void test_wp_print(Location*, byte)' declared 'stat /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used /root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt index fbeed9d9de..b3bdd1f9f6 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.size.txt @@ -311,8 +311,8 @@ 00000023 r verify_loiter_turns()::__c 00000023 r navigate()::__c 00000026 r init_ardupilot()::__c +00000026 r init_ardupilot()::__c 00000027 r change_command(unsigned char)::__c -00000027 r init_ardupilot()::__c 00000028 t demo_servos(unsigned char) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::unserialize(void*, unsigned int) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log index 6ed3a9f501..7b0ec8fe96 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.build.log @@ -13,14 +13,14 @@ autogenerated:35: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'sta autogenerated:36: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined /root/apm/ardupilot-mega/ArduPlane/GCS_Mavlink.pde:2057: warning: 'void gcs_send_text(gcs_severity, const char*)' defined but not used autogenerated:49: warning: 'bool print_log_menu()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'byte get_num_logs()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:842: warning: 'byte get_num_logs()' defined but not used autogenerated:52: warning: 'void get_log_boundaries(byte, int&, int&)' declared 'static' but never defined autogenerated:53: warning: 'int find_last()' declared 'static' but never defined autogenerated:54: warning: 'int find_last_log_page(uint16_t)' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduPlane/Log.pde:843: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:839: warning: 'void Log_Write_Performance()' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Control_Tuning()' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Raw()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:844: warning: 'void Log_Write_Attitude(int, int, uint16_t)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'void Log_Write_Performance()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:845: warning: 'void Log_Write_Control_Tuning()' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:846: warning: 'void Log_Write_Raw()' defined but not used autogenerated:65: warning: 'void Log_Read_Current()' declared 'static' but never defined autogenerated:66: warning: 'void Log_Read_Control_Tuning()' declared 'static' but never defined autogenerated:67: warning: 'void Log_Read_Nav_Tuning()' declared 'static' but never defined @@ -68,7 +68,7 @@ autogenerated:201: warning: 'void test_wp_print(Location*, byte)' declared 'stat /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:304: warning: 'airspeed_raw' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:305: warning: 'airspeed_pressure' defined but not used /root/apm/ardupilot-mega/ArduPlane/ArduPlane.pde:309: warning: 'abs_pressure' defined but not used -/root/apm/ardupilot-mega/ArduPlane/Log.pde:840: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used +/root/apm/ardupilot-mega/ArduPlane/Log.pde:841: warning: 'int8_t process_logs(uint8_t, const Menu::arg*)' defined but not used /root/apm/ardupilot-mega/ArduPlane/planner.pde:19: warning: 'int8_t planner_mode(uint8_t, const Menu::arg*)' defined but not used %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt index 16c1744827..adc9cd9c98 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.size.txt @@ -311,8 +311,8 @@ 00000023 r verify_loiter_turns()::__c 00000023 r navigate()::__c 00000026 r init_ardupilot()::__c +00000026 r init_ardupilot()::__c 00000027 r change_command(unsigned char)::__c -00000027 r init_ardupilot()::__c 00000028 t demo_servos(unsigned char) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::unserialize(void*, unsigned int) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 306c2275a4..f15428b643 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -3,14 +3,14 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex - ArduPlane V2.251 + ArduPlane V2.26 12 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex - ArduPlane V2.251 HIL + ArduPlane V2.26 HIL #define FLIGHT_MODE_CHANNEL 8 #define FLIGHT_MODE_1 AUTO @@ -44,53 +44,53 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex - ArduPlane V2.251 APM trunk + ArduPlane V2.26 APM trunk 12 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex - ArduCopter V2.0.49 Beta Quad + ArduCopter V2.0.50 Beta Quad #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION X_FRAME - 111 + 112 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex - ArduCopter V2.0.49 Beta Tri + ArduCopter V2.0.50 Beta Tri #define FRAME_CONFIG TRI_FRAME #define FRAME_ORIENTATION X_FRAME - 111 + 112 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex - ArduCopter V2.0.49 Beta Hexa + ArduCopter V2.0.50 Beta Hexa #define FRAME_CONFIG HEXA_FRAME #define FRAME_ORIENTATION X_FRAME - 111 + 112 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex - ArduCopter V2.0.49 Beta Y6 + ArduCopter V2.0.50 Beta Y6 #define FRAME_CONFIG Y6_FRAME #define FRAME_ORIENTATION X_FRAME - 111 + 112 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex @@ -142,7 +142,7 @@ http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex - ArduCopter V2.0.49 Beta Quad Hil + ArduCopter V2.0.50 Beta Quad Hil #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION PLUS_FRAME @@ -152,7 +152,7 @@ - 111 + 112 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index 69fccc6bde..1615f378de 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1,29 +1,20 @@ From https://code.google.com/p/ardupilot-mega - 66cc8dd..6f4e7ec master -> origin/master -Updating 66cc8dd..6f4e7ec + 6aeabd0..833acbd master -> origin/master +Updating 6aeabd0..833acbd Fast-forward - ArduCopter/APM_Config.h | 2 +- - ArduCopter/ArduCopter.pde | 18 ++- - ArduCopter/commands.pde | 8 +- - ArduCopter/commands_process.pde | 3 +- - ArduCopter/motors_hexa.pde | 2 +- - ArduCopter/motors_octa.pde | 2 +- - ArduCopter/motors_octa_quad.pde | 2 +- - ArduCopter/motors_y6.pde | 3 +- - ArduPlane/ArduPlane.pde | 2 +- - ArduPlane/Log.pde | 5 +- - ArduPlane/commands_logic.pde | 13 ++- - Tools/ArdupilotMegaPlanner/CurrentState.cs | 1 - - Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 27 +++- - .../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 149 +++++++++++++++++--- - Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs | 14 ++- - .../Properties/AssemblyInfo.cs | 2 +- - .../bin/Release/ArdupilotMegaPlanner.application | 2 +- - .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2195456 bytes - 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 - Tools/autotest/arducopter.py | 58 ++++++--- - Tools/autotest/common.py | 16 ++- - 24 files changed, 251 insertions(+), 78 deletions(-) + ArduCopter/ArduCopter.pde | 11 ++++- + ArduCopter/Attitude.pde | 1 - + ArduCopter/Log.pde | 28 ++++++------ + ArduCopter/Parameters.h | 50 +++++++++-------------- + ArduCopter/config.h | 20 +-------- + ArduCopter/defines.h | 2 + + ArduCopter/navigation.pde | 17 ++++++-- + ArduCopter/radio.pde | 9 +---- + ArduCopter/setup.pde | 52 ++++++++++++------------ + ArduCopter/system.pde | 22 ++++++---- + ArduCopter/test.pde | 63 +++++++++++++++-------------- + ArduPlane/ArduPlane.pde | 2 +- + ArduPlane/Log.pde | 91 +++++++++++++++++++++--------------------- + Tools/autotest/arducopter.py | 10 ++-- + Tools/autotest/common.py | 8 +++- + 15 files changed, 193 insertions(+), 193 deletions(-) From 56df75fbb158962fd5f77f035cbe85ee81f104a6 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sun, 20 Nov 2011 08:17:17 +0800 Subject: [PATCH 20/63] APM Planner 1.0.95 fix ac2 heli error fix guide mode wp fix tuning graph on mono fix autozoom on planner map modify prefetch - current screen fix zoom bar for mono fix base class for special functions --- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 2 +- Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 21 +++++- .../ArdupilotMegaPlanner/GCSViews/Firmware.cs | 3 +- .../GCSViews/FlightData.cs | 9 ++- .../GCSViews/FlightPlanner.Designer.cs | 1 + .../GCSViews/FlightPlanner.cs | 64 +++++++++++++------ .../GCSViews/FlightPlanner.resx | 4 +- .../GCSViews/Simulation.cs | 2 +- Tools/ArdupilotMegaPlanner/MAVLink.cs | 15 ++++- Tools/ArdupilotMegaPlanner/MainV2.Designer.cs | 10 ++- Tools/ArdupilotMegaPlanner/MainV2.cs | 8 +++ Tools/ArdupilotMegaPlanner/Program.cs | 2 +- .../Properties/AssemblyInfo.cs | 2 +- .../Setup/Setup.Designer.cs | 1 + Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 8 ++- .../Release/ArdupilotMegaPlanner.application | 2 +- .../bin/Release/GCSViews/FlightPlanner.resx | 4 +- 17 files changed, 120 insertions(+), 38 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 96be901ebe..1dcf908aa2 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -57,7 +57,7 @@ full true bin\Release\ - TRACE;MAVLINK10cra + DEBUG;TRACE;MAVLINK10cra prompt 4 false diff --git a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs b/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs index bc034b7dc1..43984d3fd6 100644 --- a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs +++ b/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs @@ -57,7 +57,7 @@ namespace System.IO.Ports get { return client.Available + rbuffer.Length - rbufferread; } } - public bool IsOpen { get { return client.Client.Connected; } } + public bool IsOpen { get { try { return client.Client.Connected; } catch { return false; } } } public bool DtrEnable { @@ -97,6 +97,11 @@ namespace System.IO.Ports { if (client == null || !IsOpen) { + try + { + client.Close(); + } + catch { } throw new Exception("The socket/serialproxy is closed"); } } @@ -216,11 +221,21 @@ namespace System.IO.Ports public void Close() { - if (client.Client.Connected) + try + { + if (client.Client.Connected) + { + client.Client.Close(); + client.Close(); + } + } + catch { } + + try { - client.Client.Close(); client.Close(); } + catch { } client = new TcpClient(); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index a5f08b4889..9eaeb83689 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -681,7 +681,7 @@ namespace ArdupilotMega.GCSViews } } - lbl_status.Text = "Done"; + lbl_status.Text = "Write Done... Waiting"; } else { @@ -696,6 +696,7 @@ namespace ArdupilotMega.GCSViews System.Threading.Thread.Sleep(10000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time. + lbl_status.Text = "Done"; } catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); } flashing = false; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index da53a6ddbc..9cba58f074 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -141,6 +141,8 @@ namespace ArdupilotMega.GCSViews CMB_setwp.SelectedIndex = 0; + zg1.Visible = true; + CreateChart(zg1); // config map @@ -734,6 +736,7 @@ namespace ArdupilotMega.GCSViews ZedGraphTimer.Enabled = true; ZedGraphTimer.Start(); zg1.Visible = true; + zg1.Refresh(); } else { @@ -807,9 +810,9 @@ namespace ArdupilotMega.GCSViews Locationwp gotohere = new Locationwp(); gotohere.id = (byte)MAVLink.MAV_CMD.WAYPOINT; - gotohere.alt = (int)(intalt / MainV2.cs.multiplierdist * 100); // back to m - gotohere.lat = (int)(gotolocation.Lat * 10000000); - gotohere.lng = (int)(gotolocation.Lng * 10000000); + gotohere.alt = (float)(intalt / MainV2.cs.multiplierdist); // back to m + gotohere.lat = (float)(gotolocation.Lat); + gotohere.lng = (float)(gotolocation.Lng); try { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs index 75817398cb..d94e9fecea 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs @@ -649,6 +649,7 @@ this.panelMap.ForeColor = System.Drawing.SystemColors.ControlText; this.panelMap.MinimumSize = new System.Drawing.Size(27, 27); this.panelMap.Name = "panelMap"; + this.panelMap.Resize += new System.EventHandler(this.panelMap_Resize); // // lbl_distance // diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index 027dc6441c..3deeb7ac6b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -642,6 +642,11 @@ namespace ArdupilotMega.GCSViews updateCMDParams(); + // mono + panelMap.Dock = DockStyle.None; + panelMap.Dock = DockStyle.Fill; + panelMap_Resize(null,null); + writeKML(); } @@ -672,7 +677,12 @@ namespace ArdupilotMega.GCSViews { selectedrow = e.RowIndex; string option = Commands[Command.Index, selectedrow].EditedFormattedValue.ToString(); - string cmd = Commands[0, selectedrow].Value.ToString(); + string cmd; + try + { + cmd = Commands[Command.Index, selectedrow].Value.ToString(); + } + catch { cmd = option; } Console.WriteLine("editformat " + option + " value " + cmd); ChangeColumnHeader(cmd); } @@ -873,14 +883,8 @@ namespace ArdupilotMega.GCSViews { if (Commands.Rows[a].HeaderCell.Value == null) { - if (ArdupilotMega.MainV2.MAC) - { - Commands.Rows[a].HeaderCell.Value = " " + (a + 1).ToString(); // mac doesnt auto center header text - } - else - { + Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter; Commands.Rows[a].HeaderCell.Value = (a + 1).ToString(); - } } // skip rows with the correct number string rowno = Commands.Rows[a].HeaderCell.Value.ToString(); @@ -920,14 +924,14 @@ namespace ArdupilotMega.GCSViews pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString())); addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2)); - avglong += double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()); - avglat += double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()); + avglong += double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()); + avglat += double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()); usable++; - maxlong = Math.Max(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()), maxlong); - maxlat = Math.Max(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()), maxlat); - minlong = Math.Min(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()), minlong); - minlat = Math.Min(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()), minlat); + maxlong = Math.Max(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()), maxlong); + maxlat = Math.Max(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()), maxlat); + minlong = Math.Min(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()), minlong); + minlat = Math.Min(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()), minlat); System.Diagnostics.Debug.WriteLine(temp - System.Diagnostics.Stopwatch.GetTimestamp()); } @@ -974,9 +978,11 @@ namespace ArdupilotMega.GCSViews else if (home.Length > 5 && usable == 0) { lookat = " " + TXT_homelng.Text.ToString(new System.Globalization.CultureInfo("en-US")) + " " + TXT_homelat.Text.ToString(new System.Globalization.CultureInfo("en-US")) + " 4000 "; + MainMap.HoldInvalidation = true; MainMap.ZoomAndCenterMarkers("objects"); MainMap.Zoom -= 2; MainMap_OnMapZoomChanged(); + MainMap.HoldInvalidation = false; } RegeneratePolygon(); @@ -2176,12 +2182,21 @@ namespace ArdupilotMega.GCSViews private void BUT_Prefetch_Click(object sender, EventArgs e) { RectLatLng area = MainMap.SelectedArea; + if (area.IsEmpty) + { + DialogResult res = MessageBox.Show("No ripp area defined, ripp displayed on screen?", "Rip", MessageBoxButtons.YesNo); + if (res == DialogResult.Yes) + { + area = MainMap.CurrentViewArea; + } + } + if (!area.IsEmpty) { - for (int i = (int)MainMap.Zoom; i <= MainMap.MaxZoom; i++) - { - DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + i + " ?", "GMap.NET", MessageBoxButtons.YesNoCancel); + DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + (int)MainMap.Zoom + " ?", "GMap.NET", MessageBoxButtons.YesNo); + for (int i = 1; i <= MainMap.MaxZoom; i++) + { if (res == DialogResult.Yes) { TilePrefetcher obj = new TilePrefetcher(); @@ -2588,6 +2603,7 @@ namespace ArdupilotMega.GCSViews private void clearMissionToolStripMenuItem_Click(object sender, EventArgs e) { Commands.Rows.Clear(); + selectedrow = 0; writeKML(); } @@ -2611,7 +2627,7 @@ namespace ArdupilotMega.GCSViews Commands.Rows[row].Cells[Param1.Index].Value = 1; - Commands.Rows[row].Cells[Param3.Index].Value = repeat; + Commands.Rows[row].Cells[Param2.Index].Value = repeat; } private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e) @@ -2627,7 +2643,7 @@ namespace ArdupilotMega.GCSViews Commands.Rows[row].Cells[Param1.Index].Value = wp; - Commands.Rows[row].Cells[Param3.Index].Value = repeat; + Commands.Rows[row].Cells[Param2.Index].Value = repeat; } private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e) @@ -2697,5 +2713,15 @@ namespace ArdupilotMega.GCSViews MainV2.fixtheme(form); form.Show(); } + + private void panelMap_Resize(object sender, EventArgs e) + { + // this is a mono fix for the zoom bar + Console.WriteLine("panelmap "+panelMap.Size.ToString()); + MainMap.Size = new Size(panelMap.Size.Width - 50,panelMap.Size.Height); + trackBar1.Location = new Point(panelMap.Size.Width - 50,trackBar1.Location.Y); + trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y); + label11.Location = new Point(panelMap.Size.Width - 50, label11.Location.Y); + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx index 1a4e7ea6cd..51ec819c4a 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx @@ -1627,7 +1627,7 @@ Clear Mission - 168, 186 + 168, 164 contextMenuStrip1 @@ -1636,7 +1636,7 @@ System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - 3, 4 + 0, 0 838, 306 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index 64413d2ac4..ddb1f67db9 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -556,7 +556,7 @@ namespace ArdupilotMega.GCSViews processArduPilot(); } } - catch { } + catch (Exception ex) { Console.WriteLine("SIM Main loop exception " + ex.ToString()); } if (hzcounttime.Second != DateTime.Now.Second) { diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index ae1a902b69..172006310c 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -203,7 +203,14 @@ namespace ArdupilotMega if (getparams == true) getParamList(); } - catch (Exception e) { MainV2.givecomport = false; frm.Close(); throw e; } + catch (Exception e) { + try { + BaseStream.Close(); + } catch { } + MainV2.givecomport = false; + frm.Close(); + throw e; + } frm.Close(); @@ -485,6 +492,12 @@ namespace ArdupilotMega /// public bool setParam(string paramname, float value) { + if (!param.ContainsKey(paramname)) + { + Console.WriteLine("Param doesnt exist " + paramname); + return false; + } + MainV2.givecomport = true; __mavlink_param_set_t req = new __mavlink_param_set_t(); diff --git a/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs b/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs index 7f5d152408..72bec1db1e 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs @@ -48,6 +48,7 @@ // // MenuFlightData // + this.MenuFlightData.AutoSize = false; this.MenuFlightData.BackgroundImage = global::ArdupilotMega.Properties.Resources.data; this.MenuFlightData.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuFlightData.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -59,6 +60,7 @@ // // MenuFlightPlanner // + this.MenuFlightPlanner.AutoSize = false; this.MenuFlightPlanner.BackgroundImage = global::ArdupilotMega.Properties.Resources.planner; this.MenuFlightPlanner.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuFlightPlanner.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -72,6 +74,7 @@ // // MenuConfiguration // + this.MenuConfiguration.AutoSize = false; this.MenuConfiguration.BackgroundImage = global::ArdupilotMega.Properties.Resources.configuration; this.MenuConfiguration.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuConfiguration.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -85,6 +88,7 @@ // // MenuSimulation // + this.MenuSimulation.AutoSize = false; this.MenuSimulation.BackgroundImage = global::ArdupilotMega.Properties.Resources.simulation; this.MenuSimulation.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuSimulation.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -98,6 +102,7 @@ // // MenuFirmware // + this.MenuFirmware.AutoSize = false; this.MenuFirmware.BackgroundImage = global::ArdupilotMega.Properties.Resources.firmware; this.MenuFirmware.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuFirmware.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -112,6 +117,7 @@ // MenuConnect // this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right; + this.MenuConnect.AutoSize = false; this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect; this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -132,6 +138,7 @@ // // MainMenu // + this.MainMenu.AutoSize = false; this.MainMenu.BackColor = System.Drawing.SystemColors.Control; this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage"))); this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0); @@ -159,6 +166,7 @@ // // MenuTerminal // + this.MenuTerminal.AutoSize = false; this.MenuTerminal.BackgroundImage = global::ArdupilotMega.Properties.Resources.terminal; this.MenuTerminal.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuTerminal.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -198,6 +206,7 @@ // // MenuHelp // + this.MenuHelp.AutoSize = false; this.MenuHelp.BackgroundImage = global::ArdupilotMega.Properties.Resources.help; this.MenuHelp.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuHelp.ImageTransparentColor = System.Drawing.Color.Magenta; @@ -247,7 +256,6 @@ this.MainMenu.ResumeLayout(false); this.MainMenu.PerformLayout(); this.ResumeLayout(false); - this.PerformLayout(); } diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 18336eda58..6d0024a7a6 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -742,9 +742,17 @@ namespace ArdupilotMega { comportname = CMB_serialport.Text; if (comportname == "UDP" || comportname == "TCP") + { CMB_baudrate.Enabled = false; + if (comportname == "TCP") + MainV2.comPort.BaseStream = new TcpSerial(); + if (comportname == "UDP") + MainV2.comPort.BaseStream = new UdpSerial(); + } else + { CMB_baudrate.Enabled = true; + } try { diff --git a/Tools/ArdupilotMegaPlanner/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs index b0c92d534b..6c2ef0edd1 100644 --- a/Tools/ArdupilotMegaPlanner/Program.cs +++ b/Tools/ArdupilotMegaPlanner/Program.cs @@ -24,7 +24,7 @@ namespace ArdupilotMega Application.Idle += new EventHandler(Application_Idle); - MessageBox.Show("NOTE: This version may break advanced mission scripting"); + //MessageBox.Show("NOTE: This version may break advanced mission scripting"); Application.EnableVisualStyles(); Application.SetCompatibleTextRenderingDefault(false); diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 370e9d4a96..15678c9825 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.0.94")] +[assembly: AssemblyFileVersion("1.0.95")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs index 53f605a0f3..1f30541e5a 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs @@ -1444,6 +1444,7 @@ this.Controls.Add(this.tabControl1); this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow; this.Name = "Setup"; + this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing); this.Load += new System.EventHandler(this.Setup_Load); this.tabControl1.ResumeLayout(false); this.tabReset.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs index bc715c0d10..2b55175ff8 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs @@ -75,7 +75,7 @@ namespace ArdupilotMega.Setup if (tabControl1.SelectedTab == tabHeli) { - if (MainV2.comPort.param["HSV_MAN"].ToString() == "0") + if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0") return; if (HS3.minline == 0) @@ -1254,5 +1254,11 @@ namespace ArdupilotMega.Setup if (int.Parse(temp.Text) > 2100) temp.Text = "2100"; } + + private void Setup_FormClosing(object sender, FormClosingEventArgs e) + { + timer.Stop(); + timer.Dispose(); + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application index b9ee058b99..2ad8510544 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application +++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application @@ -11,7 +11,7 @@ - N43U7y77mNy6nfkD9v5DNdwNLps= + d1SWduiRJYsMADkinyiFASzMBV8= diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx index 1a4e7ea6cd..51ec819c4a 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx @@ -1627,7 +1627,7 @@ Clear Mission - 168, 186 + 168, 164 contextMenuStrip1 @@ -1636,7 +1636,7 @@ System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - 3, 4 + 0, 0 838, 306 From 56179a24e1f28f2ce90c2919e5d4a9fe8881e713 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 16:57:10 -0800 Subject: [PATCH 21/63] Added Arbitrary data logging --- ArduCopter/Log.pde | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 9a95726fe4..9b75f0728f 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -901,6 +901,29 @@ static void Log_Read_Startup() Serial.printf_P(PSTR("START UP\n")); } +static void Log_Write_Data(int8_t _type, float _data) +{ + Log_Write_Data(_type, (int32_t)(_data * 1000)); +} + +static void Log_Write_Data(int8_t _type, int32_t _data) +{ + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteByte(LOG_DATA_MSG); + DataFlash.WriteByte(_type); + DataFlash.WriteLong(_data); + DataFlash.WriteByte(END_BYTE); +} + +// Read a mode packet +static void Log_Read_Data() +{ + int8_t temp1 = DataFlash.ReadByte(); + int32_t temp2 = DataFlash.ReadLong(); + Serial.printf_P(PSTR("DATA: %d, %ld\n"), temp1, temp2); +} + // Read the DataFlash log memory : Packet Parser static void Log_Read(int start_page, int end_page) @@ -981,6 +1004,10 @@ static void Log_Read(int start_page, int end_page) case LOG_GPS_MSG: Log_Read_GPS(); break; + + case LOG_DATA_MSG: + Log_Read_Data(); + break; } break; } From 90bc03ef99c29f8d91c9313f5e39c7fde2f9f4ad Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 16:57:25 -0800 Subject: [PATCH 22/63] new DataLog message --- ArduCopter/defines.h | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index c881148463..522ef466d6 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -236,6 +236,7 @@ enum gcs_severity { #define LOG_STARTUP_MSG 0x0A #define LOG_MOTORS_MSG 0x0B #define LOG_OPTFLOW_MSG 0x0C +#define LOG_DATA_MSG 0x0D #define LOG_INDEX_MSG 0xF0 #define MAX_NUM_LOGS 50 From 194778a6f9c68c8827de79b6112e0cfa0326d3cc Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 16:58:20 -0800 Subject: [PATCH 23/63] Logging APVar saves --- ArduCopter/GCS_Mavlink.pde | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index efda1da0ac..def4cba2be 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1367,6 +1367,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // find the requested parameter vp = AP_Var::find(key); + if ((NULL != vp) && // exists !isnan(packet.param_value) && // not nan !isinf(packet.param_value)) { // not inf @@ -1382,19 +1383,27 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // handle variables with standard type IDs if (var_type == AP_Var::k_typeid_float) { ((AP_Float *)vp)->set_and_save(packet.param_value); + Log_Write_Data(1, (float)((AP_Float *)vp)->get()); } else if (var_type == AP_Var::k_typeid_float16) { ((AP_Float16 *)vp)->set_and_save(packet.param_value); + Log_Write_Data(2, (float)((AP_Float *)vp)->get()); } else if (var_type == AP_Var::k_typeid_int32) { if (packet.param_value < 0) rounding_addition = -rounding_addition; ((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition); + Log_Write_Data(3, (int32_t)((AP_Float *)vp)->get()); + } else if (var_type == AP_Var::k_typeid_int16) { if (packet.param_value < 0) rounding_addition = -rounding_addition; ((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition); + Log_Write_Data(4, (int32_t)((AP_Float *)vp)->get()); + } else if (var_type == AP_Var::k_typeid_int8) { if (packet.param_value < 0) rounding_addition = -rounding_addition; ((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition); + Log_Write_Data(5, (int32_t)((AP_Float *)vp)->get()); + } else { // we don't support mavlink set on this parameter break; @@ -1410,6 +1419,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) vp->cast_to_float(), _count_parameters(), -1); // XXX we don't actually know what its index is... + } break; From aef4db826335334a329d6ab4909ef8f4666f2e76 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 16:58:46 -0800 Subject: [PATCH 24/63] Logging stabilization KP to hunt bug --- ArduCopter/system.pde | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 5d3fa52c67..10553fda99 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -310,6 +310,10 @@ static void init_ardupilot() startup_ground(); Log_Write_Startup(); + Log_Write_Data(10, g.pi_stabilize_roll.kP()); + Log_Write_Data(11, g.pi_stabilize_pitch.kP()); + Log_Write_Data(12, g.pi_rate_roll.kP()); + Log_Write_Data(13, g.pi_rate_pitch.kP()); SendDebug("\nReady to FLY "); } From 269c6d26c93a3d0b3f41ef1af41a696db8e1c1d8 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 16:59:45 -0800 Subject: [PATCH 25/63] Added KML link --- Tools/autotest/autotest.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index c3f6122e76..adb0478f1b 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -247,6 +247,7 @@ def run_tests(steps): if not passed: print("FAILED %u tests: %s" % (len(failed), failed)) + results.addglob("Google Earth track", '*.kml') results.addfile('Full Logs', 'autotest-output.txt') results.addglob('DataFlash Log', '*.flashlog') results.addglob("MAVLink log", '*.mavlog') From 14f0f7b6f36833776d64e5935c897fe1dade9891 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 17:31:36 -0800 Subject: [PATCH 26/63] lengthened log timeout --- Tools/autotest/autotest.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index adb0478f1b..a91e18c202 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -43,7 +43,7 @@ def dump_logs(atype): mavproxy.expect("Log]") for i in range(numlogs): mavproxy.send("dump %u\n" % (i+1)) - mavproxy.expect("logs enabled:", timeout=120) + mavproxy.expect("logs enabled:", timeout=400) mavproxy.expect("Log]") util.pexpect_close(mavproxy) util.pexpect_close(sil) From 73e0ab0c6364eceb694ba596ec4692f248303cfe Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 18 Nov 2011 19:03:21 +1100 Subject: [PATCH 27/63] desktop: more fixes for DataFlash filesystem changes --- libraries/Desktop/support/DataFlash.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/Desktop/support/DataFlash.cpp b/libraries/Desktop/support/DataFlash.cpp index 798b8e9e1b..6cc7786f01 100644 --- a/libraries/Desktop/support/DataFlash.cpp +++ b/libraries/Desktop/support/DataFlash.cpp @@ -16,7 +16,7 @@ static int flash_fd; static uint8_t buffer[2][DF_PAGE_SIZE]; -#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1 +#define OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwritten from page 1 // Constructors //////////////////////////////////////////////////////////////// DataFlash_Class::DataFlash_Class() @@ -120,7 +120,7 @@ void DataFlash_Class::ChipErase () void DataFlash_Class::StartWrite(int16_t PageAdr) { df_BufferNum = 1; - df_BufferIdx = 0; + df_BufferIdx = 4; df_PageAdr = PageAdr; df_Stop_Write = 0; @@ -137,12 +137,12 @@ void DataFlash_Class::FinishWrite(void) df_PageAdr++; if (OVERWRITE_DATA==1) { - if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining + if (df_PageAdr>=DF_LAST_PAGE) // If we reach the end of the memory, start from the begining df_PageAdr = 1; } else { - if (df_PageAdr>=4096) // If we reach the end of the memory, stop here + if (df_PageAdr>=DF_LAST_PAGE) // If we reach the end of the memory, stop here df_Stop_Write=1; } @@ -167,17 +167,17 @@ void DataFlash_Class::WriteByte(byte data) df_BufferIdx++; if (df_BufferIdx >= df_PageSize) // End of buffer? { - df_BufferIdx=0; + df_BufferIdx=4; BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT df_PageAdr++; if (OVERWRITE_DATA==1) { - if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining + if (df_PageAdr>=DF_LAST_PAGE) // If we reach the end of the memory, start from the begining df_PageAdr = 1; } else { - if (df_PageAdr>=4096) // If we reach the end of the memory, stop here + if (df_PageAdr>=DF_LAST_PAGE) // If we reach the end of the memory, stop here df_Stop_Write=1; } @@ -218,7 +218,7 @@ int16_t DataFlash_Class::GetPage() void DataFlash_Class::StartRead(int16_t PageAdr) { df_Read_BufferNum=1; - df_Read_BufferIdx=0; + df_Read_BufferIdx=4; df_Read_PageAdr=PageAdr; WaitReady(); PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer @@ -234,10 +234,10 @@ byte DataFlash_Class::ReadByte() df_Read_BufferIdx++; if (df_Read_BufferIdx >= df_PageSize) // End of buffer? { - df_Read_BufferIdx=0; + df_Read_BufferIdx=4; PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer df_Read_PageAdr++; - if (df_Read_PageAdr>=4096) // If we reach the end of the memory, start from the begining + if (df_Read_PageAdr>=DF_LAST_PAGE) // If we reach the end of the memory, start from the begining { df_Read_PageAdr = 0; df_Read_END = true; From 9ea0fc9539108a005e46db6c7d00543ae3979753 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 18 Nov 2011 19:45:54 +1100 Subject: [PATCH 28/63] Log: prevent looping forever this happened with an empty dataflash --- ArduPlane/Log.pde | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index fee3d4d745..af858b6dfd 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -376,12 +376,19 @@ static int find_last_log_page(uint16_t log_number) bottom_page_filepage = top_page_filepage; do { + int16_t last_bottom_page_file; top_page = bottom_page; bottom_page = bottom_page - bottom_page_filepage; if(bottom_page < 1) bottom_page = 1; DataFlash.StartRead(bottom_page); + last_bottom_page_file = bottom_page_file; bottom_page_file = DataFlash.GetFileNumber(); bottom_page_filepage = DataFlash.GetFilePage(); + if (bottom_page_file == last_bottom_page_file && + bottom_page_filepage == 0) { + /* no progress can be made - give up. The log may be corrupt */ + return -1; + } } while (bottom_page_file != log_number && bottom_page != 1); // Deal with stepping down too far due to overwriting a file From 5aa962c8808fffa9becc0c9dd1425ca91bc0d591 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 20 Nov 2011 19:05:33 +1100 Subject: [PATCH 29/63] ArduPPM: fixed paths for includes this allows it to build on linux/macos --- .../ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c index bac01b76f5..3422e151f2 100644 --- a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c +++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Arduino-usbserial.c @@ -35,7 +35,7 @@ */ #include "Arduino-usbserial.h" -#include "..\..\..\Libraries\ppm_encoder.h" +#include "../../../Libraries/PPM_Encoder.h" /** Circular buffer to hold data from the host before it is sent to the device via the serial port. */ From aab512636e5386a00304adb1f239ddf9fde90e0f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 20 Nov 2011 19:06:19 +1100 Subject: [PATCH 30/63] ArduPPM: let the 2560 know when the USB is connected this sets pin 23 on the 2560 according to whether the USB cable is connected or not --- Tools/ArduPPM/Libraries/PPM_Encoder.h | 28 ++++++++++++++++++++++++++- 1 file changed, 27 insertions(+), 1 deletion(-) diff --git a/Tools/ArduPPM/Libraries/PPM_Encoder.h b/Tools/ArduPPM/Libraries/PPM_Encoder.h index 3a6089b0be..af132f7d3e 100644 --- a/Tools/ArduPPM/Libraries/PPM_Encoder.h +++ b/Tools/ArduPPM/Libraries/PPM_Encoder.h @@ -243,18 +243,33 @@ const uint16_t failsafe_ppm[ PPM_ARRAY_MAX ] = #define USB_PORT PORTC #define USB_PIN PC2 +// true if we have received a USB device connect event +static bool usb_connected; + // USB connected event void EVENT_USB_Device_Connect(void) { // Toggle USB pin high if USB is connected USB_PORT |= (1 << USB_PIN); + + usb_connected = true; + + // this unsets the pin connected to PA1 on the 2560 + // when the bit is clear, USB is connected + PORTD &= ~1; } -// USB dosconnect event +// USB disconnect event void EVENT_USB_Device_Disconnect(void) { // toggle USB pin low if USB is disconnected USB_PORT &= ~(1 << USB_PIN); + + usb_connected = false; + + // this sets the pin connected to PA1 on the 2560 + // when the bit is clear, USB is connected + PORTD |= 1; } // AVR parameters for ArduPilot MEGA v1.4 PPM Encoder (ATmega328P) @@ -676,6 +691,17 @@ void ppm_encoder_init( void ) // Activate pullups on all input pins SERVO_PORT |= 0xFF; +#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__) + // on 32U2 set PD0 to be an output, and clear the bit. This tells + // the 2560 that USB is connected. The USB connection event fires + // later to set the right value + DDRD |= 1; + if (usb_connected) { + PORTD &= ~1; + } else { + PORTD |= 1; + } +#endif // SERVO/PPM INPUT - PIN CHANGE INTERRUPT // ------------------------------------------------------------------------------ From 10a24f22fa0e289468d39c7b46f3b9d1cfb6f5a9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 23:16:57 -0800 Subject: [PATCH 31/63] renamed set_cmd function --- ArduCopter/test.pde | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 5a5b3e2568..e83a72a8ee 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -970,38 +970,38 @@ static int8_t // clear home {Location t = {0, 0, 0, 0, 0, 0}; - set_command_with_index(t,0);} + set_cmd_with_index(t,0);} // CMD opt pitch alt/cm {Location t = {MAV_CMD_NAV_TAKEOFF, WP_OPTION_RELATIVE, 0, 100, 0, 0}; - set_command_with_index(t,1);} + set_cmd_with_index(t,1);} if (!strcmp_P(argv[1].str, PSTR("wp"))) { // CMD opt {Location t = {MAV_CMD_NAV_WAYPOINT, WP_OPTION_RELATIVE, 15, 0, 0, 0}; - set_command_with_index(t,2);} + set_cmd_with_index(t,2);} // CMD opt {Location t = {MAV_CMD_NAV_RETURN_TO_LAUNCH, WP_OPTION_YAW, 0, 0, 0, 0}; - set_command_with_index(t,3);} + set_cmd_with_index(t,3);} // CMD opt {Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}; - set_command_with_index(t,4);} + set_cmd_with_index(t,4);} } else { //2250 = 25 meteres // CMD opt p1 //alt //NS //WE {Location t = {MAV_CMD_NAV_LOITER_TIME, 0, 10, 0, 0, 0}; // 19 - set_command_with_index(t,2);} + set_cmd_with_index(t,2);} // CMD opt dir angle/deg deg/s relative {Location t = {MAV_CMD_CONDITION_YAW, 0, 1, 360, 60, 1}; - set_command_with_index(t,3);} + set_cmd_with_index(t,3);} // CMD opt {Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0}; - set_command_with_index(t,4);} + set_cmd_with_index(t,4);} } From 77da1227bb2d681559c2be131e4a36187b9b69e0 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 23:21:49 -0800 Subject: [PATCH 32/63] renamed set_cmd function --- ArduCopter/commands.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 0c3298fbab..c00a5a9fa0 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -50,11 +50,11 @@ static struct Location get_cmd_with_index(int i) } // Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative - //if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & WP_OPTION_ALT_RELATIVE){ + //if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & MASK_OPTIONS_RELATIVE_ALT){ //temp.alt += home.alt; //} - if(temp.options & WP_OPTION_RELATIVE){ + if(temp.options & MASK_OPTIONS_RELATIVE_ALT){ // If were relative, just offset from home temp.lat += home.lat; temp.lng += home.lng; @@ -65,7 +65,7 @@ static struct Location get_cmd_with_index(int i) // Setters // ------- -static void set_command_with_index(struct Location temp, int i) +static void set_cmd_with_index(struct Location temp, int i) { i = constrain(i, 0, g.command_total.get()); //Serial.printf("set_command: %d with id: %d\n", i, temp.id); @@ -203,7 +203,7 @@ static void init_home() // Save Home to EEPROM // ------------------- // no need to save this to EPROM - set_command_with_index(home, 0); + set_cmd_with_index(home, 0); print_wp(&home, 0); // Save prev loc this makes the calcs look better before commands are loaded From b883ff937c6efa641a4b3ad69737c2844a0036b2 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 23:23:49 -0800 Subject: [PATCH 33/63] renamed the options_mask --- ArduCopter/commands_logic.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index e83f23720d..2abb2a2bf9 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -222,7 +222,7 @@ static void do_takeoff() Location temp = current_loc; // command_nav_queue.alt is a relative altitude!!! - if (command_nav_queue.options & WP_OPTION_ALT_RELATIVE) { + if (command_nav_queue.options & MASK_OPTIONS_RELATIVE_ALT) { temp.alt = command_nav_queue.alt + home.alt; //Serial.printf("rel alt: %ld",temp.alt); } else { @@ -242,7 +242,7 @@ static void do_nav_wp() wp_control = WP_MODE; // command_nav_queue.alt is a relative altitude!!! - if (command_nav_queue.options & WP_OPTION_ALT_RELATIVE) { + if (command_nav_queue.options & MASK_OPTIONS_RELATIVE_ALT) { command_nav_queue.alt += home.alt; } set_next_WP(&command_nav_queue); @@ -258,7 +258,7 @@ static void do_nav_wp() loiter_time_max = command_nav_queue.p1 * 1000; // if we don't require an altitude minimum, we save this flag as passed (1) - if((next_WP.options & WP_OPTION_ALT_REQUIRED) == 0){ + if((next_WP.options & MASK_OPTIONS_RELATIVE_ALT) == 0){ // we don't need to worry about it wp_verify_byte |= NAV_ALTITUDE; } @@ -383,7 +383,7 @@ static bool verify_land() static bool verify_nav_wp() { // Altitude checking - if(next_WP.options & WP_OPTION_ALT_REQUIRED){ + if(next_WP.options & MASK_OPTIONS_RELATIVE_ALT){ // we desire a certain minimum altitude if (current_loc.alt > next_WP.alt){ // we have reached that altitude From c6f9c532af2371535a969b3e8690d6c54dee4402 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 23:24:14 -0800 Subject: [PATCH 34/63] renamed set_command_with_index --- ArduCopter/control_modes.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 23ba1e6c5f..3da3408df1 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -107,7 +107,7 @@ static void read_trim_switch() current_loc.id = MAV_CMD_NAV_WAYPOINT; // save command - set_command_with_index(current_loc, CH7_wp_index); + set_cmd_with_index(current_loc, CH7_wp_index); // save the index g.command_total.set_and_save(CH7_wp_index + 1); From 1e855503da7dd8d6827d6d046001c1f2c32e9d7e Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 23:26:17 -0800 Subject: [PATCH 35/63] renamed MASK_OPTIONS_RELATIVE_ALT --- ArduCopter/defines.h | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 522ef466d6..21446159dd 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -120,6 +120,8 @@ #define POSITION 8 // AUTO control #define NUM_MODES 9 +#define INITIALISING 9 // in startup routines + #define SIMPLE_1 1 #define SIMPLE_2 2 #define SIMPLE_3 4 @@ -166,14 +168,14 @@ #define CIRCLE_MODE 3 // Waypoint options -#define WP_OPTION_ALT_RELATIVE 1 -#define WP_OPTION_ALT_CHANGE 2 -#define WP_OPTION_YAW 4 -#define WP_OPTION_ALT_REQUIRED 8 -#define WP_OPTION_RELATIVE 16 +#define MASK_OPTIONS_RELATIVE_ALT 1 +#define WP_OPTION_ALT_CHANGE 2 +#define WP_OPTION_YAW 4 +#define WP_OPTION_ALT_REQUIRED 8 +#define WP_OPTION_RELATIVE 16 //#define WP_OPTION_ 32 //#define WP_OPTION_ 64 -#define WP_OPTION_NEXT_CMD 128 +#define WP_OPTION_NEXT_CMD 128 //repeating events #define NO_REPEAT 0 From 94ef8a91ff015fee35d14fa80756c3f8c877801f Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 00:20:36 -0800 Subject: [PATCH 36/63] removed typo --- ArduCopter/commands.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index c00a5a9fa0..691218493d 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -54,7 +54,7 @@ static struct Location get_cmd_with_index(int i) //temp.alt += home.alt; //} - if(temp.options & MASK_OPTIONS_RELATIVE_ALT){ + if(temp.options & WP_OPTION_RELATIVE){ // If were relative, just offset from home temp.lat += home.lat; temp.lng += home.lng; @@ -67,6 +67,7 @@ static struct Location get_cmd_with_index(int i) // ------- static void set_cmd_with_index(struct Location temp, int i) { + i = constrain(i, 0, g.command_total.get()); //Serial.printf("set_command: %d with id: %d\n", i, temp.id); From 185c2a50ce6ff363219a6f92b9e91c4ab0320605 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 00:21:19 -0800 Subject: [PATCH 37/63] added some params from Arduplane to make Mavlink upgrade easier made loiter radius smaller in storage --- ArduCopter/ArduCopter.pde | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 09b3f64b50..ceceeb28af 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -260,7 +260,12 @@ static byte control_mode = STABILIZE; static byte old_control_mode = STABILIZE; static byte oldSwitchPosition; // for remembering the control mode switch static int16_t motor_out[8]; -static bool do_simple = false; +static bool do_simple = false; + +static int16_t rc_override[8] = {0,0,0,0,0,0,0,0}; +static bool rc_override_active = false; +static uint32_t rc_override_fs_timer = 0; + // Heli // ---- @@ -480,6 +485,7 @@ static int32_t perf_mon_timer; //static float imu_health; // Metric based on accel gain deweighting static int16_t gps_fix_count; static byte gps_watchdog; +static int pmTest1; // System Timers // -------------- @@ -1473,8 +1479,8 @@ static void update_nav_wp() if (circle_angle > 6.28318531) circle_angle -= 6.28318531; - target_WP.lng = next_WP.lng + (g.loiter_radius * cos(1.57 - circle_angle) * scaleLongUp); - target_WP.lat = next_WP.lat + (g.loiter_radius * sin(1.57 - circle_angle)); + target_WP.lng = next_WP.lng + (g.loiter_radius * 100 * cos(1.57 - circle_angle) * scaleLongUp); + target_WP.lat = next_WP.lat + (g.loiter_radius * 100 * sin(1.57 - circle_angle)); // calc the lat and long error to the target calc_location_error(&target_WP); From 7feecf3220486b04c3d73cbde9d1dd6e9986c3b1 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 00:22:05 -0800 Subject: [PATCH 38/63] renamed WP mask --- ArduCopter/GCS_Mavlink.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index def4cba2be..168ee5ab7c 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -980,7 +980,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // set frame of waypoint uint8_t frame; - if (tell_command.options & WP_OPTION_ALT_RELATIVE) { + if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) { frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; // reference frame } else { frame = MAV_FRAME_GLOBAL; // reference frame @@ -1294,7 +1294,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) guided_WP = tell_command; // add home alt if needed - if (guided_WP.options & WP_OPTION_ALT_RELATIVE){ + if (guided_WP.options & MASK_OPTIONS_RELATIVE_ALT){ guided_WP.alt += home.alt; } @@ -1322,7 +1322,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; if(packet.seq != 0) - set_command_with_index(tell_command, packet.seq); + set_cmd_with_index(tell_command, packet.seq); // update waypoint receiving state machine waypoint_timelast_receive = millis(); From 556db68d2d84c9ae2162a8ea25547d5d492d4bca Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 00:22:20 -0800 Subject: [PATCH 39/63] Made loiter rad smaller in storage --- ArduCopter/Parameters.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 78a8b6c36b..e862a67c4e 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -316,7 +316,7 @@ public: command_index (0, k_param_command_index, PSTR("WP_INDEX")), command_nav_index (0, k_param_command_nav_index, PSTR("WP_MUST_INDEX")), waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")), - loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")), + loiter_radius (LOITER_RADIUS, k_param_loiter_radius, PSTR("WP_LOITER_RAD")), waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")), crosstrack_gain (CROSSTRACK_GAIN, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")), From a47f28cfdb24b0233705f26ac9383ace7575938b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 00:22:46 -0800 Subject: [PATCH 40/63] tweak to loiter turns command --- Tools/autotest/mission2.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/mission2.txt b/Tools/autotest/mission2.txt index 302bc681ba..01c9a940c1 100644 --- a/Tools/autotest/mission2.txt +++ b/Tools/autotest/mission2.txt @@ -15,7 +15,7 @@ QGC WPL 110 # MAV_CMD_NAV_LOITER_TIME # seconds empty rad Yaw per Lat lon Alt continue -4 0 3 19 35 20 0 1 0 0 0 1 +4 0 3 19 35 0 0 1 0 0 20 1 # MAV_CMD_NAV_WAYPOINT B # Hold sec Hit rad empty Yaw angle lat lon alt continue From 17041e5346f4010596ec3a27c27dec9b5f47cada Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 00:23:40 -0800 Subject: [PATCH 41/63] my take at a merge to give tridge a head start at Mav1.0 --- ArduCopter/GCS_Mavlink copy.txt | 2091 +++++++++++++++++++++++++++++++ 1 file changed, 2091 insertions(+) create mode 100644 ArduCopter/GCS_Mavlink copy.txt diff --git a/ArduCopter/GCS_Mavlink copy.txt b/ArduCopter/GCS_Mavlink copy.txt new file mode 100644 index 0000000000..129e04f356 --- /dev/null +++ b/ArduCopter/GCS_Mavlink copy.txt @@ -0,0 +1,2091 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +#include "Mavlink_compat.h" + +// use this to prevent recursion during sensor init +static bool in_mavlink_delay; + +// this costs us 51 bytes, but means that low priority +// messages don't block the CPU +static mavlink_statustext_t pending_status; + +// true when we have received at least 1 MAVLink packet +static bool mavlink_active; + +// check if a message will fit in the payload space available +#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false + +/* + !!NOTE!! + + the use of NOINLINE separate functions for each message type avoids + a compiler bug in gcc that would cause it to use far more stack + space than is needed. Without the NOINLINE we use the sum of the + stack needed for each message type. Please be careful to follow the + pattern below when adding any new messages + */ + +static NOINLINE void send_heartbeat(mavlink_channel_t chan) +{ + #ifdef MAVLINK10 + uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; + uint8_t system_status = MAV_STATE_ACTIVE; + uint32_t custom_mode = control_mode; + + // work out the base_mode. This value is not very useful + // for APM, but we calculate it as best we can so a generic + // MAVLink enabled ground station can work out something about + // what the MAV is up to. The actual bit values are highly + // ambiguous for most of the APM flight modes. In practice, you + // only get useful information from the custom_mode, which maps to + // the APM flight mode and has a well defined meaning in the + // ArduPlane documentation + switch (control_mode) { + case ACRO: + base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; + break; + case STABILIZE: + base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED; + break; + case ALT_HOLD: + case AUTO: + case GUIDED: + case LOITER: + case RTL: + case CIRCLE: + case POSITION: + base_mode = MAV_MODE_FLAG_GUIDED_ENABLED | + MAV_MODE_FLAG_STABILIZE_ENABLED; + // note that MAV_MODE_FLAG_AUTO_ENABLED does not match what + // APM does in any mode, as that is defined as "system finds its own goal + // positions", which APM does not currently do + break; + case INITIALISING: //!!! + system_status = MAV_STATE_CALIBRATING; + break; + } + + if (control_mode != STABILIZE && control_mode != INITIALISING) { + // stabiliser of some form is enabled + base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; + } + +#if HIL_MODE != HIL_MODE_DISABLED + base_mode |= MAV_MODE_FLAG_HIL_ENABLED; +#endif + + // we are armed if we are not initialising + if (control_mode != INITIALISING) { + base_mode |= MAV_MODE_FLAG_SAFETY_ARMED; + } + + // indicate we have set a custom mode + base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; + + mavlink_msg_heartbeat_send( + chan, + MAV_TYPE_FIXED_WING, + MAV_AUTOPILOT_ARDUPILOTMEGA, + base_mode, + custom_mode, + system_status); +#else // MAVLINK10 + mavlink_msg_heartbeat_send( + chan, + mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); +#endif // MAVLINK10 +} + +static NOINLINE void send_attitude(mavlink_channel_t chan) +{ + Vector3f omega = dcm.get_gyro(); + mavlink_msg_attitude_send( + chan, + micros(), + dcm.roll, + dcm.pitch, + dcm.yaw, + omega.x, + omega.y, + omega.z); +} + +static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops) +{ +#ifdef MAVLINK10 + uint32_t control_sensors_present = 0; + uint32_t control_sensors_enabled; + uint32_t control_sensors_health; + + // first what sensors/controllers we have + control_sensors_present |= (1<<0); // 3D gyro present + control_sensors_present |= (1<<1); // 3D accelerometer present + + if (g.compass_enabled) { + control_sensors_present |= (1<<2); // compass present + } + + control_sensors_present |= (1<<3); // absolute pressure sensor present + + if (g_gps->fix) { + control_sensors_present |= (1<<5); // GPS present + } + + control_sensors_present |= (1<<10); // 3D angular rate control + control_sensors_present |= (1<<11); // attitude stabilisation + control_sensors_present |= (1<<12); // yaw position + control_sensors_present |= (1<<13); // altitude control + control_sensors_present |= (1<<14); // X/Y position control + control_sensors_present |= (1<<15); // motor control + + // now what sensors/controllers are enabled + + // first the sensors + control_sensors_enabled = control_sensors_present & 0x1FF; + + // now the controllers + control_sensors_enabled = control_sensors_present & 0x1FF; + + switch (control_mode) { + case STABILIZE: + control_sensors_enabled |= (1<<10); // 3D angular rate control + control_sensors_enabled |= (1<<11); // attitude stabilisation + break; + + case AUTO: + case RTL: + case LOITER: + case GUIDED: + case CIRCLE: + control_sensors_enabled |= (1<<10); // 3D angular rate control + control_sensors_enabled |= (1<<11); // attitude stabilisation + control_sensors_enabled |= (1<<12); // yaw position + control_sensors_enabled |= (1<<13); // altitude control + control_sensors_enabled |= (1<<14); // X/Y position control + control_sensors_enabled |= (1<<15); // motor control + break; + + case INITIALISING: + break; + } + + // at the moment all sensors/controllers are assumed healthy + control_sensors_health = control_sensors_present; + + uint16_t battery_current = -1; + uint8_t battery_remaining = -1; + + if (current_total != 0 && g.pack_capacity != 0) { + battery_remaining = (100.0 * (g.pack_capacity - current_total) / g.pack_capacity); + } + if (current_total != 0) { + battery_current = current_amps * 100; + } + + mavlink_msg_sys_status_send( + chan, + control_sensors_present, + control_sensors_enabled, + control_sensors_health, + 0, + battery_voltage * 1000, // mV + battery_current, // in 10mA units + battery_remaining, // in % + 0, // comm drops %, + 0, // comm drops in pkts, + 0, 0, 0, 0); + +#else // MAVLINK10 + uint8_t mode = MAV_MODE_UNINIT; + uint8_t nav_mode = MAV_NAV_VECTOR; + + switch(control_mode) { + case STABILIZE: + mode = MAV_MODE_TEST1; + break; + case GUIDED: + mode = MAV_MODE_GUIDED; + break; + case AUTO: + mode = MAV_MODE_AUTO; + nav_mode = MAV_NAV_WAYPOINT; + break; + case RTL: + mode = MAV_MODE_AUTO; + nav_mode = MAV_NAV_RETURNING; + break; + case LOITER: + mode = MAV_MODE_AUTO; + nav_mode = MAV_NAV_LOITER; + break; + case INITIALISING: + mode = MAV_MODE_UNINIT; + nav_mode = MAV_NAV_GROUNDED; + break; + } + + uint8_t status = MAV_STATE_ACTIVE; + uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 + + mavlink_msg_sys_status_send( + chan, + mode, + nav_mode, + status, + 0, + battery_voltage * 1000, + battery_remaining, + packet_drops); +#endif // MAVLINK10 +} + +static void NOINLINE send_meminfo(mavlink_channel_t chan) +{ + extern unsigned __brkval; + mavlink_msg_meminfo_send(chan, __brkval, memcheck_available_memory()); +} + +static void NOINLINE send_location(mavlink_channel_t chan) +{ + Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now + mavlink_msg_global_position_int_send( + chan, + millis(), + current_loc.lat, // in 1E7 degrees + current_loc.lng, // in 1E7 degrees + g_gps->altitude*10, // millimeters above sea level + current_loc.alt * 10, // millimeters above ground + g_gps->ground_speed * rot.a.x, // X speed cm/s + g_gps->ground_speed * rot.b.x, // Y speed cm/s + g_gps->ground_speed * rot.c.x, + g_gps->ground_course); // course in 1/100 degree +} + +static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) +{ + mavlink_msg_nav_controller_output_send( + chan, + nav_roll / 1.0e2, + nav_pitch / 1.0e2, + target_bearing / 1.0e2, + dcm.yaw_sensor / 1.0e2, // was target_bearing + wp_distance, + altitude_error / 1.0e2, + 0, + crosstrack_error); +} + +static void NOINLINE send_gps_raw(mavlink_channel_t chan) +{ +#ifdef MAVLINK10 + uint8_t fix = (g_gps->status() == 2) ? 3:0; + + mavlink_msg_gps_raw_int_send( + chan, + micros(), + fix, + g_gps->latitude, // in 1E7 degrees + g_gps->longitude, // in 1E7 degrees + g_gps->altitude * 10, // in mm + g_gps->hdop, + 65535, + g_gps->ground_speed, // cm/s + g_gps->ground_course, // 1/100 degrees, + g_gps->num_sats); + +#else // MAVLINK10 + mavlink_msg_gps_raw_send( + chan, + micros(), + g_gps->status(), + g_gps->latitude / 1.0e7, + g_gps->longitude / 1.0e7, + g_gps->altitude / 100.0, + g_gps->hdop, + current_loc.alt / 100.0, // was 0 + g_gps->ground_speed / 100.0, + g_gps->ground_course / 100.0); +#endif // MAVLINK10 +} + +static void NOINLINE send_servo_out(mavlink_channel_t chan) +{ + const uint8_t rssi = 1; + // normalized values scaled to -10000 to 10000 + // This is used for HIL. Do not change without discussing with HIL maintainers + mavlink_msg_rc_channels_scaled_send( + chan, + millis(), + 0, // port 0 + 10000 * g.rc_1.norm_output(), + 10000 * g.rc_2.norm_output(), + 10000 * g.rc_3.norm_output(), + 10000 * g.rc_4.norm_output(), + 0, + 0, + 0, + 0, + rssi); +} + +static void NOINLINE send_radio_in(mavlink_channel_t chan) +{ + const uint8_t rssi = 1; + mavlink_msg_rc_channels_raw_send( + chan, + millis(), + 0, // port + g.rc_1.radio_in, + g.rc_2.radio_in, + g.rc_3.radio_in, + g.rc_4.radio_in, + g.rc_5.radio_in, + g.rc_6.radio_in, + g.rc_7.radio_in, + g.rc_8.radio_in, + rssi); +} + +static void NOINLINE send_radio_out(mavlink_channel_t chan) +{ + mavlink_msg_servo_output_raw_send( + chan, + micros(), + 0, // port + motor_out[0], + motor_out[1], + motor_out[2], + motor_out[3], + motor_out[4], + motor_out[5], + motor_out[6], + motor_out[7]); +} + +static void NOINLINE send_vfr_hud(mavlink_channel_t chan) +{ + mavlink_msg_vfr_hud_send( + chan, + (float)airspeed / 100.0, + (float)g_gps->ground_speed / 100.0, + (dcm.yaw_sensor / 100) % 360, + g.rc_3.servo_out / 10, + current_loc.alt / 100.0, + climb_rate); +} + +#if HIL_MODE != HIL_MODE_ATTITUDE +static void NOINLINE send_raw_imu1(mavlink_channel_t chan) +{ + Vector3f accel = imu.get_accel(); + Vector3f gyro = imu.get_gyro(); + + mavlink_msg_raw_imu_send( + chan, + micros(), + accel.x * 1000.0 / gravity, + accel.y * 1000.0 / gravity, + accel.z * 1000.0 / gravity, + gyro.x * 1000.0, + gyro.y * 1000.0, + gyro.z * 1000.0, + compass.mag_x, + compass.mag_y, + compass.mag_z); +} + +static void NOINLINE send_raw_imu2(mavlink_channel_t chan) +{ + mavlink_msg_scaled_pressure_send( + chan, + micros(), + (float)barometer.Press/100.0, + (float)(barometer.Press - ground_pressure)/100.0, + (int)(barometer.Temp*10)); +} + +static void NOINLINE send_raw_imu3(mavlink_channel_t chan) +{ + Vector3f mag_offsets = compass.get_offsets(); + + mavlink_msg_sensor_offsets_send(chan, + mag_offsets.x, + mag_offsets.y, + mag_offsets.z, + compass.get_declination(), + barometer.RawPress, + barometer.RawTemp, + imu.gx(), imu.gy(), imu.gz(), + imu.ax(), imu.ay(), imu.az()); +} +#endif // HIL_MODE != HIL_MODE_ATTITUDE + +static void NOINLINE send_gps_status(mavlink_channel_t chan) +{ + mavlink_msg_gps_status_send( + chan, + g_gps->num_sats, + NULL, + NULL, + NULL, + NULL, + NULL); +} + +static void NOINLINE send_current_waypoint(mavlink_channel_t chan) +{ + mavlink_msg_waypoint_current_send( + chan, + g.command_index); +} + +static void NOINLINE send_statustext(mavlink_channel_t chan) +{ + mavlink_msg_statustext_send( + chan, + pending_status.severity, + pending_status.text); +} + + +// try to send a message, return false if it won't fit in the serial tx buffer +static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops) +{ + int payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES; + + if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) { + // defer any messages on the telemetry port for 1 second after + // bootup, to try to prevent bricking of Xbees + return false; + } + + switch (id) { + case MSG_HEARTBEAT: + CHECK_PAYLOAD_SIZE(HEARTBEAT); + send_heartbeat(chan); + return true; + + case MSG_EXTENDED_STATUS1: + CHECK_PAYLOAD_SIZE(SYS_STATUS); + send_extended_status1(chan, packet_drops); + break; + + case MSG_EXTENDED_STATUS2: + CHECK_PAYLOAD_SIZE(MEMINFO); + send_meminfo(chan); + break; + + case MSG_ATTITUDE: + CHECK_PAYLOAD_SIZE(ATTITUDE); + send_attitude(chan); + break; + + case MSG_LOCATION: + CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT); + send_location(chan); + break; + + case MSG_NAV_CONTROLLER_OUTPUT: + CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT); + send_nav_controller_output(chan); + break; + + case MSG_GPS_RAW: + #ifdef MAVLINK10 + CHECK_PAYLOAD_SIZE(GPS_RAW_INT); + #else + CHECK_PAYLOAD_SIZE(GPS_RAW); + #endif + send_gps_raw(chan); + break; + + case MSG_SERVO_OUT: + CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED); + send_servo_out(chan); + break; + + case MSG_RADIO_IN: + CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW); + send_radio_in(chan); + break; + + case MSG_RADIO_OUT: + CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); + send_radio_out(chan); + break; + + case MSG_VFR_HUD: + CHECK_PAYLOAD_SIZE(VFR_HUD); + send_vfr_hud(chan); + break; + +#if HIL_MODE != HIL_MODE_ATTITUDE + case MSG_RAW_IMU1: + CHECK_PAYLOAD_SIZE(RAW_IMU); + send_raw_imu1(chan); + break; + + case MSG_RAW_IMU2: + CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); + send_raw_imu2(chan); + break; + + case MSG_RAW_IMU3: + CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS); + send_raw_imu3(chan); + break; +#endif // HIL_MODE != HIL_MODE_ATTITUDE + + case MSG_GPS_STATUS: + CHECK_PAYLOAD_SIZE(GPS_STATUS); + send_gps_status(chan); + break; + + case MSG_CURRENT_WAYPOINT: + CHECK_PAYLOAD_SIZE(WAYPOINT_CURRENT); + send_current_waypoint(chan); + break; + + case MSG_NEXT_PARAM: + CHECK_PAYLOAD_SIZE(PARAM_VALUE); + if (chan == MAVLINK_COMM_0) { + gcs0.queued_param_send(); + } else { + gcs3.queued_param_send(); + } + break; + + case MSG_NEXT_WAYPOINT: + CHECK_PAYLOAD_SIZE(WAYPOINT_REQUEST); + if (chan == MAVLINK_COMM_0) { + gcs0.queued_waypoint_send(); + } else { + gcs3.queued_waypoint_send(); + } + break; + + case MSG_STATUSTEXT: + CHECK_PAYLOAD_SIZE(STATUSTEXT); + send_statustext(chan); + break; + + case MSG_RETRY_DEFERRED: + break; // just here to prevent a warning + } + return true; +} + + +#define MAX_DEFERRED_MESSAGES MSG_RETRY_DEFERRED +static struct mavlink_queue { + enum ap_message deferred_messages[MAX_DEFERRED_MESSAGES]; + uint8_t next_deferred_message; + uint8_t num_deferred_messages; +} mavlink_queue[2]; + +// send a message using mavlink +static void mavlink_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops) +{ + uint8_t i, nextid; + struct mavlink_queue *q = &mavlink_queue[(uint8_t)chan]; + + // see if we can send the deferred messages, if any + while (q->num_deferred_messages != 0) { + if (!mavlink_try_send_message(chan, + q->deferred_messages[q->next_deferred_message], + packet_drops)) { + break; + } + q->next_deferred_message++; + if (q->next_deferred_message == MAX_DEFERRED_MESSAGES) { + q->next_deferred_message = 0; + } + q->num_deferred_messages--; + } + + if (id == MSG_RETRY_DEFERRED) { + return; + } + + // this message id might already be deferred + for (i=0, nextid = q->next_deferred_message; i < q->num_deferred_messages; i++) { + if (q->deferred_messages[nextid] == id) { + // its already deferred, discard + return; + } + nextid++; + if (nextid == MAX_DEFERRED_MESSAGES) { + nextid = 0; + } + } + + if (q->num_deferred_messages != 0 || + !mavlink_try_send_message(chan, id, packet_drops)) { + // can't send it now, so defer it + if (q->num_deferred_messages == MAX_DEFERRED_MESSAGES) { + // the defer buffer is full, discard + return; + } + nextid = q->next_deferred_message + q->num_deferred_messages; + if (nextid >= MAX_DEFERRED_MESSAGES) { + nextid -= MAX_DEFERRED_MESSAGES; + } + q->deferred_messages[nextid] = id; + q->num_deferred_messages++; + } +} + +void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char *str) +{ + if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) { + // don't send status MAVLink messages for 2 seconds after + // bootup, to try to prevent Xbee bricking + return; + } + + if (severity == SEVERITY_LOW) { + // send via the deferred queuing system + pending_status.severity = (uint8_t)severity; + strncpy((char *)pending_status.text, str, sizeof(pending_status.text)); + mavlink_send_message(chan, MSG_STATUSTEXT, 0); + } else { + // send immediately + mavlink_msg_statustext_send( + chan, + severity, + (const int8_t*) str); + } +} + + +GCS_MAVLINK::GCS_MAVLINK(AP_Var::Key key) : +packet_drops(0), + +// parameters +// note, all values not explicitly initialised here are zeroed +waypoint_send_timeout(1000), // 1 second +waypoint_receive_timeout(1000), // 1 second + +// stream rates +_group (key, key == Parameters::k_param_streamrates_port0 ? PSTR("SR0_"): PSTR("SR3_")), + // AP_VAR //ref //index, default, name + streamRateRawSensors (&_group, 0, 0, PSTR("RAW_SENS")), + streamRateExtendedStatus (&_group, 1, 0, PSTR("EXT_STAT")), + streamRateRCChannels (&_group, 2, 0, PSTR("RC_CHAN")), + streamRateRawController (&_group, 3, 0, PSTR("RAW_CTRL")), + streamRatePosition (&_group, 4, 0, PSTR("POSITION")), + streamRateExtra1 (&_group, 5, 0, PSTR("EXTRA1")), + streamRateExtra2 (&_group, 6, 0, PSTR("EXTRA2")), + streamRateExtra3 (&_group, 7, 0, PSTR("EXTRA3")) +{ + +} + +void +GCS_MAVLINK::init(FastSerial * port) +{ + GCS_Class::init(port); + if (port == &Serial) { + mavlink_comm_0_port = port; + chan = MAVLINK_COMM_0; + }else{ + mavlink_comm_1_port = port; + chan = MAVLINK_COMM_1; + } + _queued_parameter = NULL; +} + +void +GCS_MAVLINK::update(void) +{ + // receive new packets + mavlink_message_t msg; + mavlink_status_t status; + status.packet_rx_drop_count = 0; + + // process received bytes + while(comm_get_available(chan)) + { + uint8_t c = comm_receive_ch(chan); + +#if CLI_ENABLED == ENABLED + /* allow CLI to be started by hitting enter 3 times, if no + heartbeat packets have been received */ + if (mavlink_active == false) { + if (c == '\n' || c == '\r') { + crlf_count++; + } else { + crlf_count = 0; + } + if (crlf_count == 3) { + run_cli(); + } + } +#endif + + // Try to get a new message + if (mavlink_parse_char(chan, c, &msg, &status)) { + mavlink_active = true; + handleMessage(&msg); + } + } + + // Update packet drops counter + packet_drops += status.packet_rx_drop_count; + + // send out queued params/ waypoints + if (NULL != _queued_parameter) { + send_message(MSG_NEXT_PARAM); + } + + if (!waypoint_receiving && !waypoint_sending) { + return; + } + + uint32_t tnow = millis(); + + if (waypoint_receiving && + waypoint_request_i < (unsigned)g.command_total && + tnow > waypoint_timelast_request + 500) { + waypoint_timelast_request = tnow; + send_message(MSG_NEXT_WAYPOINT); + } + + // stop waypoint sending if timeout + if (waypoint_sending && (tnow - waypoint_timelast_send) > waypoint_send_timeout){ + waypoint_sending = false; + } + + // stop waypoint receiving if timeout + if (waypoint_receiving && (tnow - waypoint_timelast_receive) > waypoint_receive_timeout){ + waypoint_receiving = false; + } +} + +void +GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax) +{ + if (waypoint_sending == false && waypoint_receiving == false && _queued_parameter == NULL) { + + if (freqLoopMatch(streamRateRawSensors, freqMin, freqMax)){ + send_message(MSG_RAW_IMU1); + send_message(MSG_RAW_IMU2); + send_message(MSG_RAW_IMU3); + } + + if (freqLoopMatch(streamRateExtendedStatus, freqMin, freqMax)) { + send_message(MSG_EXTENDED_STATUS1); + send_message(MSG_EXTENDED_STATUS2); + send_message(MSG_GPS_STATUS); + send_message(MSG_CURRENT_WAYPOINT); + send_message(MSG_GPS_RAW); // TODO - remove this message after location message is working + send_message(MSG_NAV_CONTROLLER_OUTPUT); + //Serial.printf("mav2 %d\n", (int)streamRateExtendedStatus.get()); + } + + if (freqLoopMatch(streamRatePosition, freqMin, freqMax)) { + // sent with GPS read + send_message(MSG_LOCATION); + } + + if (freqLoopMatch(streamRateRawController, freqMin, freqMax)) { + // This is used for HIL. Do not change without discussing with HIL maintainers + send_message(MSG_SERVO_OUT); + } + + if (freqLoopMatch(streamRateRCChannels, freqMin, freqMax)) { + send_message(MSG_RADIO_OUT); + send_message(MSG_RADIO_IN); + } + + if (freqLoopMatch(streamRateExtra1, freqMin, freqMax)){ // Use Extra 1 for AHRS info + send_message(MSG_ATTITUDE); + } + + if (freqLoopMatch(streamRateExtra2, freqMin, freqMax)){ // Use Extra 2 for additional HIL info + send_message(MSG_VFR_HUD); + } + + if (freqLoopMatch(streamRateExtra3, freqMin, freqMax)){ + // Available datastream + } + } +} + + + +void +GCS_MAVLINK::send_message(enum ap_message id) +{ + mavlink_send_message(chan, id, packet_drops); +} + +void +GCS_MAVLINK::send_text(gcs_severity severity, const char *str) +{ + mavlink_send_text(chan, severity, str); +} + +void +GCS_MAVLINK::send_text(gcs_severity severity, const prog_char_t *str) +{ + mavlink_statustext_t m; + uint8_t i; + for (i = 0; i < sizeof(m.text); i++) { + m.text[i] = pgm_read_byte((const prog_char *)(str++)); + } + if (i < sizeof(m.text)) m.text[i] = 0; + mavlink_send_text(chan, severity, (const char *)m.text); +} + +void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) +{ + struct Location tell_command = {}; // command for telemetry + static uint8_t mav_nav = 255; // For setting mode (some require receipt of 2 messages...) + + switch (msg->msgid) { + + case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: + { + // decode + mavlink_request_data_stream_t packet; + mavlink_msg_request_data_stream_decode(msg, &packet); + + if (mavlink_check_target(packet.target_system, packet.target_component)) + break; + + int freq = 0; // packet frequency + + if (packet.start_stop == 0) + freq = 0; // stop sending + else if (packet.start_stop == 1) + freq = packet.req_message_rate; // start sending + else + break; + + switch(packet.req_stream_id){ + + case MAV_DATA_STREAM_ALL: + streamRateRawSensors = freq; + streamRateExtendedStatus = freq; + streamRateRCChannels = freq; + streamRateRawController = freq; + streamRatePosition = freq; + streamRateExtra1 = freq; + streamRateExtra2 = freq; + //streamRateExtra3.set_and_save(freq); // We just do set and save on the last as it takes care of the whole group. + streamRateExtra3 = freq; // Don't save!! + break; + + case MAV_DATA_STREAM_RAW_SENSORS: + streamRateRawSensors = freq; // We do not set and save this one so that if HIL is shut down incorrectly + // we will not continue to broadcast raw sensor data at 50Hz. + break; + case MAV_DATA_STREAM_EXTENDED_STATUS: + streamRateExtendedStatus = freq; + break; + + case MAV_DATA_STREAM_RC_CHANNELS: + streamRateRCChannels = freq; + break; + + case MAV_DATA_STREAM_RAW_CONTROLLER: + streamRateRawController = freq; + break; + + //case MAV_DATA_STREAM_RAW_SENSOR_FUSION: + // streamRateRawSensorFusion.set_and_save(freq); + // break; + + case MAV_DATA_STREAM_POSITION: + streamRatePosition = freq; + break; + + case MAV_DATA_STREAM_EXTRA1: + streamRateExtra1 = freq; + break; + + case MAV_DATA_STREAM_EXTRA2: + streamRateExtra2 = freq; + break; + + case MAV_DATA_STREAM_EXTRA3: + streamRateExtra3 = freq; + break; + + default: + break; + } + break; + } + +#ifdef MAVLINK10 + case MAVLINK_MSG_ID_COMMAND_LONG: + { + // decode + mavlink_command_long_t packet; + mavlink_msg_command_long_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + uint8_t result; + + // do command + send_text(SEVERITY_LOW,PSTR("command received: ")); + + switch(packet.command) { + + case MAV_CMD_NAV_LOITER_UNLIM: + set_mode(LOITER); + result = MAV_RESULT_ACCEPTED; + break; + + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + set_mode(RTL); + result = MAV_RESULT_ACCEPTED; + break; + + #if 0 + // not implemented yet, but could implement some of them + case MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_NAV_ROI: + case MAV_CMD_NAV_PATHPLANNING: + break; + #endif + + + case MAV_CMD_PREFLIGHT_CALIBRATION: + if (packet.param1 == 1 || + packet.param2 == 1 || + packet.param3 == 1) { + startup_ground(); + } + if (packet.param4 == 1) { + trim_radio(); + } + result = MAV_RESULT_ACCEPTED; + break; + + + default: + result = MAV_RESULT_UNSUPPORTED; + break; + } + + mavlink_msg_command_ack_send( + chan, + packet.command, + result); + + break; + } + +#else // MAVLINK10 + case MAVLINK_MSG_ID_ACTION: + { + // decode + mavlink_action_t packet; + mavlink_msg_action_decode(msg, &packet); + if (mavlink_check_target(packet.target, packet.target_component)) break; + + if (in_mavlink_delay) { + // don't execute action commands while in sensor + // initialisation + break; + } + + uint8_t result = 0; + + // do action + send_text(SEVERITY_LOW,PSTR("action received: ")); +//Serial.println(packet.action); + switch(packet.action){ + + case MAV_ACTION_LAUNCH: + //set_mode(TAKEOFF); + break; + + case MAV_ACTION_RETURN: + set_mode(RTL); + result = 1; + break; + + case MAV_ACTION_EMCY_LAND: + //set_mode(LAND); + break; + + case MAV_ACTION_HALT: + do_loiter_at_location(); + result = 1; + break; + + /* No mappable implementation in APM 2.0 + case MAV_ACTION_MOTORS_START: + case MAV_ACTION_CONFIRM_KILL: + case MAV_ACTION_EMCY_KILL: + case MAV_ACTION_MOTORS_STOP: + case MAV_ACTION_SHUTDOWN: + break; + */ + + case MAV_ACTION_CONTINUE: + //process_command_queue(); + result = 1; + break; + + case MAV_ACTION_SET_MANUAL: + set_mode(STABILIZE); + result = 1; + break; + + case MAV_ACTION_SET_AUTO: + set_mode(AUTO); + result = 1; + break; + + case MAV_ACTION_STORAGE_READ: + AP_Var::load_all(); + result = 1; + break; + + case MAV_ACTION_STORAGE_WRITE: + AP_Var::save_all(); + result = 1; + break; + + case MAV_ACTION_CALIBRATE_RC: break; + trim_radio(); + result = 1; + break; + + case MAV_ACTION_CALIBRATE_GYRO: + case MAV_ACTION_CALIBRATE_MAG: + case MAV_ACTION_CALIBRATE_PRESSURE: + //case MAV_ACTION_REBOOT: // this is a rough interpretation + startup_ground(); + result=1; + break; + + case MAV_ACTION_CALIBRATE_ACC: + imu.init_accel(mavlink_delay); + result = 1; + break; + + /* For future implemtation + case MAV_ACTION_REC_START: break; + case MAV_ACTION_REC_PAUSE: break; + case MAV_ACTION_REC_STOP: break; + */ + + /* Takeoff is not an implemented flight mode in APM 2.0 + case MAV_ACTION_TAKEOFF: + set_mode(TAKEOFF); + break; + */ + + case MAV_ACTION_NAVIGATE: + set_mode(AUTO); + result = 1; + break; + + /* Land is not an implemented flight mode in APM 2.0 + case MAV_ACTION_LAND: + set_mode(LAND); + break; + */ + + case MAV_ACTION_LOITER: + set_mode(LOITER); + result = 1; + break; + + default: break; + } + + mavlink_msg_action_ack_send( + chan, + packet.action, + result + ); + + break; + } +#endif + + case MAVLINK_MSG_ID_SET_MODE: + { + // decode + mavlink_set_mode_t packet; + mavlink_msg_set_mode_decode(msg, &packet); + +#ifdef MAVLINK10 + if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) { + // we ignore base_mode as there is no sane way to map + // from that bitmap to a APM flight mode. We rely on + // custom_mode instead. + break; + } + switch (packet.custom_mode) { + case CIRCLE: + case STABILIZE: + case AUTO: + case RTL: + case LOITER: + set_mode(packet.custom_mode); + break; + } + +#else // MAVLINK10 + + switch(packet.mode){ + + case MAV_MODE_MANUAL: + set_mode(STABILIZE); + break; + + case MAV_MODE_GUIDED: + set_mode(GUIDED); + break; + + case MAV_MODE_AUTO: + if(mav_nav == 255 || mav_nav == MAV_NAV_WAYPOINT) + set_mode(AUTO); + if(mav_nav == MAV_NAV_RETURNING) + set_mode(RTL); + if(mav_nav == MAV_NAV_LOITER) + set_mode(LOITER); + mav_nav = 255; + break; + + case MAV_MODE_TEST1: + set_mode(STABILIZE); + break; + } +#endif + break; + } + +#ifndef MAVLINK10 + case MAVLINK_MSG_ID_SET_NAV_MODE: + { + // decode + mavlink_set_nav_mode_t packet; + mavlink_msg_set_nav_mode_decode(msg, &packet); + // To set some flight modes we must first receive a "set nav mode" message and then a "set mode" message + mav_nav = packet.nav_mode; + break; + } +#endif // MAVLINK10 + + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: + { + // decode + mavlink_waypoint_request_list_t packet; + mavlink_msg_waypoint_request_list_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) + break; + + // Start sending waypoints + mavlink_msg_waypoint_count_send( + chan, msg->sysid, + msg->compid, + g.command_total); // includes home + + waypoint_timelast_send = millis(); + waypoint_sending = true; + waypoint_receiving = false; + waypoint_dest_sysid = msg->sysid; + waypoint_dest_compid = msg->compid; + break; + } + + // XXX read a WP from EEPROM and send it to the GCS + case MAVLINK_MSG_ID_WAYPOINT_REQUEST: + { + // Check if sending waypiont + //if (!waypoint_sending) break; + // 5/10/11 - We are trying out relaxing the requirement that we be in waypoint sending mode to respond to a waypoint request. DEW + + // decode + mavlink_waypoint_request_t packet; + mavlink_msg_waypoint_request_decode(msg, &packet); + + if (mavlink_check_target(packet.target_system, packet.target_component)) + break; + + // send waypoint + tell_command = get_cmd_with_index(packet.seq); + + // set frame of waypoint + uint8_t frame; + + if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) { + frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; // reference frame + } else { + frame = MAV_FRAME_GLOBAL; // reference frame + } + + float param1 = 0, param2 = 0 , param3 = 0, param4 = 0; + + // time that the mav should loiter in milliseconds + uint8_t current = 0; // 1 (true), 0 (false) + + if (packet.seq == (uint16_t)g.command_index) + current = 1; + + uint8_t autocontinue = 1; // 1 (true), 0 (false) + + float x = 0, y = 0, z = 0; + + if (tell_command.id < MAV_CMD_NAV_LAST || tell_command.id == MAV_CMD_CONDITION_CHANGE_ALT) { + // command needs scaling + x = tell_command.lat / 1.0e7; // local (x), global (latitude) + y = tell_command.lng / 1.0e7; // local (y), global (longitude) + // ACM is processing alt inside each command. so we save and load raw values. - this is diffrent to APM + z = tell_command.alt / 1.0e2; // local (z), global / relative (altitude) + } + + // Switch to map APM command fields inot MAVLink command fields + switch (tell_command.id) { + + case MAV_CMD_NAV_LOITER_TURNS: + case MAV_CMD_CONDITION_CHANGE_ALT: + case MAV_CMD_DO_SET_HOME: + param1 = tell_command.p1; + break; + + case MAV_CMD_CONDITION_YAW: + param3 = tell_command.p1; + param1 = tell_command.alt; + param2 = tell_command.lat; + param4 = tell_command.lng; + break; + + case MAV_CMD_NAV_TAKEOFF: + param1 = 0; + break; + + case MAV_CMD_NAV_LOITER_TIME: + param1 = tell_command.p1; // ACM loiter time is in 1 second increments + break; + + case MAV_CMD_CONDITION_DELAY: + case MAV_CMD_CONDITION_DISTANCE: + param1 = tell_command.lat; + break; + + case MAV_CMD_DO_JUMP: + param2 = tell_command.lat; + param1 = tell_command.p1; + break; + + case MAV_CMD_DO_REPEAT_SERVO: + param4 = tell_command.lng; + case MAV_CMD_DO_REPEAT_RELAY: + case MAV_CMD_DO_CHANGE_SPEED: + param3 = tell_command.lat; + param2 = tell_command.alt; + param1 = tell_command.p1; + break; + + case MAV_CMD_NAV_WAYPOINT: + param1 = tell_command.p1; + break; + + case MAV_CMD_DO_SET_PARAMETER: + case MAV_CMD_DO_SET_RELAY: + case MAV_CMD_DO_SET_SERVO: + param2 = tell_command.alt; + param1 = tell_command.p1; + break; + } + + mavlink_msg_waypoint_send(chan, msg->sysid, + msg->compid, + packet.seq, + frame, + tell_command.id, + current, + autocontinue, + param1, + param2, + param3, + param4, + x, + y, + z); + + // update last waypoint comm stamp + waypoint_timelast_send = millis(); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_ACK: + { + // decode + mavlink_waypoint_ack_t packet; + mavlink_msg_waypoint_ack_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + // turn off waypoint send + waypoint_sending = false; + break; + } + + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: + { + // decode + mavlink_param_request_list_t packet; + mavlink_msg_param_request_list_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + // Start sending parameters - next call to ::update will kick the first one out + + _queued_parameter = AP_Var::first(); + _queued_parameter_index = 0; + _queued_parameter_count = _count_parameters(); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: + { + // decode + mavlink_waypoint_clear_all_t packet; + mavlink_msg_waypoint_clear_all_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + // clear all commands + g.command_total.set_and_save(1); + + // note that we don't send multiple acks, as otherwise a + // GCS that is doing a clear followed by a set may see + // the additional ACKs as ACKs of the set operations + mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: + { + // decode + mavlink_waypoint_set_current_t packet; + mavlink_msg_waypoint_set_current_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + // set current command + change_command(packet.seq); + + mavlink_msg_waypoint_current_send(chan, g.command_index); + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_COUNT: + { + // decode + mavlink_waypoint_count_t packet; + mavlink_msg_waypoint_count_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + // start waypoint receiving + if (packet.count > MAX_WAYPOINTS) { + packet.count = MAX_WAYPOINTS; + } + g.command_total.set_and_save(packet.count); + + waypoint_timelast_receive = millis(); + waypoint_receiving = true; + waypoint_sending = false; + waypoint_request_i = 0; + waypoint_timelast_request = 0; + break; + } + +#ifdef MAVLINK_MSG_ID_SET_MAG_OFFSETS + case MAVLINK_MSG_ID_SET_MAG_OFFSETS: + { + mavlink_set_mag_offsets_t packet; + mavlink_msg_set_mag_offsets_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + compass.set_offsets(Vector3f(packet.mag_ofs_x, packet.mag_ofs_y, packet.mag_ofs_z)); + break; + } +#endif + + // XXX receive a WP from GCS and store in EEPROM + case MAVLINK_MSG_ID_WAYPOINT: + { + // decode + mavlink_waypoint_t packet; + uint8_t result = MAV_MISSION_ACCEPTED; + + mavlink_msg_waypoint_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + // defaults + tell_command.id = packet.command; + + switch (packet.frame) + { + case MAV_FRAME_MISSION: + case MAV_FRAME_GLOBAL: + { + tell_command.lat = 1.0e7*packet.x; // in as DD converted to * t7 + tell_command.lng = 1.0e7*packet.y; // in as DD converted to * t7 + tell_command.alt = packet.z*1.0e2; // in as m converted to cm + tell_command.options = 0; // absolute altitude + break; + } + + #ifdef MAV_FRAME_LOCAL_NED + case MAV_FRAME_LOCAL_NED: // local (relative to home position) + { + tell_command.lat = 1.0e7*ToDeg(packet.x/ + (radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lat; + tell_command.lng = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lng; + tell_command.alt = -packet.z*1.0e2; + tell_command.options = MASK_OPTIONS_RELATIVE_ALT; + break; + } + #endif + + #ifdef MAV_FRAME_LOCAL + case MAV_FRAME_LOCAL: // local (relative to home position) + { + tell_command.lat = 1.0e7*ToDeg(packet.x/ + (radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lat; + tell_command.lng = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lng; + tell_command.alt = packet.z*1.0e2; + tell_command.options = MASK_OPTIONS_RELATIVE_ALT; + break; + } + #endif + + case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude + { + tell_command.lat = 1.0e7 * packet.x; // in as DD converted to * t7 + tell_command.lng = 1.0e7 * packet.y; // in as DD converted to * t7 + tell_command.alt = packet.z * 1.0e2; + tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!! + break; + } + + default: + result = MAV_MISSION_UNSUPPORTED_FRAME; + break; + } + + + if (result != MAV_MISSION_ACCEPTED) goto mission_failed; + + switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields + + case MAV_CMD_NAV_LOITER_UNLIM: + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + case MAV_CMD_NAV_LAND: + break; + + case MAV_CMD_NAV_LOITER_TURNS: + case MAV_CMD_DO_SET_HOME: + case MAV_CMD_DO_SET_ROI: + tell_command.p1 = packet.param1; + break; + + case MAV_CMD_CONDITION_YAW: + tell_command.p1 = packet.param3; + tell_command.alt = packet.param1; + tell_command.lat = packet.param2; + tell_command.lng = packet.param4; + break; + + case MAV_CMD_NAV_TAKEOFF: + tell_command.p1 = 0; + break; + + case MAV_CMD_CONDITION_CHANGE_ALT: + tell_command.p1 = packet.param1 * 100; + break; + + case MAV_CMD_NAV_LOITER_TIME: + tell_command.p1 = packet.param1; // ACM is in seconds + break; + + case MAV_CMD_CONDITION_DELAY: + case MAV_CMD_CONDITION_DISTANCE: + tell_command.lat = packet.param1; + break; + + case MAV_CMD_DO_JUMP: + tell_command.lat = packet.param2; + tell_command.p1 = packet.param1; + break; + + case MAV_CMD_DO_REPEAT_SERVO: + tell_command.lng = packet.param4; + case MAV_CMD_DO_REPEAT_RELAY: + case MAV_CMD_DO_CHANGE_SPEED: + tell_command.lat = packet.param3; + tell_command.alt = packet.param2; + tell_command.p1 = packet.param1; + break; + + case MAV_CMD_NAV_WAYPOINT: + tell_command.p1 = packet.param1; + break; + + case MAV_CMD_DO_SET_PARAMETER: + case MAV_CMD_DO_SET_RELAY: + case MAV_CMD_DO_SET_SERVO: + tell_command.alt = packet.param2; + tell_command.p1 = packet.param1; + break; + + default: + #ifdef MAVLINK10 + result = MAV_MISSION_UNSUPPORTED; + #endif + break; + } + + if (result != MAV_MISSION_ACCEPTED) goto mission_failed; + + if(packet.current == 2){ //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission + guided_WP = tell_command; + + // add home alt if needed + if (guided_WP.options & MASK_OPTIONS_RELATIVE_ALT){ + guided_WP.alt += home.alt; + } + + set_mode(GUIDED); + + // make any new wp uploaded instant (in case we are already in Guided mode) + set_next_WP(&guided_WP); + + // verify we recevied the command + mavlink_msg_waypoint_ack_send( + chan, + msg->sysid, + msg->compid, + 0); + + } else { + // Check if receiving waypoints (mission upload expected) + if (!waypoint_receiving) { + result = MAV_MISSION_ERROR; + goto mission_failed; + } + + // check if this is the requested waypoint + if (packet.seq != waypoint_request_i) { + result = MAV_MISSION_INVALID_SEQUENCE; + goto mission_failed; + } + + if(packet.seq != 0) + set_cmd_with_index(tell_command, packet.seq); + + // update waypoint receiving state machine + waypoint_timelast_receive = millis(); + waypoint_timelast_request = 0; + waypoint_request_i++; + + if (waypoint_request_i == (uint16_t)g.command_total){ + mavlink_msg_waypoint_ack_send( + chan, + msg->sysid, + msg->compid, + result); + + send_text(SEVERITY_LOW,PSTR("flight plan received")); + waypoint_receiving = false; + // XXX ignores waypoint radius for individual waypoints, can + // only set WP_RADIUS parameter + } + } + break; + + mission_failed: + // we are rejecting the mission/waypoint + mavlink_msg_waypoint_ack_send( + chan, + msg->sysid, + msg->compid, + result); + break; + } + + case MAVLINK_MSG_ID_PARAM_SET: + { + AP_Var *vp; + AP_Meta_class::Type_id var_type; + + // decode + mavlink_param_set_t packet; + mavlink_msg_param_set_decode(msg, &packet); + + if (mavlink_check_target(packet.target_system, packet.target_component)) + break; + + // set parameter + + char key[ONBOARD_PARAM_NAME_LENGTH + 1]; + strncpy(key, (char *)packet.param_id, ONBOARD_PARAM_NAME_LENGTH); + key[ONBOARD_PARAM_NAME_LENGTH] = 0; + + // find the requested parameter + vp = AP_Var::find(key); + + if ((NULL != vp) && // exists + !isnan(packet.param_value) && // not nan + !isinf(packet.param_value)) { // not inf + + // add a small amount before casting parameter values + // from float to integer to avoid truncating to the + // next lower integer value. + float rounding_addition = 0.01; + + // fetch the variable type ID + var_type = vp->meta_type_id(); + + // handle variables with standard type IDs + if (var_type == AP_Var::k_typeid_float) { + ((AP_Float *)vp)->set_and_save(packet.param_value); + Log_Write_Data(1, (float)((AP_Float *)vp)->get()); + + } else if (var_type == AP_Var::k_typeid_float16) { + ((AP_Float16 *)vp)->set_and_save(packet.param_value); + Log_Write_Data(2, (float)((AP_Float *)vp)->get()); + + } else if (var_type == AP_Var::k_typeid_int32) { + if (packet.param_value < 0) rounding_addition = -rounding_addition; + ((AP_Int32 *)vp)->set_and_save(packet.param_value + rounding_addition); + Log_Write_Data(3, (int32_t)((AP_Float *)vp)->get()); + + } else if (var_type == AP_Var::k_typeid_int16) { + if (packet.param_value < 0) rounding_addition = -rounding_addition; + ((AP_Int16 *)vp)->set_and_save(packet.param_value + rounding_addition); + Log_Write_Data(4, (int32_t)((AP_Float *)vp)->get()); + + } else if (var_type == AP_Var::k_typeid_int8) { + if (packet.param_value < 0) rounding_addition = -rounding_addition; + ((AP_Int8 *)vp)->set_and_save(packet.param_value + rounding_addition); + Log_Write_Data(5, (int32_t)((AP_Float *)vp)->get()); + + } else { + // we don't support mavlink set on this parameter + break; + } + + // Report back the new value if we accepted the change + // we send the value we actually set, which could be + // different from the value sent, in case someone sent + // a fractional value to an integer type + mavlink_msg_param_value_send( + chan, + key, + vp->cast_to_float(), + mav_var_type(vp->meta_type_id()), + _count_parameters(), + -1); // XXX we don't actually know what its index is... + } + + break; + } // end case + + case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: + { + // allow override of RC channel values for HIL + // or for complete GCS control of switch position + // and RC PWM values. + if(msg->sysid != g.sysid_my_gcs) break; // Only accept control from our gcs + mavlink_rc_channels_override_t packet; + int16_t v[8]; + mavlink_msg_rc_channels_override_decode(msg, &packet); + + if (mavlink_check_target(packet.target_system, packet.target_component)) + break; + + v[0] = packet.chan1_raw; + v[1] = packet.chan2_raw; + v[2] = packet.chan3_raw; + v[3] = packet.chan4_raw; + v[4] = packet.chan5_raw; + v[5] = packet.chan6_raw; + v[6] = packet.chan7_raw; + v[7] = packet.chan8_raw; + //rc_override_active = APM_RC.setHIL(v); + rc_override_fs_timer = millis(); + break; + } + + case MAVLINK_MSG_ID_HEARTBEAT: + { + // We keep track of the last time we received a heartbeat from our GCS for failsafe purposes + if(msg->sysid != g.sysid_my_gcs) break; + rc_override_fs_timer = millis(); + pmTest1++; + break; + } + + #if HIL_MODE != HIL_MODE_DISABLED + // This is used both as a sensor and to pass the location + // in HIL_ATTITUDE mode. +#ifdef MAVLINK10 + case MAVLINK_MSG_ID_GPS_RAW_INT: + { + // decode + mavlink_gps_raw_int_t packet; + mavlink_msg_gps_raw_int_decode(msg, &packet); + + // set gps hil sensor + g_gps->setHIL(packet.time_usec/1000.0, + packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3, + packet.vel*1.0e-2, packet.cog*1.0e-2, 0, 0); + break; + } +#else // MAVLINK10 + case MAVLINK_MSG_ID_GPS_RAW: + { + // decode + mavlink_gps_raw_t packet; + mavlink_msg_gps_raw_decode(msg, &packet); + + // set gps hil sensor + g_gps->setHIL(packet.usec / 1000.0, packet.lat, packet.lon, packet.alt, + packet.v, packet.hdg, 0, 0); + break; + } +#endif // MAVLINK10 + + // Is this resolved? - MAVLink protocol change..... + case MAVLINK_MSG_ID_VFR_HUD: + { + // decode + mavlink_vfr_hud_t packet; + mavlink_msg_vfr_hud_decode(msg, &packet); + + // set airspeed + airspeed = 100 * packet.airspeed; + break; + } +#ifdef MAVLINK10 + case MAVLINK_MSG_ID_HIL_STATE: + { + mavlink_hil_state_t packet; + mavlink_msg_hil_state_decode(msg, &packet); + + float vel = sqrt((packet.vx * packet.vx) + (packet.vy * packet.vy)); + float cog = wrap_360(ToDeg(atan2(packet.vx, packet.vy)) * 100); + + // set gps hil sensor + g_gps->setHIL(packet.time_usec/1000.0, + packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3, + vel*1.0e-2, cog*1.0e-2, 0, 0); + + #if HIL_MODE == HIL_MODE_SENSORS + + // rad/sec + Vector3f gyros; + gyros.x = (float)packet.xgyro / 1000.0; + gyros.y = (float)packet.ygyro / 1000.0; + gyros.z = (float)packet.zgyro / 1000.0; + // m/s/s + Vector3f accels; + accels.x = (float)packet.xacc / 1000.0; + accels.y = (float)packet.yacc / 1000.0; + accels.z = (float)packet.zacc / 1000.0; + + imu.set_gyro(gyros); + + imu.set_accel(accels); + + #else + + // set dcm hil sensor + dcm.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed, + packet.pitchspeed,packet.yawspeed); + + #endif + + break; + } +#endif // MAVLINK10 +#endif +#if HIL_MODE == HIL_MODE_ATTITUDE + case MAVLINK_MSG_ID_ATTITUDE: + { + // decode + mavlink_attitude_t packet; + mavlink_msg_attitude_decode(msg, &packet); + + // set dcm hil sensor + dcm.setHil(packet.roll, packet.pitch, packet.yaw, packet.rollspeed, + packet.pitchspeed, packet.yawspeed); + break; + } +#endif +#if HIL_MODE == HIL_MODE_SENSORS + + case MAVLINK_MSG_ID_RAW_IMU: + { + // decode + mavlink_raw_imu_t packet; + mavlink_msg_raw_imu_decode(msg, &packet); + + // set imu hil sensors + // TODO: check scaling for temp/absPress + float temp = 70; + float absPress = 1; + // Serial.printf_P(PSTR("accel:\t%d\t%d\t%d\n"), packet.xacc, packet.yacc, packet.zacc); + // Serial.printf_P(PSTR("gyro:\t%d\t%d\t%d\n"), packet.xgyro, packet.ygyro, packet.zgyro); + + // rad/sec + Vector3f gyros; + gyros.x = (float)packet.xgyro / 1000.0; + gyros.y = (float)packet.ygyro / 1000.0; + gyros.z = (float)packet.zgyro / 1000.0; + // m/s/s + Vector3f accels; + accels.x = (float)packet.xacc / 1000.0; + accels.y = (float)packet.yacc / 1000.0; + accels.z = (float)packet.zacc / 1000.0; + + imu.set_gyro(gyros); + + imu.set_accel(accels); + + compass.setHIL(packet.xmag, packet.ymag, packet.zmag); + break; + } + + case MAVLINK_MSG_ID_RAW_PRESSURE: + { + // decode + mavlink_raw_pressure_t packet; + mavlink_msg_raw_pressure_decode(msg, &packet); + + // set pressure hil sensor + // TODO: check scaling + float temp = 70; + barometer.setHIL(temp,packet.press_diff1 + 101325); + break; + } +#endif // HIL_MODE + +#if MOUNT == ENABLED + case MAVLINK_MSG_ID_MOUNT_CONFIGURE: + { + camera_mount.configure_msg(msg); + break; + } + + case MAVLINK_MSG_ID_MOUNT_CONTROL: + { + camera_mount.control_msg(msg); + break; + } + + case MAVLINK_MSG_ID_MOUNT_STATUS: + { + camera_mount.status_msg(msg); + break; + } +#endif // MOUNT == ENABLED + } // end switch +} // end handle mavlink + +uint16_t +GCS_MAVLINK::_count_parameters() +{ + // if we haven't cached the parameter count yet... + if (0 == _parameter_count) { + AP_Var *vp; + + vp = AP_Var::first(); + do { + // if a parameter responds to cast_to_float then we are going to be able to report it + if (!isnan(vp->cast_to_float())) { + _parameter_count++; + } + } while (NULL != (vp = vp->next())); + } + return _parameter_count; +} + +AP_Var * +GCS_MAVLINK::_find_parameter(uint16_t index) +{ + AP_Var *vp; + + vp = AP_Var::first(); + while (NULL != vp) { + + // if the parameter is reportable + if (!(isnan(vp->cast_to_float()))) { + // if we have counted down to the index we want + if (0 == index) { + // return the parameter + return vp; + } + // count off this parameter, as it is reportable but not + // the one we want + index--; + } + // and move to the next parameter + vp = vp->next(); + } + return NULL; +} + +/** +* @brief Send the next pending parameter, called from deferred message +* handling code +*/ +void +GCS_MAVLINK::queued_param_send() +{ + // Check to see if we are sending parameters + if (NULL == _queued_parameter) return; + + AP_Var *vp; + float value; + + // copy the current parameter and prepare to move to the next + vp = _queued_parameter; + _queued_parameter = _queued_parameter->next(); + + // if the parameter can be cast to float, report it here and break out of the loop + value = vp->cast_to_float(); + if (!isnan(value)) { + char param_name[ONBOARD_PARAM_NAME_LENGTH]; // / XXX HACK + vp->copy_name(param_name, sizeof(param_name)); + + mavlink_msg_param_value_send( + chan, + param_name, + value, + mav_var_type(vp->meta_type_id()), + _queued_parameter_count, + _queued_parameter_index); + + _queued_parameter_index++; + } +} + +/** +* @brief Send the next pending waypoint, called from deferred message +* handling code +*/ +void +GCS_MAVLINK::queued_waypoint_send() +{ + if (waypoint_receiving && + waypoint_request_i < (unsigned)g.command_total) { + mavlink_msg_waypoint_request_send( + chan, + waypoint_dest_sysid, + waypoint_dest_compid, + waypoint_request_i); + } +} + +/* + a delay() callback that processes MAVLink packets. We set this as the + callback in long running library initialisation routines to allow + MAVLink to process packets while waiting for the initialisation to + complete +*/ +static void mavlink_delay(unsigned long t) +{ + uint32_t tstart; + static uint32_t last_1hz, last_50hz; + + if (in_mavlink_delay) { + // this should never happen, but let's not tempt fate by + // letting the stack grow too much + delay(t); + return; + } + + in_mavlink_delay = true; + + tstart = millis(); + do { + uint32_t tnow = millis(); + if (tnow - last_1hz > 1000) { + last_1hz = tnow; + gcs_send_message(MSG_HEARTBEAT); + gcs_send_message(MSG_EXTENDED_STATUS1); + } + if (tnow - last_50hz > 20) { + last_50hz = tnow; + gcs_update(); + } + delay(1); + } while (millis() - tstart < t); + + in_mavlink_delay = false; +} + +/* + send a message on both GCS links + */ +static void gcs_send_message(enum ap_message id) +{ + gcs0.send_message(id); + gcs3.send_message(id); +} + +/* + send data streams in the given rate range on both links + */ +static void gcs_data_stream_send(uint16_t freqMin, uint16_t freqMax) +{ + gcs0.data_stream_send(freqMin, freqMax); + gcs3.data_stream_send(freqMin, freqMax); +} + +/* + look for incoming commands on the GCS links + */ +static void gcs_update(void) +{ + gcs0.update(); + gcs3.update(); +} + +static void gcs_send_text(gcs_severity severity, const char *str) +{ + gcs0.send_text(severity, str); + gcs3.send_text(severity, str); +} + +static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str) +{ + gcs0.send_text(severity, str); + gcs3.send_text(severity, str); +} + +/* + send a low priority formatted message to the GCS + only one fits in the queue, so if you send more than one before the + last one gets into the serial buffer then the old one will be lost + */ +static void gcs_send_text_fmt(const prog_char_t *fmt, ...) +{ + char fmtstr[40]; + va_list ap; + uint8_t i; + for (i = 0; i < sizeof(fmtstr)-1; i++) { + fmtstr[i] = pgm_read_byte((const prog_char *)(fmt++)); + if (fmtstr[i] == 0) break; + } + fmtstr[i] = 0; + pending_status.severity = (uint8_t)SEVERITY_LOW; + va_start(ap, fmt); + vsnprintf((char *)pending_status.text, sizeof(pending_status.text), fmtstr, ap); + va_end(ap); + mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0); + mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0); +} From 02591d8d389c4e45e72c534e266fe2a46172857a Mon Sep 17 00:00:00 2001 From: Hazy Date: Sun, 20 Nov 2011 20:16:47 +0800 Subject: [PATCH 42/63] APM Planner - fix "Invalid Board Type" bug for board using mega32u2 --- Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 9eaeb83689..698fe0c59e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -510,7 +510,7 @@ namespace ArdupilotMega.GCSViews Console.WriteLine("Detected a " + board); string baseurl = ""; - if (board == "2560") + if (board == "2560" || board == "2560-2") { baseurl = temp.url2560.ToString(); } @@ -605,7 +605,7 @@ namespace ArdupilotMega.GCSViews //port = new ArduinoSTK(); port.BaudRate = 57600; } - else if (board == "2560") + else if (board == "2560" || board == "2560-2") { port = new ArduinoSTKv2(); port.BaudRate = 115200; From f397bae793b9740fd8ce8e4ec0308bd092072d07 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 20 Nov 2011 22:30:42 +0900 Subject: [PATCH 43/63] ArduCopter Alt Hold - Change to not run get_nav_throttle if manually adjusting altitude with manual_boost - removes possibility of I term running up Tuning - added ability to modify altitude (position, not rate) controller TradHeli - Fairly large change to how throttle is scaled and collective moves. --- ArduCopter/ArduCopter.pde | 47 ++++++++++------ ArduCopter/defines.h | 5 +- ArduCopter/heli.pde | 115 +++++++++++++++++++++++--------------- 3 files changed, 104 insertions(+), 63 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index ceceeb28af..0d9e2d4c68 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1057,7 +1057,7 @@ void update_throttle_mode(void) case THROTTLE_MANUAL: if (g.rc_3.control_in > 0){ #if FRAME_CONFIG == HELI_FRAME - g.rc_3.servo_out = heli_get_angle_boost(heli_get_scaled_throttle(g.rc_3.control_in)); + g.rc_3.servo_out = heli_get_angle_boost(g.rc_3.control_in); #else angle_boost = get_angle_boost(g.rc_3.control_in); g.rc_3.servo_out = g.rc_3.control_in + angle_boost; @@ -1077,34 +1077,40 @@ void update_throttle_mode(void) // fall through case THROTTLE_AUTO: - // 10hz, don't run up i term - if(invalid_throttle && motor_auto_armed == true){ - // how far off are we - altitude_error = get_altitude_error(); - - // get the AP throttle - nav_throttle = get_nav_throttle(altitude_error);//, 250); //150 = target speed of 1.5m/s - //Serial.printf("in:%d, cr:%d, NT:%d, I:%1.4f\n", g.rc_3.control_in,altitude_error, nav_throttle, g.pi_throttle.get_integrator()); - - // clear the new data flag - invalid_throttle = false; - } + // calculate angle boost angle_boost = get_angle_boost(g.throttle_cruise); - + + // manual command up or down? if(manual_boost != 0){ + //remove alt_hold_velocity when implemented #if FRAME_CONFIG == HELI_FRAME - g.rc_3.servo_out = heli_get_angle_boost(heli_get_scaled_throttle(g.throttle_cruise + nav_throttle + manual_boost + get_z_damping())); + g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + manual_boost + get_z_damping()); #else g.rc_3.servo_out = g.throttle_cruise + angle_boost + manual_boost + get_z_damping(); #endif + // reset next_WP.alt next_WP.alt = max(current_loc.alt, 100); + }else{ + // 10hz, don't run up i term + if(invalid_throttle && motor_auto_armed == true){ + + // how far off are we + altitude_error = get_altitude_error(); + + // get the AP throttle + nav_throttle = get_nav_throttle(altitude_error);//, 250); //150 = target speed of 1.5m/s + //Serial.printf("in:%d, cr:%d, NT:%d, I:%1.4f\n", g.rc_3.control_in,altitude_error, nav_throttle, g.pi_throttle.get_integrator()); + + // clear the new data flag + invalid_throttle = false; + } + #if FRAME_CONFIG == HELI_FRAME - //g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + nav_throttle + get_z_damping()); - g.rc_3.servo_out = heli_get_angle_boost(heli_get_scaled_throttle(g.throttle_cruise + nav_throttle + get_z_damping())); + g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + nav_throttle + get_z_damping()); #else g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost + get_z_damping(); #endif @@ -1399,7 +1405,7 @@ static void tuning(){ break; case CH6_THROTTLE_KP: - g.rc_6.set_range(0,1000); + g.rc_6.set_range(0,1000); // 0 to 1 g.pi_throttle.kP(tuning_value); break; @@ -1437,6 +1443,11 @@ static void tuning(){ g.heli_ext_gyro_gain = tuning_value * 1000; break; #endif + + case CH6_THR_HOLD_KP: + g.rc_6.set_range(0,1000); // 0 to 1 + g.pi_alt_hold.kP(tuning_value); + break; } } diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 21446159dd..d26bf3a658 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -140,7 +140,7 @@ #define CH6_RATE_KP 4 #define CH6_RATE_KI 5 #define CH6_YAW_RATE_KP 6 -// Altitude +// Altitude rate controller #define CH6_THROTTLE_KP 7 // Extras #define CH6_TOP_BOTTOM_RATIO 8 @@ -151,6 +151,9 @@ #define CH6_LOITER_P 12 #define CH6_HELI_EXTERNAL_GYRO 13 +// altitude controller +#define CH6_THR_HOLD_KP 14 + // nav byte mask // ------------- #define NAV_LOCATION 1 diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde index 3baf8d5ef1..c0d7c03367 100644 --- a/ArduCopter/heli.pde +++ b/ArduCopter/heli.pde @@ -5,8 +5,8 @@ #define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz #define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz -static float heli_throttle_scaler = 0; static bool heli_swash_initialised = false; +static int heli_throttle_mid = 0; // throttle mid point in pwm form (i.e. 0 ~ 1000) // heli_servo_averaging: // 0 or 1 = no averaging, 250hz @@ -19,8 +19,6 @@ static bool heli_swash_initialised = false; static void heli_init_swash() { int i; - int tilt_max[CH_3+1]; - int total_tilt_max = 0; // swash servo initialisation g.heli_servo_1.set_range(0,1000); @@ -38,23 +36,38 @@ static void heli_init_swash() heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle)); heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle)); - // collective min / max - total_tilt_max = 0; - for( i=CH_1; i<=CH_3; i++ ) { - tilt_max[i] = max(abs(heli_rollFactor[i]*g.heli_roll_max), abs(heli_pitchFactor[i]*g.heli_pitch_max))/100; - total_tilt_max = max(total_tilt_max,tilt_max[i]); + // ensure g.heli_coll values are reasonable + if( g.heli_coll_min >= g.heli_coll_max ) { + g.heli_coll_min = 1000; + g.heli_coll_max = 2000; } - - // servo min/max values - or should I use set_range? - g.heli_servo_1.radio_min = g.heli_coll_min - tilt_max[CH_1]; - g.heli_servo_1.radio_max = g.heli_coll_max + tilt_max[CH_1]; - g.heli_servo_2.radio_min = g.heli_coll_min - tilt_max[CH_2]; - g.heli_servo_2.radio_max = g.heli_coll_max + tilt_max[CH_2]; - g.heli_servo_3.radio_min = g.heli_coll_min - tilt_max[CH_3]; - g.heli_servo_3.radio_max = g.heli_coll_max + tilt_max[CH_3]; - - // scaler for changing channel 3 radio input into collective range - heli_throttle_scaler = ((float)(g.heli_coll_max - g.heli_coll_min))/1000; + g.heli_coll_mid = constrain(g.heli_coll_mid, g.heli_coll_min, g.heli_coll_max); + + // servo min/max values + if( g.heli_servo_1.get_reverse() ) { + g.heli_servo_1.radio_min = 3000 - g.heli_coll_max + (g.heli_servo_1.radio_trim-1500); + g.heli_servo_1.radio_max = 3000 - g.heli_coll_min + (g.heli_servo_1.radio_trim-1500); + }else{ + g.heli_servo_1.radio_min = g.heli_coll_min + (g.heli_servo_1.radio_trim-1500); + g.heli_servo_1.radio_max = g.heli_coll_max + (g.heli_servo_1.radio_trim-1500); + } + if( g.heli_servo_2.get_reverse() ) { + g.heli_servo_2.radio_min = 3000 - g.heli_coll_max + (g.heli_servo_2.radio_trim-1500); + g.heli_servo_2.radio_max = 3000 - g.heli_coll_min + (g.heli_servo_2.radio_trim-1500); + }else{ + g.heli_servo_2.radio_min = g.heli_coll_min + (g.heli_servo_2.radio_trim-1500); + g.heli_servo_2.radio_max = g.heli_coll_max + (g.heli_servo_2.radio_trim-1500); + } + if( g.heli_servo_3.get_reverse() ) { + g.heli_servo_3.radio_min = 3000 - g.heli_coll_max + (g.heli_servo_3.radio_trim-1500); + g.heli_servo_3.radio_max = 3000 - g.heli_coll_min + (g.heli_servo_3.radio_trim-1500); + }else{ + g.heli_servo_3.radio_min = g.heli_coll_min + (g.heli_servo_3.radio_trim-1500); + g.heli_servo_3.radio_max = g.heli_coll_max + (g.heli_servo_3.radio_trim-1500); + } + + // calculate throttle mid point + heli_throttle_mid = (g.heli_coll_mid-g.heli_coll_min)*(1000.0/(g.heli_coll_max-g.heli_coll_min)); // reset the servo averaging for( i=0; i<=3; i++ ) @@ -72,7 +85,7 @@ static void heli_init_swash() static void heli_move_servos_to_mid() { - heli_move_swash(0,0,1500,0); + heli_move_swash(0,0,500,0); } // @@ -80,7 +93,7 @@ static void heli_move_servos_to_mid() // - expected ranges: // roll : -4500 ~ 4500 // pitch: -4500 ~ 4500 -// collective: 1000 ~ 2000 +// collective: 0 ~ 1000 // yaw: -4500 ~ 4500 // static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out) @@ -92,6 +105,29 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o // we must be in set-up mode so mark swash as uninitialised heli_swash_initialised = false; + // free up servo ranges + if( g.heli_servo_1.get_reverse() ) { + g.heli_servo_1.radio_min = 3000 - g.rc_3.radio_max + (g.heli_servo_1.radio_trim-1500); + g.heli_servo_1.radio_max = 3000 - g.rc_3.radio_min + (g.heli_servo_1.radio_trim-1500); + }else{ + g.heli_servo_1.radio_min = g.rc_3.radio_min + (g.heli_servo_1.radio_trim-1500); + g.heli_servo_1.radio_max = g.rc_3.radio_max + (g.heli_servo_1.radio_trim-1500); + } + if( g.heli_servo_2.get_reverse() ) { + g.heli_servo_2.radio_min = 3000 - g.rc_3.radio_max + (g.heli_servo_2.radio_trim-1500); + g.heli_servo_2.radio_max = 3000 - g.rc_3.radio_min + (g.heli_servo_2.radio_trim-1500); + }else{ + g.heli_servo_2.radio_min = g.rc_3.radio_min + (g.heli_servo_2.radio_trim-1500); + g.heli_servo_2.radio_max = g.rc_3.radio_max + (g.heli_servo_2.radio_trim-1500); + } + if( g.heli_servo_3.get_reverse() ) { + g.heli_servo_3.radio_min = 3000 - g.rc_3.radio_max + (g.heli_servo_3.radio_trim-1500); + g.heli_servo_3.radio_max = 3000 - g.rc_3.radio_min + (g.heli_servo_3.radio_trim-1500); + }else{ + g.heli_servo_3.radio_min = g.rc_3.radio_min + (g.heli_servo_3.radio_trim-1500); + g.heli_servo_3.radio_max = g.rc_3.radio_max + (g.heli_servo_3.radio_trim-1500); + } + }else{ // regular flight mode // check if we need to reinitialise the swash @@ -102,7 +138,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o // ensure values are acceptable: roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max); pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max); - coll_out = constrain(coll_out, (int)g.heli_coll_min, (int)g.heli_coll_max); + coll_out = constrain(coll_out, 0, 1000); // rudder feed forward based on collective #if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator @@ -113,9 +149,9 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o } // swashplate servos - g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_1.radio_trim-1500); - g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_2.radio_trim-1500); - g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_3.radio_trim-1500); + g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out + (g.heli_servo_1.radio_trim-1500); + g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out + (g.heli_servo_2.radio_trim-1500); + g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out + (g.heli_servo_3.radio_trim-1500); g.heli_servo_4.servo_out = yaw_out + yaw_offset; // use servo_out to calculate pwm_out and radio_out @@ -130,7 +166,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o heli_servo_out[2] += g.heli_servo_3.radio_out; heli_servo_out[3] += g.heli_servo_4.radio_out; heli_servo_out_count++; - + // is it time to move the servos? if( heli_servo_out_count >= g.heli_servo_averaging ) { @@ -171,8 +207,8 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 + ICR5 = 8000; // 250 hz output CH 1, 2, 9 + ICR1 = 8000; // 250 hz output CH 3, 4, 10 ICR3 = 40000; // 50 hz output CH 7, 8, 11 #endif } @@ -194,7 +230,7 @@ static void output_motors_armed() g.rc_3.calc_pwm(); g.rc_4.calc_pwm(); - heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out ); + heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.servo_out, g.rc_4.servo_out ); } // for helis - armed or disarmed we allow servos to move @@ -212,25 +248,16 @@ static void output_motor_test() { } -// heli_get_scaled_throttle - user's throttle scaled to collective range -// input is expected to be in the range of 0~1000 (ie. pwm) -// also does equivalent of angle_boost -static int heli_get_scaled_throttle(int throttle) -{ - float scaled_throttle = (g.heli_coll_min - 1000) + throttle * heli_throttle_scaler; - return scaled_throttle; -} - -// heli_angle_boost - takes servo_out position -// adds a boost depending on roll/pitch values +// heli_angle_boost - adds a boost depending on roll/pitch values // equivalent of quad's angle_boost function -// pwm_out value should be 0 ~ 1000 -static int heli_get_angle_boost(int pwm_out) +// throttle value should be 0 ~ 1000 +static int heli_get_angle_boost(int throttle) { float angle_boost_factor = cos_pitch_x * cos_roll_x; angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0); - int throttle_above_center = max(1000 + pwm_out - g.heli_coll_mid,0); - return pwm_out + throttle_above_center*angle_boost_factor; + int throttle_above_mid = max(throttle - heli_throttle_mid,0); + return throttle + throttle_above_mid*angle_boost_factor; + } #endif // HELI_FRAME From 307971f82b0626ef87f3e80fa3c82002212a93cc Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Mon, 21 Nov 2011 03:03:42 +0800 Subject: [PATCH 44/63] firmware build --- .../Firmware/AC2-Hexa-1280.build.log | 58 +++-- .../Firmware/AC2-Hexa-1280.size.txt | 203 +++++++++--------- .../Firmware/AC2-Hexa-2560.build.log | 58 +++-- .../Firmware/AC2-Hexa-2560.size.txt | 203 +++++++++--------- .../Firmware/AC2-QUADHIL-1280.build.log | 95 ++++---- .../Firmware/AC2-QUADHIL-1280.size.txt | 196 ++++++++--------- .../Firmware/AC2-QUADHIL-2560.build.log | 95 ++++---- .../Firmware/AC2-QUADHIL-2560.size.txt | 196 ++++++++--------- .../Firmware/AC2-Quad-1280.build.log | 58 +++-- .../Firmware/AC2-Quad-1280.size.txt | 199 +++++++++-------- .../Firmware/AC2-Quad-2560.build.log | 58 +++-- .../Firmware/AC2-Quad-2560.size.txt | 199 +++++++++-------- .../Firmware/AC2-Tri-1280.build.log | 58 +++-- .../Firmware/AC2-Tri-1280.size.txt | 199 +++++++++-------- .../Firmware/AC2-Tri-2560.build.log | 58 +++-- .../Firmware/AC2-Tri-2560.size.txt | 199 +++++++++-------- .../Firmware/AC2-Y6-1280.build.log | 58 +++-- .../Firmware/AC2-Y6-1280.size.txt | 203 +++++++++--------- .../Firmware/AC2-Y6-2560.build.log | 58 +++-- .../Firmware/AC2-Y6-2560.size.txt | 203 +++++++++--------- .../Firmware/firmware2.xml | 10 +- Tools/ArdupilotMegaPlanner/Firmware/git.log | 65 ++++-- 22 files changed, 1358 insertions(+), 1371 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt index 7dbb3e32c5..6c2208496d 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -270,9 +278,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r report_frame()::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,22 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +404,21 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c +0000001d r Log_Read_Motors()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,14 +477,13 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007c t test_baro(unsigned char, Menu::arg const*) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,107 +526,101 @@ 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) -0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass 000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) +000000c2 t Log_Read_Motors() 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -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() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) +000000d0 t Log_Read_Nav_Tuning() +000000d0 t Log_Read_Control_Tuning() 000000d2 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000de t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000160 t test_wp(unsigned char, Menu::arg const*) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +0000017a t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() -000001cc t start_new_log() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001e6 t verify_nav_wp() -000001ea t init_home() 00000210 t setup_motors(unsigned char, Menu::arg const*) -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -00000638 t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001a00 T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000704 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +00001bc0 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt index 2ec1484a25..ac07817565 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -270,9 +278,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r report_frame()::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,22 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +404,21 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c +0000001d r Log_Read_Motors()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,15 +477,14 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue 00000050 t report_version() -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() -0000007a t test_baro(unsigned char, Menu::arg const*) +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,22 +526,18 @@ 00000090 t report_tuning() 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() -0000009e t Log_Write_Cmd(unsigned char, Location*) +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass @@ -546,84 +545,82 @@ 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) +000000c2 t Log_Read_Motors() 000000c2 t Log_Read_Attitude() 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() +000000cc t Log_Read_Nav_Tuning() +000000cc t Log_Read_Control_Tuning() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) 000000d0 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000dc t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() +0000015c t test_wp(unsigned char, Menu::arg const*) 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +00000178 t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() -000001cc t start_new_log() -000001e4 t verify_nav_wp() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001ea t init_home() 00000210 t setup_motors(unsigned char, Menu::arg const*) -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -00000636 t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001a00 T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000702 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +00001bc0 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log index 7490666e83..6e171525d0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.build.log @@ -3,59 +3,54 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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/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 -autogenerated: At global scope: -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 -autogenerated:105: warning: 'void Log_Write_Raw()' declared 'static' but never defined -autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined -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 -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/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:55: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined +autogenerated:56: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined +autogenerated:57: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined +autogenerated:110: warning: 'void Log_Write_Raw()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used +autogenerated:249: warning: 'void ReadSCP1000()' declared 'static' but never defined +autogenerated:250: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined +autogenerated:252: warning: 'int32_t read_barometer()' declared 'static' but never defined +autogenerated:253: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:254: warning: 'void zero_airspeed()' declared 'static' but never defined +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:365: warning: 'abs_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'ground_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_temperature' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'old_sonar_alt' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -96,7 +91,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt index 824b833eac..ce952b7fa0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,24 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -67,6 +73,8 @@ 00000002 r comma 00000002 b g_gps 00000002 b airspeed +00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long)) @@ -83,6 +91,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,6 +104,7 @@ 00000004 d scaleLongUp 00000004 b sin_pitch_y 00000004 b wp_distance +00000004 b circle_angle 00000004 b current_amps 00000004 b gps_base_alt 00000004 b original_alt @@ -101,7 +113,6 @@ 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -190,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -202,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -211,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -218,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -227,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -257,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -267,9 +278,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t setup_accel(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*) @@ -281,10 +293,13 @@ 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r report_frame()::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -296,6 +311,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -306,12 +323,13 @@ 0000000e V vtable for AP_VarT 0000000e V vtable for AP_VarT 0000000e V vtable for AP_VarT -0000000e r arm_motors()::__c 0000000e r erase_logs(unsigned char, Menu::arg const*)::__c 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c +0000000e r init_arm_motors()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -319,6 +337,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -330,29 +349,27 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 00000010 r planner_menu_commands 00000010 b motor_out 00000010 T GCS_MAVLINK::send_message(ap_message) 00000010 W AP_VarT::cast_to_float() const 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r report_compass()::__c -00000011 r arm_motors()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c +00000011 r init_disarm_motors()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -366,79 +383,74 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B adc 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarT::unserialize(void*, unsigned int) 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c +0000001e t init_disarm_motors() 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000030 B imu 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() @@ -446,34 +458,30 @@ 00000033 b pending_status 00000034 t _MAV_RETURN_float 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c t read_AHRS() 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 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000052 t report_version() @@ -483,55 +491,55 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 B dcm +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() 00000064 t print_gyro_offsets() 00000064 t print_accel_offsets() 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() +00000068 t init_arm_motors() 00000068 t find_last_log_page(int) 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 00000088 t Log_Read_Raw() 0000008c t setup_frame(unsigned char, Menu::arg const*) 00000090 t init_compass() +00000090 r test_menu_commands 00000090 t dump_log(unsigned char, Menu::arg const*) 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) +0000009a t arm_motors() 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) -0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ab B compass 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000be t update_events() @@ -539,76 +547,72 @@ 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -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 read_radio() 000000d0 t get_bearing(Location*, Location*) +000000d0 t Log_Read_Nav_Tuning() +000000d0 t Log_Read_Control_Tuning() 000000d2 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) -000000e0 r test_menu_commands +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() +000000fa t calc_loiter_pitch_roll() 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*) 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() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) +00000160 t test_wp(unsigned char, Menu::arg const*) +00000164 t set_cmd_with_index(Location, int) 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) +0000017a t verify_nav_wp() +0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001a8 t print_radio_values() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) 000001c8 t setup_motors(unsigned char, Menu::arg const*) -000001cc t start_new_log() +000001ce T GCS_MAVLINK::update() 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*) +00000204 t test_imu(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) -00000330 t tuning() +00000246 t calc_loiter(int, int) +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -00000598 t __static_initialization_and_destruction_0(int, int) -0000061e t init_ardupilot() -0000071a t update_nav_wp() -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -00001372 T loop -00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*) +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +000005a8 t __static_initialization_and_destruction_0(int, int) +00000640 t init_ardupilot() +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*) +000017d4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log index 7490666e83..6e171525d0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.build.log @@ -3,59 +3,54 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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/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 -autogenerated: At global scope: -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 -autogenerated:105: warning: 'void Log_Write_Raw()' declared 'static' but never defined -autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined -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 -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/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:300: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope: +/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:55: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined +autogenerated:56: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined +autogenerated:57: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined +autogenerated:110: warning: 'void Log_Write_Raw()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: warning: 'void throttle_failsafe(uint16_t)' defined but not used +autogenerated:249: warning: 'void ReadSCP1000()' declared 'static' but never defined +autogenerated:250: warning: 'void init_barometer()' declared 'static' but never defined +autogenerated:251: warning: 'int32_t read_baro_filtered()' declared 'static' but never defined +autogenerated:252: warning: 'int32_t read_barometer()' declared 'static' but never defined +autogenerated:253: warning: 'void read_airspeed()' declared 'static' but never defined +autogenerated:254: warning: 'void zero_airspeed()' declared 'static' but never defined +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:365: warning: 'abs_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'ground_pressure' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_temperature' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:377: warning: 'old_sonar_alt' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used /root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -96,7 +91,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt index 1fa3c06703..b61e4b36b8 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,24 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -67,6 +73,8 @@ 00000002 r comma 00000002 b g_gps 00000002 b airspeed +00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 W AP_IMU_Shim::init_accel(void (*)(unsigned long)) 00000002 W AP_IMU_Shim::init(IMU::Start_style, void (*)(unsigned long)) @@ -83,6 +91,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,6 +104,7 @@ 00000004 d scaleLongUp 00000004 b sin_pitch_y 00000004 b wp_distance +00000004 b circle_angle 00000004 b current_amps 00000004 b gps_base_alt 00000004 b original_alt @@ -101,7 +113,6 @@ 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -190,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -202,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -211,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -218,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -227,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -257,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -267,9 +278,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t setup_accel(unsigned char, Menu::arg const*) 0000000c t process_logs(unsigned char, Menu::arg const*) @@ -281,10 +293,13 @@ 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r report_frame()::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -296,6 +311,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -306,12 +323,13 @@ 0000000e V vtable for AP_VarT 0000000e V vtable for AP_VarT 0000000e V vtable for AP_VarT -0000000e r arm_motors()::__c 0000000e r erase_logs(unsigned char, Menu::arg const*)::__c 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c +0000000e r init_arm_motors()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -319,6 +337,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -330,29 +349,27 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 00000010 r planner_menu_commands 00000010 b motor_out 00000010 T GCS_MAVLINK::send_message(ap_message) 00000010 W AP_VarT::cast_to_float() const 00000010 r test_sonar(unsigned char, Menu::arg const*)::__c 00000010 r report_compass()::__c -00000011 r arm_motors()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c +00000011 r init_disarm_motors()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -366,79 +383,74 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B adc 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarT::unserialize(void*, unsigned int) 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c +0000001e t init_disarm_motors() 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000030 B imu 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() @@ -446,35 +458,31 @@ 00000033 b pending_status 00000034 t _MAV_RETURN_float 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c t read_AHRS() 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 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 t byte_swap_8 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue 00000050 t report_version() -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000052 W AP_IMU_Shim::update() @@ -483,29 +491,31 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c 00000057 B dcm +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() 00000064 t print_gyro_offsets() 00000064 t print_accel_offsets() 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() +00000068 t init_arm_motors() 00000068 t find_last_log_page(int) 0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*) 0000006a W GCS_MAVLINK::~GCS_MAVLINK() 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -514,24 +524,22 @@ 0000008e t dump_log(unsigned char, Menu::arg const*) 00000090 t init_compass() 00000090 t report_tuning() +00000090 r test_menu_commands 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) +0000009a t arm_motors() 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() -0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ab B compass 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000be t update_events() @@ -540,75 +548,71 @@ 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 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*) +000000cc t Log_Read_Nav_Tuning() +000000cc t Log_Read_Control_Tuning() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) 000000d0 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) -000000e0 r test_menu_commands +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() +000000fa t calc_loiter_pitch_roll() 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*) 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() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() +0000015c t test_wp(unsigned char, Menu::arg const*) 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) +00000164 t set_cmd_with_index(Location, int) 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 verify_nav_wp() 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) +0000018c T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 000001a8 t print_radio_values() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) 000001c8 t setup_motors(unsigned char, Menu::arg const*) -000001cc t start_new_log() -000001e4 t verify_nav_wp() +000001ce T GCS_MAVLINK::update() 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*) +00000204 t test_imu(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) -00000330 t tuning() +00000246 t calc_loiter(int, int) +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -00000598 t __static_initialization_and_destruction_0(int, int) -0000061c t init_ardupilot() -0000071a t update_nav_wp() -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -00001372 T loop -00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*) +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +000005a8 t __static_initialization_and_destruction_0(int, int) +0000063e t init_ardupilot() +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*) +000017d4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt index f0da4a64e5..ac89d2a8a3 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -270,9 +278,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r report_frame()::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,23 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +405,20 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,14 +477,13 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007c t test_baro(unsigned char, Menu::arg const*) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,22 +526,19 @@ 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() 0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) -0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass @@ -547,83 +547,80 @@ 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -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() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) +000000d0 t Log_Read_Nav_Tuning() +000000d0 t Log_Read_Control_Tuning() 000000d2 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000de t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000160 t test_wp(unsigned char, Menu::arg const*) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +0000017a t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) 000001c8 t setup_motors(unsigned char, Menu::arg const*) -000001cc t start_new_log() +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001e6 t verify_nav_wp() -000001ea t init_home() -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -0000063c t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -000018fa T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000708 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +00001a9a T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt index ff4be8e9be..2d636affaa 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -270,9 +278,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r report_frame()::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,23 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +405,20 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,15 +477,14 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue 00000050 t report_version() -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() -0000007a t test_baro(unsigned char, Menu::arg const*) +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,22 +526,19 @@ 00000090 t report_tuning() 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() 0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() -0000009e t Log_Write_Cmd(unsigned char, Location*) +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass @@ -548,82 +548,79 @@ 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 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() +000000cc t Log_Read_Nav_Tuning() +000000cc t Log_Read_Control_Tuning() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) 000000d0 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000dc t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() +0000015c t test_wp(unsigned char, Menu::arg const*) 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +00000178 t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) 000001c8 t setup_motors(unsigned char, Menu::arg const*) -000001cc t start_new_log() -000001e4 t verify_nav_wp() +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001ea t init_home() -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -0000063a t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -000018fa T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000706 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +00001a9a T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt index 34c74448ee..803ae4acd8 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -270,10 +278,11 @@ 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_frame()::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c V vtable for IMU 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,23 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +405,20 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,14 +477,13 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007c t test_baro(unsigned char, Menu::arg const*) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,22 +526,19 @@ 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() 0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) -0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass @@ -547,83 +547,80 @@ 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -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() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) +000000d0 t Log_Read_Nav_Tuning() +000000d0 t Log_Read_Control_Tuning() 000000d2 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() +000000dc t Log_Read(int, int) 000000de t setup_motors(unsigned char, Menu::arg const*) -000000de t test_adc(unsigned char, Menu::arg const*) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000160 t test_wp(unsigned char, Menu::arg const*) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +0000017a t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() -000001cc t start_new_log() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001e6 t verify_nav_wp() -000001ea t init_home() -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -0000063c t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001836 T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000708 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +000019d6 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt index 0b2a85e7fc..6ff9d78809 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c 0000000a r Log_Read_Startup()::__c @@ -270,10 +278,11 @@ 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_frame()::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c V vtable for IMU 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,23 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +405,20 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,15 +477,14 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue 00000050 t report_version() -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() -0000007a t test_baro(unsigned char, Menu::arg const*) +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,22 +526,19 @@ 00000090 t report_tuning() 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() 0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() -0000009e t Log_Write_Cmd(unsigned char, Location*) +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass @@ -548,82 +548,79 @@ 000000c2 t send_radio_out(mavlink_channel_t) 000000c2 t Log_Read_Attitude() 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() +000000cc t Log_Read_Nav_Tuning() +000000cc t Log_Read_Control_Tuning() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) 000000d0 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000dc t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000de t setup_motors(unsigned char, Menu::arg const*) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() +0000015c t test_wp(unsigned char, Menu::arg const*) 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +00000178 t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() -000001cc t start_new_log() -000001e4 t verify_nav_wp() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001ea t init_home() -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -0000063a t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001836 T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000706 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +000019d6 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt index 7df5b02f4f..f9580e0e2c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r report_frame()::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c @@ -271,9 +279,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c V vtable for IMU 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,22 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +404,21 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c +0000001d r Log_Read_Motors()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,14 +477,13 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007c t test_baro(unsigned char, Menu::arg const*) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,107 +526,101 @@ 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 t report_tuning() 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) -0000009e t Log_Write_Cmd(unsigned char, Location*) 000000a0 t Log_Read_Mode() +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000aa t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass 000000be t update_events() 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) +000000c2 t Log_Read_Motors() 000000c2 t Log_Read_Attitude() 000000c4 t get_distance(Location*, Location*) -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() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) +000000d0 t Log_Read_Nav_Tuning() +000000d0 t Log_Read_Control_Tuning() 000000d2 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000de t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() 0000015c t setup_motors(unsigned char, Menu::arg const*) 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000160 t test_wp(unsigned char, Menu::arg const*) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +0000017a t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() -000001cc t start_new_log() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001e6 t verify_nav_wp() -000001ea t init_home() -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -00000220 t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000384 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -00000638 t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -0000190e T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000704 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +00001ce4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log index b2a63cd62c..930bed821c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.build.log @@ -3,40 +3,38 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition -In file included from /root/apm/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 -autogenerated: At global scope: -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 -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/Attitude.pde:132: warning: 'void reset_hold_I()' defined but not used +autogenerated:33: warning: 'void init_z_damper()' declared 'static' but never defined +autogenerated:114: warning: 'void Log_Write_Optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:106: warning: 'void handle_no_commands()' defined but not used +/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:433: 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:183: warning: 'void heli_init_swash()' declared 'static' but never defined -autogenerated:184: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined -autogenerated:185: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:180: warning: 'void heli_init_swash()' declared 'static' but never defined +autogenerated:181: warning: 'void heli_move_servos_to_mid()' declared 'static' but never defined +autogenerated:182: warning: 'void heli_move_swash(int, int, int, int)' declared 'static' but never defined +autogenerated:187: warning: 'int heli_get_angle_boost(int)' declared 'static' but never defined 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 +/root/apm/ardupilot-mega/ArduCopter/navigation.pde:98: warning: 'void calc_loiter2(int, int)' defined but not used +autogenerated:236: warning: 'int32_t get_crosstrack_correction()' declared 'static' but never defined +autogenerated:238: warning: 'void reset_crosstrack()' declared 'static' but never defined +autogenerated:240: warning: 'int32_t get_alt_distance(Location*, Location*)' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/radio.pde:132: 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:251: warning: 'int32_t 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 -autogenerated:262: warning: 'void report_heli()' declared 'static' but never defined -autogenerated:263: warning: 'void report_gyro()' declared 'static' but never defined -autogenerated:270: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined -autogenerated:271: warning: 'int read_num_from_serial()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: 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/test.pde:1028: warning: 'void print_motor_out()' 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 +autogenerated:265: warning: 'void report_heli()' declared 'static' but never defined +autogenerated:266: warning: 'void report_gyro()' declared 'static' but never defined +autogenerated:273: warning: 'RC_Channel* heli_get_servo(int)' declared 'static' but never defined +autogenerated:274: warning: 'int read_num_from_serial()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/system.pde:486: warning: 'void set_failsafe(boolean)' defined but not used +autogenerated:289: warning: 'void init_optflow()' declared 'static' but never defined +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:265: warning: 'rc_override' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:266: warning: 'rc_override_active' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:267: warning: 'rc_override_fs_timer' defined but not used +/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:488: warning: 'pmTest1' defined but not used +/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1768: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/test.pde:34: warning: 'int8_t test_rawgps(uint8_t, const Menu::arg*)' declared 'static' but never defined %% libraries/APM_BMP085/APM_BMP085.o %% libraries/APM_BMP085/APM_BMP085_hil.o %% libraries/APM_PI/APM_PI.o @@ -77,7 +75,7 @@ In file included from /root/apm/ardupilot-mega/libraries/AP_OpticalFlow/AP_Optic %% libraries/AP_RangeFinder/RangeFinder.o %% libraries/AP_Relay/AP_Relay.o %% libraries/DataFlash/DataFlash.o -In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:35: +In file included from /root/apm/ardupilot-mega/libraries/DataFlash/DataFlash.cpp:36: /usr/local/share/arduino/libraries/SPI/SPI.h:25:1: warning: "SPI_CLOCK_DIV64" redefined /usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition %% libraries/FastSerial/BetterStream.o diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt index 7895b8e72b..553b7223a9 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt @@ -3,16 +3,17 @@ 00000001 b home_is_set 00000001 b motor_armed 00000001 b motor_light +00000001 b CH7_wp_index 00000001 b control_mode 00000001 b gps_watchdog 00000001 b simple_timer 00000001 d yaw_tracking 00000001 b land_complete 00000001 b throttle_mode -00000001 b command_may_ID +00000001 b mavlink_active +00000001 b prev_nav_index 00000001 b wp_verify_byte 00000001 d altitude_sensor -00000001 b command_must_ID 00000001 b command_yaw_dir 00000001 b new_radio_frame 00000001 b roll_pitch_mode @@ -24,13 +25,14 @@ 00000001 b old_control_mode 00000001 b slow_loopCounter 00000001 b takeoff_complete -00000001 b command_may_index +00000001 b command_nav_index 00000001 b oldSwitchPosition -00000001 b command_must_index +00000001 b command_cond_index 00000001 d ground_start_count 00000001 b medium_loopCounter 00000001 b command_yaw_relative 00000001 d jump +00000001 b nav_ok 00000001 b event_id 00000001 b led_mode 00000001 b yaw_mode @@ -45,20 +47,25 @@ 00000002 T userhook_init() 00000002 b climb_rate 00000002 b loiter_sum +00000002 b sonar_rate +00000002 b angle_boost 00000002 b event_delay 00000002 b event_value 00000002 b event_repeat 00000002 b loiter_total +00000002 b manual_boost 00000002 b nav_throttle +00000002 b old_baro_alt 00000002 b x_rate_error 00000002 b y_rate_error -00000002 b altitude_rate 00000002 b gps_fix_count +00000002 b old_sonar_alt 00000002 b velocity_land 00000002 b x_actual_speed 00000002 b y_actual_speed 00000002 b loiter_time_max 00000002 b command_yaw_time +00000002 b crosstrack_error 00000002 b event_undo_value 00000002 b command_yaw_speed 00000002 b auto_level_counter @@ -69,6 +76,7 @@ 00000002 b g_gps 00000002 b airspeed 00000002 b baro_alt +00000002 b baro_rate 00000002 b sonar_alt 00000002 b arm_motors()::arming_counter 00000002 r setup_frame(unsigned char, Menu::arg const*)::__c @@ -82,6 +90,9 @@ 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 r report_batt_monitor()::__c +00000003 r report_batt_monitor()::__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 @@ -93,15 +104,14 @@ 00000004 b sin_pitch_y 00000004 b wp_distance 00000004 b abs_pressure +00000004 b circle_angle 00000004 b current_amps -00000004 b old_altitude 00000004 b original_alt 00000004 b simple_cos_x 00000004 b simple_sin_y 00000004 b current_total 00000004 b nav_loopTimer 00000004 d scaleLongDown -00000004 t test_failsafe(unsigned char, Menu::arg const*) 00000004 b altitude_error 00000004 b fast_loopTimer 00000004 b perf_mon_timer @@ -152,7 +162,6 @@ 00000004 r setup_compass(unsigned char, Menu::arg const*)::__c 00000004 r print_log_menu()::__c 00000004 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c -00000004 r test_adc(unsigned char, Menu::arg const*)::__c 00000004 V Parameters::Parameters()::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c 00000004 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c @@ -171,7 +180,6 @@ 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c 00000005 r print_log_menu()::__c -00000005 r test_adc(unsigned char, Menu::arg const*)::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c 00000005 V Parameters::Parameters()::__c @@ -193,6 +201,7 @@ 00000006 r Log_Read_Mode()::__c 00000006 r print_log_menu()::__c 00000006 r print_log_menu()::__c +00000006 r report_batt_monitor()::__c 00000006 V Parameters::Parameters()::__c 00000007 b setup_menu 00000007 b planner_menu @@ -205,6 +214,8 @@ 00000007 r report_radio()::__c 00000007 r report_sonar()::__c 00000007 r print_enabled(unsigned char)::__c +00000007 r Log_Read_Nav_Tuning()::__c +00000007 r Log_Read_Control_Tuning()::__c 00000007 r test_wp(unsigned char, Menu::arg const*)::__c 00000007 V Parameters::Parameters()::__c 00000007 V Parameters::Parameters()::__c @@ -214,6 +225,7 @@ 00000007 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000008 t setup_erase(unsigned char, Menu::arg const*) 00000008 r __menu_name__planner_menu +00000008 r print_done()::__c 00000008 r select_logs(unsigned char, Menu::arg const*)::__c 00000008 r report_frame()::__c 00000008 r report_frame()::__c @@ -221,8 +233,6 @@ 00000008 r report_tuning()::__c 00000008 r init_ardupilot()::__c 00000008 r print_log_menu()::__c -00000008 r report_batt_monitor()::__c -00000008 r report_batt_monitor()::__c 00000008 r test_wp(unsigned char, Menu::arg const*)::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c @@ -230,7 +240,6 @@ 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c 00000008 V Parameters::Parameters()::__c -00000008 V Parameters::Parameters()::__c 00000008 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 00000009 r print_switch(unsigned char, unsigned char, bool)::__c 00000009 r print_log_menu()::__c @@ -260,7 +269,6 @@ 00000009 r GCS_MAVLINK::GCS_MAVLINK(unsigned int)::__c 0000000a T piezo_on() 0000000a T piezo_off() -0000000a r test_relay(unsigned char, Menu::arg const*)::__c 0000000a r report_frame()::__c 0000000a r start_new_log()::__c 0000000a r print_log_menu()::__c @@ -271,9 +279,10 @@ 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c 0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c +0000000a V Parameters::Parameters()::__c 0000000a T setup -0000000b r test_relay(unsigned char, Menu::arg const*)::__c -0000000b r report_batt_monitor()::__c +0000000b r setup_esc(unsigned char, Menu::arg const*)::__c 0000000b V Parameters::Parameters()::__c 0000000c t process_logs(unsigned char, Menu::arg const*) 0000000c b omega @@ -282,11 +291,13 @@ 0000000c V vtable for IMU 0000000c r print_switch(unsigned char, unsigned char, bool)::__c 0000000c r setup_factory(unsigned char, Menu::arg const*)::__c -0000000c r test_baro(unsigned char, Menu::arg const*)::__c +0000000c r report_version()::__c +0000000c r report_batt_monitor()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000c V Parameters::Parameters()::__c 0000000d r select_logs(unsigned char, Menu::arg const*)::__c +0000000d r setup_frame(unsigned char, Menu::arg const*)::__c 0000000d r test_tuning(unsigned char, Menu::arg const*)::__c 0000000d r test_battery(unsigned char, Menu::arg const*)::__c 0000000d r startup_ground()::__c @@ -298,6 +309,8 @@ 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c 0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c +0000000d V Parameters::Parameters()::__c 0000000d B sonar_mode_filter 0000000e t global destructors keyed to Serial 0000000e t global constructors keyed to Serial @@ -313,6 +326,7 @@ 0000000e r setup_mode(unsigned char, Menu::arg const*)::__c 0000000e r test_sonar(unsigned char, Menu::arg const*)::__c 0000000e r select_logs(unsigned char, Menu::arg const*)::__c +0000000e r setup_compass(unsigned char, Menu::arg const*)::__c 0000000e r print_log_menu()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c @@ -321,6 +335,7 @@ 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c 0000000e r print_radio_values()::__c +0000000e r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 0000000e r report_batt_monitor()::__c 0000000e r report_flight_modes()::__c 0000000e r dump_log(unsigned char, Menu::arg const*)::__c @@ -332,19 +347,18 @@ 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c 0000000e V Parameters::Parameters()::__c -0000000e V Parameters::Parameters()::__c 0000000f b current_loc -0000000f b next_command +0000000f b command_nav_queue +0000000f b command_cond_queue 0000000f b home 0000000f b next_WP 0000000f b prev_WP 0000000f b guided_WP 0000000f b target_WP +0000000f r setup_sonar(unsigned char, Menu::arg const*)::__c +0000000f r Log_Read_Data()::__c 0000000f r print_log_menu()::__c 0000000f r print_log_menu()::__c -0000000f r report_version()::__c -0000000f r report_batt_monitor()::__c -0000000f r test_imu(unsigned char, Menu::arg const*)::__c 0000000f V AP_IMU_Oilpan::AP_IMU_Oilpan(AP_ADC*, unsigned int)::__c 00000010 r planner_menu_commands 00000010 b motor_out @@ -354,7 +368,6 @@ 00000010 r report_compass()::__c 00000011 r erase_logs(unsigned char, Menu::arg const*)::__c 00000011 r zero_eeprom()::__c -00000011 r update_commands()::__c 00000012 B Serial 00000012 B Serial1 00000012 B Serial3 @@ -368,30 +381,22 @@ 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::~AP_VarT() 00000012 W AP_VarT::serialize(void*, unsigned int) const -00000012 r print_done()::__c 00000012 r select_logs(unsigned char, Menu::arg const*)::__c -00000012 r setup_frame(unsigned char, Menu::arg const*)::__c 00000012 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c -00000013 r setup_compass(unsigned char, Menu::arg const*)::__c -00000013 r change_command(unsigned char)::__c -00000013 r setup_batt_monitor(unsigned char, Menu::arg const*)::__c 00000014 W AP_VarT::unserialize(void*, unsigned int) 00000014 W AP_VarT::cast_to_float() const 00000014 W AP_VarT::cast_to_float() const -00000014 r setup_sonar(unsigned char, Menu::arg const*)::__c -00000014 r test_tri(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() +00000016 r setup_mode(unsigned char, Menu::arg const*)::__c 00000016 B sonar 00000018 t setup_tune(unsigned char, Menu::arg const*) 00000018 t setup_accel(unsigned char, Menu::arg const*) 00000018 r __menu_name__main_menu 00000018 W AP_VarT::serialize(void*, unsigned int) const 0000001a r print_log_menu()::__c -0000001a r Log_Read_Nav_Tuning()::__c 0000001c W AP_VarA::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) 0000001c W AP_VarS >::unserialize(void*, unsigned int) @@ -399,18 +404,21 @@ 0000001c W AP_VarA::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const 0000001c W AP_VarS >::serialize(void*, unsigned int) const +0000001c r print_gyro_offsets()::__c +0000001c r print_accel_offsets()::__c +0000001d r report_compass()::__c +0000001d r Log_Read_Motors()::__c 0000001d r Log_Read_Attitude()::__c +0000001d r Log_Read_Performance()::__c 0000001e r Log_Read_Optflow()::__c 00000020 t gcs_send_message(ap_message) 00000020 r test_current(unsigned char, Menu::arg const*)::__c 00000020 t byte_swap_4 +00000021 r setup_mode(unsigned char, Menu::arg const*)::__c 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() @@ -419,52 +427,49 @@ 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() 00000022 W AP_VarT::~AP_VarT() -00000023 r setup_mode(unsigned char, Menu::arg const*)::__c -00000023 r print_gyro_offsets()::__c +00000022 r test_imu(unsigned char, Menu::arg const*)::__c +00000023 r test_baro(unsigned char, Menu::arg const*)::__c 00000024 r init_ardupilot()::__c -00000024 r print_accel_offsets()::__c 00000026 t print_done() +00000026 t Log_Write_Data(signed char, float) 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*) 00000028 W AP_VarT::unserialize(void*, unsigned int) 00000028 W AP_VarT::serialize(void*, unsigned int) const 00000028 r Log_Read_Cmd()::__c -00000029 r setup_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 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 0000002f r test_radio(unsigned char, Menu::arg const*)::__c -0000002f r init_ardupilot()::__c +0000002f r setup_factory(unsigned char, Menu::arg const*)::__c 00000030 t planner_mode(unsigned char, Menu::arg const*) 00000030 t send_heartbeat(mavlink_channel_t) +00000030 r setup_radio(unsigned char, Menu::arg const*)::__c 00000032 T GCS_MAVLINK::init(FastSerial*) 00000032 W APM_PI::~APM_PI() 00000032 r Log_Read_GPS()::__c 00000033 b pending_status 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() -00000037 r print_wp(Location*, unsigned char)::__c -00000038 t init_throttle_cruise() +00000036 r print_wp(Location*, unsigned char)::__c 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() +0000003c B barometer 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) +00000040 r log_menu_commands +00000040 t init_throttle_cruise() 00000040 t read_AHRS() 00000040 W AP_Float16::unserialize(void*, unsigned int) 00000040 B adc @@ -472,15 +477,14 @@ 00000042 t report_sonar() 00000044 t setup_show(unsigned char, Menu::arg const*) 00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char) -00000048 t change_command(unsigned char) +00000044 r setup_flightmodes(unsigned char, Menu::arg const*)::__c +00000046 W RC_Channel::~RC_Channel() 00000048 t update_motor_leds() -00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c 0000004a t send_meminfo(mavlink_channel_t) 0000004a W AP_VarT::AP_VarT(AP_Var_group*, unsigned int, int, prog_char_t const*, unsigned char) 0000004c t update_auto_yaw() 00000050 b mavlink_queue 00000050 t report_version() -00000050 r log_menu_commands 00000050 r main_menu_commands 00000050 T GCS_MAVLINK::_find_parameter(unsigned int) 00000050 B imu @@ -489,13 +493,13 @@ 00000056 t readSwitch() 00000056 t dancing_light() 00000056 T GCS_MAVLINK::queued_waypoint_send() -00000057 r help_log(unsigned char, Menu::arg const*)::__c +0000005a t Log_Write_Data(signed char, long) 0000005a W AP_VarT::AP_VarT(float, unsigned int, prog_char_t const*, unsigned char) 0000005c t get_num_logs() 0000005c t setup_esc(unsigned char, Menu::arg const*) +0000005e t change_command(unsigned char) 0000005e t update_GPS_light() 0000005e T GCS_MAVLINK::_count_parameters() -00000064 B barometer 00000064 t mavlink_msg_param_value_send 00000068 t zero_eeprom() 00000068 t find_last_log_page(int) @@ -504,13 +508,12 @@ 0000006c t setup_sonar(unsigned char, Menu::arg const*) 0000006e T output_min() 00000078 t setup_batt_monitor(unsigned char, Menu::arg const*) -00000078 t do_RTL() 0000007a t setup_factory(unsigned char, Menu::arg const*) 0000007a t read_control_switch() 0000007a t report_flight_modes() -0000007a t test_baro(unsigned char, Menu::arg const*) +0000007a t do_RTL() +0000007c t Log_Read_Data() 0000007c t send_gps_status(mavlink_channel_t) -0000007e t test_rawgps(unsigned char, Menu::arg const*) 00000080 T __vector_25 00000080 T __vector_36 00000080 T __vector_54 @@ -523,22 +526,18 @@ 00000090 t report_tuning() 00000092 t test_tuning(unsigned char, Menu::arg const*) 00000092 T GCS_MAVLINK::queued_param_send() -00000096 t print_wp(Location*, unsigned char) 0000009a t planner_gcs(unsigned char, Menu::arg const*) 0000009a t init_compass() -0000009a t Log_Read_Motors() -0000009b B gcs0 -0000009b B gcs3 +0000009c B gcs0 +0000009c B gcs3 0000009e t setup_mode(unsigned char, Menu::arg const*) 0000009e t Log_Read_Mode() -0000009e t Log_Write_Cmd(unsigned char, Location*) +000000a0 r test_menu_commands 000000a4 T __vector_26 000000a4 T __vector_37 000000a4 T __vector_55 000000a8 t test_sonar(unsigned char, Menu::arg const*) -000000aa t Log_Read_Nav_Tuning() 000000ae t report_frame() -000000b0 t test_relay(unsigned char, Menu::arg const*) 000000b2 t erase_logs(unsigned char, Menu::arg const*) 000000b6 t get_log_boundaries(unsigned char, int&, int&) 000000b7 B compass @@ -546,84 +545,82 @@ 000000c2 t test_eedump(unsigned char, Menu::arg const*) 000000c2 t setup_compass(unsigned char, Menu::arg const*) 000000c2 t send_radio_out(mavlink_channel_t) +000000c2 t Log_Read_Motors() 000000c2 t Log_Read_Attitude() 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() +000000cc t Log_Read_Nav_Tuning() +000000cc t Log_Read_Control_Tuning() 000000d0 t read_radio() 000000d0 t get_bearing(Location*, Location*) 000000d0 t print_switch(unsigned char, unsigned char, bool) -000000d4 t Log_Read(int, int) +000000d4 t print_wp(Location*, unsigned char) 000000d8 t test_radio(unsigned char, Menu::arg const*) 000000d8 t read_barometer() -000000dc t test_adc(unsigned char, Menu::arg const*) +000000dc t Log_Read(int, int) 000000e0 r setup_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() +000000ee t Log_Read_Performance() 000000f6 t Log_Read_Cmd() -00000100 r test_menu_commands +000000fa t calc_loiter_pitch_roll() 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*) 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() +00000118 t arm_motors() +0000011c t get_cmd_with_index(int) 00000130 t report_compass() -00000138 t get_stabilize_roll(long) -00000138 t get_stabilize_pitch(long) -00000148 t Log_Read_GPS() +00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*) +0000013a t test_baro(unsigned char, Menu::arg const*) +0000014c t get_stabilize_roll(long) +0000014c t get_stabilize_pitch(long) 0000014e t send_servo_out(mavlink_channel_t) -00000156 t update_commands() +00000152 t init_home() +00000156 t Log_Read_GPS() 0000015c t update_trig() 0000015c t setup_motors(unsigned char, Menu::arg const*) +0000015c t test_wp(unsigned char, Menu::arg const*) 00000160 t send_location(mavlink_channel_t) -00000160 t send_nav_controller_output(mavlink_channel_t) -00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) +00000164 t set_cmd_with_index(Location, 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*) +00000166 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int) 0000016e t send_attitude(mavlink_channel_t) 00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int) +00000178 t verify_nav_wp() 000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int) 000001a8 t print_radio_values() -000001be t arm_motors() -000001cc t start_new_log() -000001e4 t verify_nav_wp() +000001b2 t start_new_log() +000001b8 t send_nav_controller_output(mavlink_channel_t) +000001ce T GCS_MAVLINK::update() 000001e4 t setup_flightmodes(unsigned char, Menu::arg const*) -000001ea t init_home() -00000216 t set_mode(unsigned char) +00000210 t test_imu(unsigned char, Menu::arg const*) 0000021a t send_raw_imu1(mavlink_channel_t) -0000021c t test_wp(unsigned char, Menu::arg const*) 00000228 t setup_radio(unsigned char, Menu::arg const*) -0000022a t send_gps_raw(mavlink_channel_t) -00000242 t calc_loiter(int, int) +00000246 t calc_loiter(int, int) 00000268 t send_raw_imu3(mavlink_channel_t) -00000330 t tuning() +0000026a t send_gps_raw(mavlink_channel_t) +000002cc t set_mode(unsigned char) +00000362 t tuning() 00000382 t print_log_menu() -0000039a T update_throttle_mode() +00000396 T update_roll_pitch_mode() 000003a0 t read_battery() -00000410 T update_yaw_mode() -0000046e T update_roll_pitch_mode() -00000636 t init_ardupilot() -0000071a t update_nav_wp() -000007c8 t __static_initialization_and_destruction_0(int, int) -00000842 b g -00000870 t process_next_command() -00000884 W Parameters::Parameters() -000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*) -0000190e T loop +0000041c T update_yaw_mode() +00000444 T update_throttle_mode() +00000702 t init_ardupilot() +000007d8 t __static_initialization_and_destruction_0(int, int) +00000878 t update_nav_wp() +000008f6 W Parameters::Parameters() +000008fa b g +000009be t update_commands(bool) +000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) +00001ce4 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index f15428b643..3f4ea6a658 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -57,7 +57,7 @@ #define FRAME_ORIENTATION X_FRAME - 112 + 113 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex @@ -68,7 +68,7 @@ #define FRAME_ORIENTATION X_FRAME - 112 + 113 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex @@ -79,7 +79,7 @@ #define FRAME_ORIENTATION X_FRAME - 112 + 113 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex @@ -90,7 +90,7 @@ #define FRAME_ORIENTATION X_FRAME - 112 + 113 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex @@ -152,7 +152,7 @@ - 112 + 113 http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index 1615f378de..bba134ae9c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1,20 +1,49 @@ From https://code.google.com/p/ardupilot-mega - 6aeabd0..833acbd master -> origin/master -Updating 6aeabd0..833acbd + 6d78bad..6d8e6a8 master -> origin/master +Updating 6d78bad..6d8e6a8 Fast-forward - ArduCopter/ArduCopter.pde | 11 ++++- - ArduCopter/Attitude.pde | 1 - - ArduCopter/Log.pde | 28 ++++++------ - ArduCopter/Parameters.h | 50 +++++++++-------------- - ArduCopter/config.h | 20 +-------- - ArduCopter/defines.h | 2 + - ArduCopter/navigation.pde | 17 ++++++-- - ArduCopter/radio.pde | 9 +---- - ArduCopter/setup.pde | 52 ++++++++++++------------ - ArduCopter/system.pde | 22 ++++++---- - ArduCopter/test.pde | 63 +++++++++++++++-------------- - ArduPlane/ArduPlane.pde | 2 +- - ArduPlane/Log.pde | 91 +++++++++++++++++++++--------------------- - Tools/autotest/arducopter.py | 10 ++-- - Tools/autotest/common.py | 8 +++- - 15 files changed, 193 insertions(+), 193 deletions(-) + ArduCopter/ArduCopter.pde | 59 +- + ArduCopter/GCS_Mavlink copy.txt | 2091 ++++++++++++++++++++ + ArduCopter/GCS_Mavlink.pde | 16 +- + ArduCopter/Log.pde | 27 + + ArduCopter/Parameters.h | 2 +- + ArduCopter/commands.pde | 7 +- + ArduCopter/commands_logic.pde | 8 +- + ArduCopter/control_modes.pde | 2 +- + ArduCopter/defines.h | 20 +- + ArduCopter/heli.pde | 115 +- + ArduCopter/system.pde | 4 + + ArduCopter/test.pde | 16 +- + ArduPlane/Log.pde | 7 + + .../Projects/arduino-usbserial/Arduino-usbserial.c | 2 +- + Tools/ArduPPM/Libraries/PPM_Encoder.h | 28 +- + Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 2 +- + Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 21 +- + Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 7 +- + Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 9 +- + .../GCSViews/FlightPlanner.Designer.cs | 1 + + .../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 64 +- + .../GCSViews/FlightPlanner.resx | 4 +- + Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 2 +- + Tools/ArdupilotMegaPlanner/MAVLink.cs | 15 +- + Tools/ArdupilotMegaPlanner/MainV2.Designer.cs | 10 +- + Tools/ArdupilotMegaPlanner/MainV2.cs | 8 + + Tools/ArdupilotMegaPlanner/Program.cs | 2 +- + .../Properties/AssemblyInfo.cs | 2 +- + Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs | 1 + + Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 8 +- + .../bin/Release/ArdupilotMegaPlanner.application | 2 +- + .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2212864 -> 2214400 bytes + .../bin/Release/BSE.Windows.Forms.dll | Bin 141824 -> 141824 bytes + .../bin/Release/GCSViews/FlightPlanner.resx | 4 +- + .../bin/Release/GMap.NET.Core.dll | Bin 189952 -> 183808 bytes + .../bin/Release/GMap.NET.WindowsForms.dll | Bin 77824 -> 77824 bytes + 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 + Tools/autotest/autotest.py | 3 +- + Tools/autotest/mission2.txt | 2 +- + libraries/Desktop/support/DataFlash.cpp | 20 +- + 43 files changed, 2445 insertions(+), 146 deletions(-) + create mode 100644 ArduCopter/GCS_Mavlink copy.txt From fbf09dbf2dc3602a60edd01f5b2d56b89f092959 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 12:49:00 -0800 Subject: [PATCH 45/63] Made save WP the default Cosmetic updates --- ArduCopter/ArduCopter.pde | 15 +++++++-------- ArduCopter/config.h | 2 +- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 0d9e2d4c68..0d466b480d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1080,20 +1080,20 @@ void update_throttle_mode(void) // calculate angle boost angle_boost = get_angle_boost(g.throttle_cruise); - + // manual command up or down? if(manual_boost != 0){ - + //remove alt_hold_velocity when implemented #if FRAME_CONFIG == HELI_FRAME g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + manual_boost + get_z_damping()); #else g.rc_3.servo_out = g.throttle_cruise + angle_boost + manual_boost + get_z_damping(); #endif - + // reset next_WP.alt next_WP.alt = max(current_loc.alt, 100); - + }else{ // 10hz, don't run up i term if(invalid_throttle && motor_auto_armed == true){ @@ -1102,13 +1102,12 @@ void update_throttle_mode(void) altitude_error = get_altitude_error(); // get the AP throttle - nav_throttle = get_nav_throttle(altitude_error);//, 250); //150 = target speed of 1.5m/s - //Serial.printf("in:%d, cr:%d, NT:%d, I:%1.4f\n", g.rc_3.control_in,altitude_error, nav_throttle, g.pi_throttle.get_integrator()); + nav_throttle = get_nav_throttle(altitude_error); // clear the new data flag invalid_throttle = false; } - + #if FRAME_CONFIG == HELI_FRAME g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + nav_throttle + get_z_damping()); #else @@ -1443,7 +1442,7 @@ static void tuning(){ g.heli_ext_gyro_gain = tuning_value * 1000; break; #endif - + case CH6_THR_HOLD_KP: g.rc_6.set_range(0,1000); // 0 to 1 g.pi_alt_hold.kP(tuning_value); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index e1f0b07ffb..46e686c6f8 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -71,7 +71,7 @@ // #ifndef CH7_OPTION -# define CH7_OPTION CH7_SET_HOVER +# define CH7_OPTION CH7_SAVE_WP #endif From 2600f19172297f9584192b5c6c065a36cb252f33 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 12:50:06 -0800 Subject: [PATCH 46/63] RTL Yaw hold as default --- ArduCopter/config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 46e686c6f8..17a2f879fb 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -343,7 +343,7 @@ // RTL Mode #ifndef RTL_YAW -# define RTL_YAW YAW_AUTO +# define RTL_YAW YAW_HOLD #endif #ifndef RTL_RP From 076b93967d4a4c2a0131638b037a3b7ccc3fb723 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Mon, 21 Nov 2011 04:53:20 +0800 Subject: [PATCH 47/63] firmware build --- .../Firmware/AC2-Hexa-1280.size.txt | 2 +- .../Firmware/AC2-Hexa-2560.size.txt | 2 +- .../Firmware/AC2-QUADHIL-1280.size.txt | 2 +- .../Firmware/AC2-QUADHIL-2560.size.txt | 2 +- .../Firmware/AC2-Quad-1280.size.txt | 2 +- .../Firmware/AC2-Quad-2560.size.txt | 2 +- .../Firmware/AC2-Tri-1280.size.txt | 2 +- .../Firmware/AC2-Tri-2560.size.txt | 2 +- .../Firmware/AC2-Y6-1280.size.txt | 2 +- .../Firmware/AC2-Y6-2560.size.txt | 2 +- Tools/ArdupilotMegaPlanner/Firmware/git.log | 52 ++----------------- 11 files changed, 15 insertions(+), 57 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt index 6c2208496d..658cbea72a 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001bc0 T loop +00001c1e T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt index ac07817565..5050b23006 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001bc0 T loop +00001c1e T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt index ce952b7fa0..be02c8694c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.size.txt @@ -615,4 +615,4 @@ 000008fa b g 000009be t update_commands(bool) 000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*) -000017d4 T loop +00001832 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt index b61e4b36b8..09a098addd 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.size.txt @@ -615,4 +615,4 @@ 000008fa b g 000009be t update_commands(bool) 000017b8 T GCS_MAVLINK::handleMessage(__mavlink_message*) -000017d4 T loop +00001832 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt index ac89d2a8a3..56f2cab357 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001a9a T loop +00001af8 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt index 2d636affaa..7eac03fa06 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001a9a T loop +00001af8 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt index 803ae4acd8..26f8427173 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -000019d6 T loop +00001a34 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt index 6ff9d78809..fa5668bde0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -000019d6 T loop +00001a34 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt index f9580e0e2c..665c862ca0 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001ce4 T loop +00001d42 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt index 553b7223a9..c353f44ecb 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.size.txt @@ -623,4 +623,4 @@ 000008fa b g 000009be t update_commands(bool) 000014f0 T GCS_MAVLINK::handleMessage(__mavlink_message*) -00001ce4 T loop +00001d42 T loop diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index bba134ae9c..7fc7238cc7 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1,49 +1,7 @@ From https://code.google.com/p/ardupilot-mega - 6d78bad..6d8e6a8 master -> origin/master -Updating 6d78bad..6d8e6a8 + 5602ec3..413fb29 master -> origin/master +Updating 5602ec3..413fb29 Fast-forward - ArduCopter/ArduCopter.pde | 59 +- - ArduCopter/GCS_Mavlink copy.txt | 2091 ++++++++++++++++++++ - ArduCopter/GCS_Mavlink.pde | 16 +- - ArduCopter/Log.pde | 27 + - ArduCopter/Parameters.h | 2 +- - ArduCopter/commands.pde | 7 +- - ArduCopter/commands_logic.pde | 8 +- - ArduCopter/control_modes.pde | 2 +- - ArduCopter/defines.h | 20 +- - ArduCopter/heli.pde | 115 +- - ArduCopter/system.pde | 4 + - ArduCopter/test.pde | 16 +- - ArduPlane/Log.pde | 7 + - .../Projects/arduino-usbserial/Arduino-usbserial.c | 2 +- - Tools/ArduPPM/Libraries/PPM_Encoder.h | 28 +- - Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 2 +- - Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 21 +- - Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 7 +- - Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 9 +- - .../GCSViews/FlightPlanner.Designer.cs | 1 + - .../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 64 +- - .../GCSViews/FlightPlanner.resx | 4 +- - Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 2 +- - Tools/ArdupilotMegaPlanner/MAVLink.cs | 15 +- - Tools/ArdupilotMegaPlanner/MainV2.Designer.cs | 10 +- - Tools/ArdupilotMegaPlanner/MainV2.cs | 8 + - Tools/ArdupilotMegaPlanner/Program.cs | 2 +- - .../Properties/AssemblyInfo.cs | 2 +- - Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs | 1 + - Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 8 +- - .../bin/Release/ArdupilotMegaPlanner.application | 2 +- - .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2212864 -> 2214400 bytes - .../bin/Release/BSE.Windows.Forms.dll | Bin 141824 -> 141824 bytes - .../bin/Release/GCSViews/FlightPlanner.resx | 4 +- - .../bin/Release/GMap.NET.Core.dll | Bin 189952 -> 183808 bytes - .../bin/Release/GMap.NET.WindowsForms.dll | Bin 77824 -> 77824 bytes - 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 - Tools/autotest/autotest.py | 3 +- - Tools/autotest/mission2.txt | 2 +- - libraries/Desktop/support/DataFlash.cpp | 20 +- - 43 files changed, 2445 insertions(+), 146 deletions(-) - create mode 100644 ArduCopter/GCS_Mavlink copy.txt + ArduCopter/ArduCopter.pde | 15 +++++++-------- + ArduCopter/config.h | 4 ++-- + 2 files changed, 9 insertions(+), 10 deletions(-) From eb2f8180aba68c5f359bd2ac358f3a293c8ca4f4 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Mon, 21 Nov 2011 05:02:13 +0800 Subject: [PATCH 48/63] firmware build --- Tools/ArdupilotMegaPlanner/Firmware/git.log | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index 7fc7238cc7..2a7bfed917 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1,7 +1 @@ -From https://code.google.com/p/ardupilot-mega - 5602ec3..413fb29 master -> origin/master -Updating 5602ec3..413fb29 -Fast-forward - ArduCopter/ArduCopter.pde | 15 +++++++-------- - ArduCopter/config.h | 4 ++-- - 2 files changed, 9 insertions(+), 10 deletions(-) +Already up-to-date. From db8efd3287bd91daf33429f628c79bee71c7cdec Mon Sep 17 00:00:00 2001 From: Olivier ADLER Date: Mon, 21 Nov 2011 02:22:36 +0100 Subject: [PATCH 49/63] ArduPPM 0.9.86 update : #define to allow Radio Passthrough mode disabling on APM v1.4 (hardware failsafe for Arduplane) This is to allow for safe use of CH8 with Arducopter. --- Tools/ArduPPM/ATMega328p/Encoder-PPM.c | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c index fa4aefc454..1d8159e57e 100644 --- a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c +++ b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c @@ -1,5 +1,5 @@ // ------------------------------------------------------------------------------------------------------------------------------------------------------------ -// ARDUCODER Version v0.9.85 +// ArduPPM Version v0.9.86 // ------------------------------------------------------------------------------------------------------------------------------------------------------------ // ARDUCOPTER 2 : PPM ENCODER for AT Mega 328p and APM v1.4 Boards // By:John Arne Birkeland - 2011 @@ -33,6 +33,7 @@ // 0.9.83 : Implemented PPM passtrough failsafe // 0.9.84 : Corrected pin and port names in Encoder-PPM.c according to #define for Mega32U2 compatibility // 0.9.85 : Added brownout reset detection flag +// 0.9.86 : Added a #define to disable Radio Passthrough mode (hardware failsafe for Arduplane) // ------------------------------------------------------------------------------------------------------------------------------------------------------------ // PREPROCESSOR DIRECTIVES // ------------------------------------------------------------------------------------------------------------------------------------------------------------ @@ -41,10 +42,11 @@ #include -#define ERROR_THRESHOLD 1 // Number of servo input errors before alerting +#define ERROR_THRESHOLD 2 // Number of servo input errors before alerting #define ERROR_DETECTION_WINDOW 3000 * LOOP_TIMER_10MS // Detection window for error detection (default to 30s) #define ERROR_CONDITION_DELAY 500 * LOOP_TIMER_10MS // Servo error condition LED delay (LED blinking duration) +#define PASSTHROUGH_MODE ENABLED // Set it to "DISABLED" to remove radio passthrough mode (hardware failsafe for Arduplane) #define PASSTHROUGH_CHANNEL 8 * 2 // Channel for passthrough mode selection #define PASSTHROUGH_CHANNEL_OFF_US ONE_US * 1600 - PPM_PRE_PULSE // Passthrough off threshold #define PASSTHROUGH_CHANNEL_ON_US ONE_US * 1800 - PPM_PRE_PULSE // Passthrough on threshold @@ -87,8 +89,6 @@ int main(void) // LOCAL VARIABLES // ------------------------------------------------------------------------------------------------------------------------------------------------------------ bool init = true; // We are inside init sequence - int8_t mux_check = 0; - uint16_t mux_ppm = 500; bool mux_passthrough = false; // Mux passthrough mode status Flag : passthrough is off uint16_t led_acceleration; // Led acceleration based on throttle stick position bool servo_error_condition = false; // Servo signal error condition @@ -96,8 +96,14 @@ int main(void) static uint16_t servo_error_detection_timer=0; // Servo error detection timer static uint16_t servo_error_condition_timer=0; // Servo error condition timer static uint16_t blink_led_timer = 0; // Blink led timer + + #if PASSTHROUGH_MODE == ENABLED static uint8_t mux_timer = 0; // Mux timer static uint8_t mux_counter = 0; // Mux counter + static int8_t mux_check = 0; + static uint16_t mux_ppm = 500; + #endif + static uint16_t led_code_timer = 0; // Blink Code Timer static uint8_t led_code_symbol = 0; // Blink Code current symbol @@ -308,6 +314,7 @@ int main(void) PWM_LOOP: // SERVO_PWM_MODE while( 1 ) { + #if PASSTHROUGH_MODE == ENABLED // ------------------------------------------------------------------------------ // Radio passthrough control (mux chip A/B control) // ------------------------------------------------------------------------------ @@ -355,7 +362,7 @@ int main(void) } - + #endif // ------------------------------------------------------------------------------ // Status LED control From beeba99b9278d3be3cef7d9573f63335348541ce Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 20:29:48 -0800 Subject: [PATCH 50/63] Missed a function definition for no_logs option --- ArduCopter/Log.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 9b75f0728f..1e19b9b3a9 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -1027,6 +1027,7 @@ static void Log_Write_Raw() {} static void Log_Write_GPS() {} static void Log_Write_Current() {} static void Log_Write_Attitude() {} +static void Log_Write_Data() {} #ifdef OPTFLOW_ENABLED static void Log_Write_Optflow() {} #endif From 5c797e91b55a26267407a44547529da4b76e4d57 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 20:32:46 -0800 Subject: [PATCH 51/63] Better function definition --- ArduCopter/Log.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 1e19b9b3a9..fadc2d6fed 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -1028,6 +1028,8 @@ static void Log_Write_GPS() {} static void Log_Write_Current() {} static void Log_Write_Attitude() {} static void Log_Write_Data() {} +static void Log_Write_Data(int8_t _type, float _data){} +static void Log_Write_Data(int8_t _type, int32_t _data){} #ifdef OPTFLOW_ENABLED static void Log_Write_Optflow() {} #endif From 95b797d359dabf35400fdd2dde82aaf4e68b2440 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 21:24:32 -0800 Subject: [PATCH 52/63] removed the init_esc - reworking the method to avoid the use of the CLI. --- ArduCopter/system.pde | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 10553fda99..73c97ffa00 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -184,6 +184,7 @@ static void init_ardupilot() init_rc_in(); // sets up rc channels from radio init_rc_out(); // sets up the timer libs + init_camera(); #if HIL_MODE != HIL_MODE_ATTITUDE @@ -238,10 +239,6 @@ static void init_ardupilot() Serial.printf_P(PSTR("\nPress ENTER 3 times for CLI\n\n")); #endif // CLI_ENABLED - if(g.esc_calibrate == 1){ - init_esc(); - } - #if LOGGING_ENABLED == ENABLED if(g.log_bitmask != 0){ // TODO - Here we will check on the length of the last log From 6d99e78887394c4d2c711cabf2611aed00a12aa5 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 20 Nov 2011 21:59:55 -0800 Subject: [PATCH 53/63] removed unused function --- ArduCopter/Log.pde | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index fadc2d6fed..af55339341 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -1027,7 +1027,6 @@ static void Log_Write_Raw() {} static void Log_Write_GPS() {} static void Log_Write_Current() {} static void Log_Write_Attitude() {} -static void Log_Write_Data() {} static void Log_Write_Data(int8_t _type, float _data){} static void Log_Write_Data(int8_t _type, int32_t _data){} #ifdef OPTFLOW_ENABLED From faaaf118227a7bfd197c8ac3607a56457a6b2c13 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Nov 2011 20:26:36 +1100 Subject: [PATCH 54/63] fixed disabling of GPS in ArduPlane we may need a new hex --- ArduPlane/APM_Config.h | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index fce773f7cf..d7abbcc277 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -36,4 +36,3 @@ #define AIRSPEED_CRUISE 25 #define THROTTLE_FAILSAFE ENABLED */ -#define GPS_PROTOCOL GPS_NONE \ No newline at end of file From 4933c5bcdd91959772403b27fb89c6d9e2c07b93 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Nov 2011 12:05:43 +1100 Subject: [PATCH 55/63] zero airspeed on ground start when initiated by MAVLink If the users asks for a new calibration, that should include the airspeed sensor --- ArduPlane/system.pde | 23 +++++++++-------------- 1 file changed, 9 insertions(+), 14 deletions(-) diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 237a473e54..6e352014a1 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -286,20 +286,6 @@ static void startup_ground(void) // --------------------------- trim_radio(); // This was commented out as a HACK. Why? I don't find a problem. -#if HIL_MODE != HIL_MODE_ATTITUDE -if (g.airspeed_enabled == true) - { - // initialize airspeed sensor - // -------------------------- - zero_airspeed(); - gcs_send_text_P(SEVERITY_LOW,PSTR(" zero airspeed calibrated")); - } -else - { - gcs_send_text_P(SEVERITY_LOW,PSTR(" NO airspeed")); - } -#endif - // Save the settings for in-air restart // ------------------------------------ //save_EEPROM_groundstart(); @@ -439,6 +425,15 @@ static void startup_IMU_ground(void) //----------------------------- init_barometer(); + if (g.airspeed_enabled == true) { + // initialize airspeed sensor + // -------------------------- + zero_airspeed(); + gcs_send_text_P(SEVERITY_LOW,PSTR(" zero airspeed calibrated")); + } else { + gcs_send_text_P(SEVERITY_LOW,PSTR(" NO airspeed")); + } + #endif // HIL_MODE_ATTITUDE digitalWrite(B_LED_PIN, HIGH); // Set LED B high to indicate IMU ready From 8ef364657bf0168f8495618bdb78c9100ccce781 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Nov 2011 12:06:14 +1100 Subject: [PATCH 56/63] MAVLink: fixed throttle display in VFR_HUD --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 20c2043c25..e30ea70b75 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -409,7 +409,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) (float)airspeed / 100.0, (float)g_gps->ground_speed / 100.0, (dcm.yaw_sensor / 100) % 360, - (int)g.channel_throttle.servo_out, + (uint16_t)(100 * g.channel_throttle.norm_output()), current_loc.alt / 100.0, 0); } From a5f2cb5ec0ffc136533b020787a68fae97290b67 Mon Sep 17 00:00:00 2001 From: Hazy Date: Mon, 21 Nov 2011 20:20:59 +0800 Subject: [PATCH 57/63] APMPlanner a few Chinese translations --- .../GCSViews/Configuration.Designer.cs | 700 +- .../GCSViews/Configuration.resx | 12998 ++++++++-------- .../GCSViews/Configuration.zh-Hans.resx | 88 +- .../GCSViews/FlightData.Designer.cs | 50 +- .../GCSViews/FlightData.resx | 130 +- .../GCSViews/FlightData.zh-Hans.resx | 140 +- .../GCSViews/FlightPlanner.resx | 59 +- .../GCSViews/FlightPlanner.zh-Hans.resx | 4 + .../GCSViews/Simulation.Designer.cs | 91 +- .../GCSViews/Simulation.resx | 3879 ++--- .../GCSViews/Simulation.zh-Hans.resx | 30 +- .../Setup/Setup.Designer.cs | 204 +- Tools/ArdupilotMegaPlanner/Setup/Setup.resx | 7320 +++++---- .../Setup/Setup.zh-Hans.resx | 273 +- 14 files changed, 14081 insertions(+), 11885 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs index 890821ed41..5ce6f0e836 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs @@ -141,6 +141,13 @@ this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown(); this.label52 = new System.Windows.Forms.Label(); this.TabAC2 = new System.Windows.Forms.TabPage(); + this.groupBox17 = new System.Windows.Forms.GroupBox(); + this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown(); + this.label27 = new System.Windows.Forms.Label(); + this.ACRO_PIT_I = new System.Windows.Forms.NumericUpDown(); + this.label29 = new System.Windows.Forms.Label(); + this.ACRO_PIT_P = new System.Windows.Forms.NumericUpDown(); + this.label33 = new System.Windows.Forms.Label(); this.groupBox5 = new System.Windows.Forms.GroupBox(); this.label14 = new System.Windows.Forms.Label(); this.THR_RATE_IMAX = new System.Windows.Forms.NumericUpDown(); @@ -148,6 +155,13 @@ this.label20 = new System.Windows.Forms.Label(); this.THR_RATE_P = new System.Windows.Forms.NumericUpDown(); this.label25 = new System.Windows.Forms.Label(); + this.groupBox18 = new System.Windows.Forms.GroupBox(); + this.ACRO_RLL_IMAX = new System.Windows.Forms.NumericUpDown(); + this.label40 = new System.Windows.Forms.Label(); + this.ACRO_RLL_I = new System.Windows.Forms.NumericUpDown(); + this.label44 = new System.Windows.Forms.Label(); + this.ACRO_RLL_P = new System.Windows.Forms.NumericUpDown(); + this.label48 = new System.Windows.Forms.Label(); this.CHK_lockrollpitch = new System.Windows.Forms.CheckBox(); this.groupBox4 = new System.Windows.Forms.GroupBox(); this.WP_SPEED_MAX = new System.Windows.Forms.NumericUpDown(); @@ -275,58 +289,129 @@ this.BUT_load = new ArdupilotMega.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.BUT_compare = new ArdupilotMega.MyButton(); - this.groupBox17 = new System.Windows.Forms.GroupBox(); - this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown(); - this.label27 = new System.Windows.Forms.Label(); - this.ACRO_PIT_I = new System.Windows.Forms.NumericUpDown(); - this.label29 = new System.Windows.Forms.Label(); - this.ACRO_PIT_P = new System.Windows.Forms.NumericUpDown(); - this.label33 = new System.Windows.Forms.Label(); - this.groupBox18 = new System.Windows.Forms.GroupBox(); - this.ACRO_RLL_IMAX = new System.Windows.Forms.NumericUpDown(); - this.label40 = new System.Windows.Forms.Label(); - this.ACRO_RLL_I = new System.Windows.Forms.NumericUpDown(); - this.label44 = new System.Windows.Forms.Label(); - this.ACRO_RLL_P = new System.Windows.Forms.NumericUpDown(); - this.label48 = new System.Windows.Forms.Label(); ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit(); this.ConfigTabs.SuspendLayout(); this.TabAPM2.SuspendLayout(); this.groupBox3.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).BeginInit(); this.groupBox1.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).BeginInit(); this.groupBox2.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).BeginInit(); this.groupBox15.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).BeginInit(); this.groupBox16.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).BeginInit(); this.groupBox14.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).BeginInit(); this.groupBox13.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).BeginInit(); this.groupBox12.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).BeginInit(); this.groupBox11.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).BeginInit(); this.groupBox10.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).BeginInit(); this.groupBox9.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).BeginInit(); this.groupBox8.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).BeginInit(); this.TabAC2.SuspendLayout(); + this.groupBox17.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_P)).BeginInit(); this.groupBox5.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).BeginInit(); + this.groupBox18.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_P)).BeginInit(); this.groupBox4.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).BeginInit(); this.groupBox6.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD1)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRACK_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRACK_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRACK_P)).BeginInit(); this.groupBox7.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).BeginInit(); this.groupBox19.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).BeginInit(); this.groupBox20.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).BeginInit(); this.groupBox21.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).BeginInit(); this.groupBox22.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).BeginInit(); this.groupBox23.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).BeginInit(); this.groupBox24.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).BeginInit(); this.groupBox25.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).BeginInit(); this.TabPlanner.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit(); - this.groupBox17.SuspendLayout(); - this.groupBox18.SuspendLayout(); this.SuspendLayout(); // // Params // + resources.ApplyResources(this.Params, "Params"); this.Params.AllowUserToAddRows = false; this.Params.AllowUserToDeleteRows = false; - resources.ApplyResources(this.Params, "Params"); dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon; dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); @@ -352,6 +437,7 @@ dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True; this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2; this.Params.RowHeadersVisible = false; + this.toolTip1.SetToolTip(this.Params, resources.GetString("Params.ToolTip")); this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged); // // Command @@ -389,10 +475,12 @@ this.ConfigTabs.Controls.Add(this.TabSetup); this.ConfigTabs.Name = "ConfigTabs"; this.ConfigTabs.SelectedIndex = 0; + this.toolTip1.SetToolTip(this.ConfigTabs, resources.GetString("ConfigTabs.ToolTip")); this.ConfigTabs.SelectedIndexChanged += new System.EventHandler(this.Planner_TabIndexChanged); // // TabAPM2 // + resources.ApplyResources(this.TabAPM2, "TabAPM2"); this.TabAPM2.BackColor = System.Drawing.Color.Transparent; this.TabAPM2.Controls.Add(this.groupBox3); this.TabAPM2.Controls.Add(this.groupBox1); @@ -406,11 +494,12 @@ this.TabAPM2.Controls.Add(this.groupBox10); this.TabAPM2.Controls.Add(this.groupBox9); this.TabAPM2.Controls.Add(this.groupBox8); - resources.ApplyResources(this.TabAPM2, "TabAPM2"); this.TabAPM2.Name = "TabAPM2"; + this.toolTip1.SetToolTip(this.TabAPM2, resources.GetString("TabAPM2.ToolTip")); // // groupBox3 // + resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Controls.Add(this.THR_FS_VALUE); this.groupBox3.Controls.Add(this.label5); this.groupBox3.Controls.Add(this.THR_MAX); @@ -419,52 +508,61 @@ this.groupBox3.Controls.Add(this.label7); this.groupBox3.Controls.Add(this.TRIM_THROTTLE); this.groupBox3.Controls.Add(this.label8); - resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Name = "groupBox3"; this.groupBox3.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox3, resources.GetString("groupBox3.ToolTip")); // // THR_FS_VALUE // resources.ApplyResources(this.THR_FS_VALUE, "THR_FS_VALUE"); this.THR_FS_VALUE.Name = "THR_FS_VALUE"; + this.toolTip1.SetToolTip(this.THR_FS_VALUE, resources.GetString("THR_FS_VALUE.ToolTip")); // // label5 // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; + this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // THR_MAX // resources.ApplyResources(this.THR_MAX, "THR_MAX"); this.THR_MAX.Name = "THR_MAX"; + this.toolTip1.SetToolTip(this.THR_MAX, resources.GetString("THR_MAX.ToolTip")); // // label6 // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; + this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // THR_MIN // resources.ApplyResources(this.THR_MIN, "THR_MIN"); this.THR_MIN.Name = "THR_MIN"; + this.toolTip1.SetToolTip(this.THR_MIN, resources.GetString("THR_MIN.ToolTip")); // // label7 // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; + this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // TRIM_THROTTLE // resources.ApplyResources(this.TRIM_THROTTLE, "TRIM_THROTTLE"); this.TRIM_THROTTLE.Name = "TRIM_THROTTLE"; + this.toolTip1.SetToolTip(this.TRIM_THROTTLE, resources.GetString("TRIM_THROTTLE.ToolTip")); // // label8 // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; + this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // groupBox1 // + resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Controls.Add(this.ARSPD_RATIO); this.groupBox1.Controls.Add(this.label1); this.groupBox1.Controls.Add(this.ARSPD_FBW_MAX); @@ -473,166 +571,194 @@ this.groupBox1.Controls.Add(this.label3); this.groupBox1.Controls.Add(this.TRIM_ARSPD_CM); this.groupBox1.Controls.Add(this.label4); - resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Name = "groupBox1"; this.groupBox1.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox1, resources.GetString("groupBox1.ToolTip")); // // ARSPD_RATIO // resources.ApplyResources(this.ARSPD_RATIO, "ARSPD_RATIO"); this.ARSPD_RATIO.Name = "ARSPD_RATIO"; + this.toolTip1.SetToolTip(this.ARSPD_RATIO, resources.GetString("ARSPD_RATIO.ToolTip")); // // label1 // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; + this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // ARSPD_FBW_MAX // resources.ApplyResources(this.ARSPD_FBW_MAX, "ARSPD_FBW_MAX"); this.ARSPD_FBW_MAX.Name = "ARSPD_FBW_MAX"; + this.toolTip1.SetToolTip(this.ARSPD_FBW_MAX, resources.GetString("ARSPD_FBW_MAX.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; + this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // ARSPD_FBW_MIN // resources.ApplyResources(this.ARSPD_FBW_MIN, "ARSPD_FBW_MIN"); this.ARSPD_FBW_MIN.Name = "ARSPD_FBW_MIN"; + this.toolTip1.SetToolTip(this.ARSPD_FBW_MIN, resources.GetString("ARSPD_FBW_MIN.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; + this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // TRIM_ARSPD_CM // resources.ApplyResources(this.TRIM_ARSPD_CM, "TRIM_ARSPD_CM"); this.TRIM_ARSPD_CM.Name = "TRIM_ARSPD_CM"; + this.toolTip1.SetToolTip(this.TRIM_ARSPD_CM, resources.GetString("TRIM_ARSPD_CM.ToolTip")); // // label4 // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; + this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // groupBox2 // + resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Controls.Add(this.LIM_PITCH_MIN); this.groupBox2.Controls.Add(this.label39); this.groupBox2.Controls.Add(this.LIM_PITCH_MAX); this.groupBox2.Controls.Add(this.label38); this.groupBox2.Controls.Add(this.LIM_ROLL_CD); this.groupBox2.Controls.Add(this.label37); - resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Name = "groupBox2"; this.groupBox2.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox2, resources.GetString("groupBox2.ToolTip")); // // LIM_PITCH_MIN // resources.ApplyResources(this.LIM_PITCH_MIN, "LIM_PITCH_MIN"); this.LIM_PITCH_MIN.Name = "LIM_PITCH_MIN"; + this.toolTip1.SetToolTip(this.LIM_PITCH_MIN, resources.GetString("LIM_PITCH_MIN.ToolTip")); // // label39 // resources.ApplyResources(this.label39, "label39"); this.label39.Name = "label39"; + this.toolTip1.SetToolTip(this.label39, resources.GetString("label39.ToolTip")); // // LIM_PITCH_MAX // resources.ApplyResources(this.LIM_PITCH_MAX, "LIM_PITCH_MAX"); this.LIM_PITCH_MAX.Name = "LIM_PITCH_MAX"; + this.toolTip1.SetToolTip(this.LIM_PITCH_MAX, resources.GetString("LIM_PITCH_MAX.ToolTip")); // // label38 // resources.ApplyResources(this.label38, "label38"); this.label38.Name = "label38"; + this.toolTip1.SetToolTip(this.label38, resources.GetString("label38.ToolTip")); // // LIM_ROLL_CD // resources.ApplyResources(this.LIM_ROLL_CD, "LIM_ROLL_CD"); this.LIM_ROLL_CD.Name = "LIM_ROLL_CD"; + this.toolTip1.SetToolTip(this.LIM_ROLL_CD, resources.GetString("LIM_ROLL_CD.ToolTip")); // // label37 // resources.ApplyResources(this.label37, "label37"); this.label37.Name = "label37"; + this.toolTip1.SetToolTip(this.label37, resources.GetString("label37.ToolTip")); // // groupBox15 // + resources.ApplyResources(this.groupBox15, "groupBox15"); this.groupBox15.Controls.Add(this.XTRK_ANGLE_CD); this.groupBox15.Controls.Add(this.label79); this.groupBox15.Controls.Add(this.XTRK_GAIN_SC); this.groupBox15.Controls.Add(this.label80); - resources.ApplyResources(this.groupBox15, "groupBox15"); this.groupBox15.Name = "groupBox15"; this.groupBox15.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox15, resources.GetString("groupBox15.ToolTip")); // // XTRK_ANGLE_CD // resources.ApplyResources(this.XTRK_ANGLE_CD, "XTRK_ANGLE_CD"); this.XTRK_ANGLE_CD.Name = "XTRK_ANGLE_CD"; + this.toolTip1.SetToolTip(this.XTRK_ANGLE_CD, resources.GetString("XTRK_ANGLE_CD.ToolTip")); // // label79 // resources.ApplyResources(this.label79, "label79"); this.label79.Name = "label79"; + this.toolTip1.SetToolTip(this.label79, resources.GetString("label79.ToolTip")); // // XTRK_GAIN_SC // resources.ApplyResources(this.XTRK_GAIN_SC, "XTRK_GAIN_SC"); this.XTRK_GAIN_SC.Name = "XTRK_GAIN_SC"; + this.toolTip1.SetToolTip(this.XTRK_GAIN_SC, resources.GetString("XTRK_GAIN_SC.ToolTip")); // // label80 // resources.ApplyResources(this.label80, "label80"); this.label80.Name = "label80"; + this.toolTip1.SetToolTip(this.label80, resources.GetString("label80.ToolTip")); // // groupBox16 // + resources.ApplyResources(this.groupBox16, "groupBox16"); this.groupBox16.Controls.Add(this.KFF_PTCH2THR); this.groupBox16.Controls.Add(this.label83); this.groupBox16.Controls.Add(this.KFF_RDDRMIX); this.groupBox16.Controls.Add(this.label78); this.groupBox16.Controls.Add(this.KFF_PTCHCOMP); this.groupBox16.Controls.Add(this.label81); - resources.ApplyResources(this.groupBox16, "groupBox16"); this.groupBox16.Name = "groupBox16"; this.groupBox16.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox16, resources.GetString("groupBox16.ToolTip")); // // KFF_PTCH2THR // resources.ApplyResources(this.KFF_PTCH2THR, "KFF_PTCH2THR"); this.KFF_PTCH2THR.Name = "KFF_PTCH2THR"; + this.toolTip1.SetToolTip(this.KFF_PTCH2THR, resources.GetString("KFF_PTCH2THR.ToolTip")); // // label83 // resources.ApplyResources(this.label83, "label83"); this.label83.Name = "label83"; + this.toolTip1.SetToolTip(this.label83, resources.GetString("label83.ToolTip")); // // KFF_RDDRMIX // resources.ApplyResources(this.KFF_RDDRMIX, "KFF_RDDRMIX"); this.KFF_RDDRMIX.Name = "KFF_RDDRMIX"; + this.toolTip1.SetToolTip(this.KFF_RDDRMIX, resources.GetString("KFF_RDDRMIX.ToolTip")); // // label78 // resources.ApplyResources(this.label78, "label78"); this.label78.Name = "label78"; + this.toolTip1.SetToolTip(this.label78, resources.GetString("label78.ToolTip")); // // KFF_PTCHCOMP // resources.ApplyResources(this.KFF_PTCHCOMP, "KFF_PTCHCOMP"); this.KFF_PTCHCOMP.Name = "KFF_PTCHCOMP"; + this.toolTip1.SetToolTip(this.KFF_PTCHCOMP, resources.GetString("KFF_PTCHCOMP.ToolTip")); // // label81 // resources.ApplyResources(this.label81, "label81"); this.label81.Name = "label81"; + this.toolTip1.SetToolTip(this.label81, resources.GetString("label81.ToolTip")); // // groupBox14 // + resources.ApplyResources(this.groupBox14, "groupBox14"); this.groupBox14.Controls.Add(this.ENRGY2THR_IMAX); this.groupBox14.Controls.Add(this.label73); this.groupBox14.Controls.Add(this.ENRGY2THR_D); @@ -641,52 +767,61 @@ this.groupBox14.Controls.Add(this.label75); this.groupBox14.Controls.Add(this.ENRGY2THR_P); this.groupBox14.Controls.Add(this.label76); - resources.ApplyResources(this.groupBox14, "groupBox14"); this.groupBox14.Name = "groupBox14"; this.groupBox14.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox14, resources.GetString("groupBox14.ToolTip")); // // ENRGY2THR_IMAX // resources.ApplyResources(this.ENRGY2THR_IMAX, "ENRGY2THR_IMAX"); this.ENRGY2THR_IMAX.Name = "ENRGY2THR_IMAX"; + this.toolTip1.SetToolTip(this.ENRGY2THR_IMAX, resources.GetString("ENRGY2THR_IMAX.ToolTip")); // // label73 // resources.ApplyResources(this.label73, "label73"); this.label73.Name = "label73"; + this.toolTip1.SetToolTip(this.label73, resources.GetString("label73.ToolTip")); // // ENRGY2THR_D // resources.ApplyResources(this.ENRGY2THR_D, "ENRGY2THR_D"); this.ENRGY2THR_D.Name = "ENRGY2THR_D"; + this.toolTip1.SetToolTip(this.ENRGY2THR_D, resources.GetString("ENRGY2THR_D.ToolTip")); // // label74 // resources.ApplyResources(this.label74, "label74"); this.label74.Name = "label74"; + this.toolTip1.SetToolTip(this.label74, resources.GetString("label74.ToolTip")); // // ENRGY2THR_I // resources.ApplyResources(this.ENRGY2THR_I, "ENRGY2THR_I"); this.ENRGY2THR_I.Name = "ENRGY2THR_I"; + this.toolTip1.SetToolTip(this.ENRGY2THR_I, resources.GetString("ENRGY2THR_I.ToolTip")); // // label75 // resources.ApplyResources(this.label75, "label75"); this.label75.Name = "label75"; + this.toolTip1.SetToolTip(this.label75, resources.GetString("label75.ToolTip")); // // ENRGY2THR_P // resources.ApplyResources(this.ENRGY2THR_P, "ENRGY2THR_P"); this.ENRGY2THR_P.Name = "ENRGY2THR_P"; + this.toolTip1.SetToolTip(this.ENRGY2THR_P, resources.GetString("ENRGY2THR_P.ToolTip")); // // label76 // resources.ApplyResources(this.label76, "label76"); this.label76.Name = "label76"; + this.toolTip1.SetToolTip(this.label76, resources.GetString("label76.ToolTip")); // // groupBox13 // + resources.ApplyResources(this.groupBox13, "groupBox13"); this.groupBox13.Controls.Add(this.ALT2PTCH_IMAX); this.groupBox13.Controls.Add(this.label69); this.groupBox13.Controls.Add(this.ALT2PTCH_D); @@ -695,52 +830,61 @@ this.groupBox13.Controls.Add(this.label71); this.groupBox13.Controls.Add(this.ALT2PTCH_P); this.groupBox13.Controls.Add(this.label72); - resources.ApplyResources(this.groupBox13, "groupBox13"); this.groupBox13.Name = "groupBox13"; this.groupBox13.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox13, resources.GetString("groupBox13.ToolTip")); // // ALT2PTCH_IMAX // resources.ApplyResources(this.ALT2PTCH_IMAX, "ALT2PTCH_IMAX"); this.ALT2PTCH_IMAX.Name = "ALT2PTCH_IMAX"; + this.toolTip1.SetToolTip(this.ALT2PTCH_IMAX, resources.GetString("ALT2PTCH_IMAX.ToolTip")); // // label69 // resources.ApplyResources(this.label69, "label69"); this.label69.Name = "label69"; + this.toolTip1.SetToolTip(this.label69, resources.GetString("label69.ToolTip")); // // ALT2PTCH_D // resources.ApplyResources(this.ALT2PTCH_D, "ALT2PTCH_D"); this.ALT2PTCH_D.Name = "ALT2PTCH_D"; + this.toolTip1.SetToolTip(this.ALT2PTCH_D, resources.GetString("ALT2PTCH_D.ToolTip")); // // label70 // resources.ApplyResources(this.label70, "label70"); this.label70.Name = "label70"; + this.toolTip1.SetToolTip(this.label70, resources.GetString("label70.ToolTip")); // // ALT2PTCH_I // resources.ApplyResources(this.ALT2PTCH_I, "ALT2PTCH_I"); this.ALT2PTCH_I.Name = "ALT2PTCH_I"; + this.toolTip1.SetToolTip(this.ALT2PTCH_I, resources.GetString("ALT2PTCH_I.ToolTip")); // // label71 // resources.ApplyResources(this.label71, "label71"); this.label71.Name = "label71"; + this.toolTip1.SetToolTip(this.label71, resources.GetString("label71.ToolTip")); // // ALT2PTCH_P // resources.ApplyResources(this.ALT2PTCH_P, "ALT2PTCH_P"); this.ALT2PTCH_P.Name = "ALT2PTCH_P"; + this.toolTip1.SetToolTip(this.ALT2PTCH_P, resources.GetString("ALT2PTCH_P.ToolTip")); // // label72 // resources.ApplyResources(this.label72, "label72"); this.label72.Name = "label72"; + this.toolTip1.SetToolTip(this.label72, resources.GetString("label72.ToolTip")); // // groupBox12 // + resources.ApplyResources(this.groupBox12, "groupBox12"); this.groupBox12.Controls.Add(this.ARSP2PTCH_IMAX); this.groupBox12.Controls.Add(this.label65); this.groupBox12.Controls.Add(this.ARSP2PTCH_D); @@ -749,52 +893,61 @@ this.groupBox12.Controls.Add(this.label67); this.groupBox12.Controls.Add(this.ARSP2PTCH_P); this.groupBox12.Controls.Add(this.label68); - resources.ApplyResources(this.groupBox12, "groupBox12"); this.groupBox12.Name = "groupBox12"; this.groupBox12.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox12, resources.GetString("groupBox12.ToolTip")); // // ARSP2PTCH_IMAX // resources.ApplyResources(this.ARSP2PTCH_IMAX, "ARSP2PTCH_IMAX"); this.ARSP2PTCH_IMAX.Name = "ARSP2PTCH_IMAX"; + this.toolTip1.SetToolTip(this.ARSP2PTCH_IMAX, resources.GetString("ARSP2PTCH_IMAX.ToolTip")); // // label65 // resources.ApplyResources(this.label65, "label65"); this.label65.Name = "label65"; + this.toolTip1.SetToolTip(this.label65, resources.GetString("label65.ToolTip")); // // ARSP2PTCH_D // resources.ApplyResources(this.ARSP2PTCH_D, "ARSP2PTCH_D"); this.ARSP2PTCH_D.Name = "ARSP2PTCH_D"; + this.toolTip1.SetToolTip(this.ARSP2PTCH_D, resources.GetString("ARSP2PTCH_D.ToolTip")); // // label66 // resources.ApplyResources(this.label66, "label66"); this.label66.Name = "label66"; + this.toolTip1.SetToolTip(this.label66, resources.GetString("label66.ToolTip")); // // ARSP2PTCH_I // resources.ApplyResources(this.ARSP2PTCH_I, "ARSP2PTCH_I"); this.ARSP2PTCH_I.Name = "ARSP2PTCH_I"; + this.toolTip1.SetToolTip(this.ARSP2PTCH_I, resources.GetString("ARSP2PTCH_I.ToolTip")); // // label67 // resources.ApplyResources(this.label67, "label67"); this.label67.Name = "label67"; + this.toolTip1.SetToolTip(this.label67, resources.GetString("label67.ToolTip")); // // ARSP2PTCH_P // resources.ApplyResources(this.ARSP2PTCH_P, "ARSP2PTCH_P"); this.ARSP2PTCH_P.Name = "ARSP2PTCH_P"; + this.toolTip1.SetToolTip(this.ARSP2PTCH_P, resources.GetString("ARSP2PTCH_P.ToolTip")); // // label68 // resources.ApplyResources(this.label68, "label68"); this.label68.Name = "label68"; + this.toolTip1.SetToolTip(this.label68, resources.GetString("label68.ToolTip")); // // groupBox11 // + resources.ApplyResources(this.groupBox11, "groupBox11"); this.groupBox11.Controls.Add(this.HDNG2RLL_IMAX); this.groupBox11.Controls.Add(this.label61); this.groupBox11.Controls.Add(this.HDNG2RLL_D); @@ -803,52 +956,61 @@ this.groupBox11.Controls.Add(this.label63); this.groupBox11.Controls.Add(this.HDNG2RLL_P); this.groupBox11.Controls.Add(this.label64); - resources.ApplyResources(this.groupBox11, "groupBox11"); this.groupBox11.Name = "groupBox11"; this.groupBox11.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox11, resources.GetString("groupBox11.ToolTip")); // // HDNG2RLL_IMAX // resources.ApplyResources(this.HDNG2RLL_IMAX, "HDNG2RLL_IMAX"); this.HDNG2RLL_IMAX.Name = "HDNG2RLL_IMAX"; + this.toolTip1.SetToolTip(this.HDNG2RLL_IMAX, resources.GetString("HDNG2RLL_IMAX.ToolTip")); // // label61 // resources.ApplyResources(this.label61, "label61"); this.label61.Name = "label61"; + this.toolTip1.SetToolTip(this.label61, resources.GetString("label61.ToolTip")); // // HDNG2RLL_D // resources.ApplyResources(this.HDNG2RLL_D, "HDNG2RLL_D"); this.HDNG2RLL_D.Name = "HDNG2RLL_D"; + this.toolTip1.SetToolTip(this.HDNG2RLL_D, resources.GetString("HDNG2RLL_D.ToolTip")); // // label62 // resources.ApplyResources(this.label62, "label62"); this.label62.Name = "label62"; + this.toolTip1.SetToolTip(this.label62, resources.GetString("label62.ToolTip")); // // HDNG2RLL_I // resources.ApplyResources(this.HDNG2RLL_I, "HDNG2RLL_I"); this.HDNG2RLL_I.Name = "HDNG2RLL_I"; + this.toolTip1.SetToolTip(this.HDNG2RLL_I, resources.GetString("HDNG2RLL_I.ToolTip")); // // label63 // resources.ApplyResources(this.label63, "label63"); this.label63.Name = "label63"; + this.toolTip1.SetToolTip(this.label63, resources.GetString("label63.ToolTip")); // // HDNG2RLL_P // resources.ApplyResources(this.HDNG2RLL_P, "HDNG2RLL_P"); this.HDNG2RLL_P.Name = "HDNG2RLL_P"; + this.toolTip1.SetToolTip(this.HDNG2RLL_P, resources.GetString("HDNG2RLL_P.ToolTip")); // // label64 // resources.ApplyResources(this.label64, "label64"); this.label64.Name = "label64"; + this.toolTip1.SetToolTip(this.label64, resources.GetString("label64.ToolTip")); // // groupBox10 // + resources.ApplyResources(this.groupBox10, "groupBox10"); this.groupBox10.Controls.Add(this.YW2SRV_IMAX); this.groupBox10.Controls.Add(this.label57); this.groupBox10.Controls.Add(this.YW2SRV_D); @@ -857,52 +1019,61 @@ this.groupBox10.Controls.Add(this.label59); this.groupBox10.Controls.Add(this.YW2SRV_P); this.groupBox10.Controls.Add(this.label60); - resources.ApplyResources(this.groupBox10, "groupBox10"); this.groupBox10.Name = "groupBox10"; this.groupBox10.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox10, resources.GetString("groupBox10.ToolTip")); // // YW2SRV_IMAX // resources.ApplyResources(this.YW2SRV_IMAX, "YW2SRV_IMAX"); this.YW2SRV_IMAX.Name = "YW2SRV_IMAX"; + this.toolTip1.SetToolTip(this.YW2SRV_IMAX, resources.GetString("YW2SRV_IMAX.ToolTip")); // // label57 // resources.ApplyResources(this.label57, "label57"); this.label57.Name = "label57"; + this.toolTip1.SetToolTip(this.label57, resources.GetString("label57.ToolTip")); // // YW2SRV_D // resources.ApplyResources(this.YW2SRV_D, "YW2SRV_D"); this.YW2SRV_D.Name = "YW2SRV_D"; + this.toolTip1.SetToolTip(this.YW2SRV_D, resources.GetString("YW2SRV_D.ToolTip")); // // label58 // resources.ApplyResources(this.label58, "label58"); this.label58.Name = "label58"; + this.toolTip1.SetToolTip(this.label58, resources.GetString("label58.ToolTip")); // // YW2SRV_I // resources.ApplyResources(this.YW2SRV_I, "YW2SRV_I"); this.YW2SRV_I.Name = "YW2SRV_I"; + this.toolTip1.SetToolTip(this.YW2SRV_I, resources.GetString("YW2SRV_I.ToolTip")); // // label59 // resources.ApplyResources(this.label59, "label59"); this.label59.Name = "label59"; + this.toolTip1.SetToolTip(this.label59, resources.GetString("label59.ToolTip")); // // YW2SRV_P // resources.ApplyResources(this.YW2SRV_P, "YW2SRV_P"); this.YW2SRV_P.Name = "YW2SRV_P"; + this.toolTip1.SetToolTip(this.YW2SRV_P, resources.GetString("YW2SRV_P.ToolTip")); // // label60 // resources.ApplyResources(this.label60, "label60"); this.label60.Name = "label60"; + this.toolTip1.SetToolTip(this.label60, resources.GetString("label60.ToolTip")); // // groupBox9 // + resources.ApplyResources(this.groupBox9, "groupBox9"); this.groupBox9.Controls.Add(this.PTCH2SRV_IMAX); this.groupBox9.Controls.Add(this.label53); this.groupBox9.Controls.Add(this.PTCH2SRV_D); @@ -911,52 +1082,61 @@ this.groupBox9.Controls.Add(this.label55); this.groupBox9.Controls.Add(this.PTCH2SRV_P); this.groupBox9.Controls.Add(this.label56); - resources.ApplyResources(this.groupBox9, "groupBox9"); this.groupBox9.Name = "groupBox9"; this.groupBox9.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox9, resources.GetString("groupBox9.ToolTip")); // // PTCH2SRV_IMAX // resources.ApplyResources(this.PTCH2SRV_IMAX, "PTCH2SRV_IMAX"); this.PTCH2SRV_IMAX.Name = "PTCH2SRV_IMAX"; + this.toolTip1.SetToolTip(this.PTCH2SRV_IMAX, resources.GetString("PTCH2SRV_IMAX.ToolTip")); // // label53 // resources.ApplyResources(this.label53, "label53"); this.label53.Name = "label53"; + this.toolTip1.SetToolTip(this.label53, resources.GetString("label53.ToolTip")); // // PTCH2SRV_D // resources.ApplyResources(this.PTCH2SRV_D, "PTCH2SRV_D"); this.PTCH2SRV_D.Name = "PTCH2SRV_D"; + this.toolTip1.SetToolTip(this.PTCH2SRV_D, resources.GetString("PTCH2SRV_D.ToolTip")); // // label54 // resources.ApplyResources(this.label54, "label54"); this.label54.Name = "label54"; + this.toolTip1.SetToolTip(this.label54, resources.GetString("label54.ToolTip")); // // PTCH2SRV_I // resources.ApplyResources(this.PTCH2SRV_I, "PTCH2SRV_I"); this.PTCH2SRV_I.Name = "PTCH2SRV_I"; + this.toolTip1.SetToolTip(this.PTCH2SRV_I, resources.GetString("PTCH2SRV_I.ToolTip")); // // label55 // resources.ApplyResources(this.label55, "label55"); this.label55.Name = "label55"; + this.toolTip1.SetToolTip(this.label55, resources.GetString("label55.ToolTip")); // // PTCH2SRV_P // resources.ApplyResources(this.PTCH2SRV_P, "PTCH2SRV_P"); this.PTCH2SRV_P.Name = "PTCH2SRV_P"; + this.toolTip1.SetToolTip(this.PTCH2SRV_P, resources.GetString("PTCH2SRV_P.ToolTip")); // // label56 // resources.ApplyResources(this.label56, "label56"); this.label56.Name = "label56"; + this.toolTip1.SetToolTip(this.label56, resources.GetString("label56.ToolTip")); // // groupBox8 // + resources.ApplyResources(this.groupBox8, "groupBox8"); this.groupBox8.Controls.Add(this.RLL2SRV_IMAX); this.groupBox8.Controls.Add(this.label49); this.groupBox8.Controls.Add(this.RLL2SRV_D); @@ -965,52 +1145,61 @@ this.groupBox8.Controls.Add(this.label51); this.groupBox8.Controls.Add(this.RLL2SRV_P); this.groupBox8.Controls.Add(this.label52); - resources.ApplyResources(this.groupBox8, "groupBox8"); this.groupBox8.Name = "groupBox8"; this.groupBox8.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox8, resources.GetString("groupBox8.ToolTip")); // // RLL2SRV_IMAX // resources.ApplyResources(this.RLL2SRV_IMAX, "RLL2SRV_IMAX"); this.RLL2SRV_IMAX.Name = "RLL2SRV_IMAX"; + this.toolTip1.SetToolTip(this.RLL2SRV_IMAX, resources.GetString("RLL2SRV_IMAX.ToolTip")); // // label49 // resources.ApplyResources(this.label49, "label49"); this.label49.Name = "label49"; + this.toolTip1.SetToolTip(this.label49, resources.GetString("label49.ToolTip")); // // RLL2SRV_D // resources.ApplyResources(this.RLL2SRV_D, "RLL2SRV_D"); this.RLL2SRV_D.Name = "RLL2SRV_D"; + this.toolTip1.SetToolTip(this.RLL2SRV_D, resources.GetString("RLL2SRV_D.ToolTip")); // // label50 // resources.ApplyResources(this.label50, "label50"); this.label50.Name = "label50"; + this.toolTip1.SetToolTip(this.label50, resources.GetString("label50.ToolTip")); // // RLL2SRV_I // resources.ApplyResources(this.RLL2SRV_I, "RLL2SRV_I"); this.RLL2SRV_I.Name = "RLL2SRV_I"; + this.toolTip1.SetToolTip(this.RLL2SRV_I, resources.GetString("RLL2SRV_I.ToolTip")); // // label51 // resources.ApplyResources(this.label51, "label51"); this.label51.Name = "label51"; + this.toolTip1.SetToolTip(this.label51, resources.GetString("label51.ToolTip")); // // RLL2SRV_P // resources.ApplyResources(this.RLL2SRV_P, "RLL2SRV_P"); this.RLL2SRV_P.Name = "RLL2SRV_P"; + this.toolTip1.SetToolTip(this.RLL2SRV_P, resources.GetString("RLL2SRV_P.ToolTip")); // // label52 // resources.ApplyResources(this.label52, "label52"); this.label52.Name = "label52"; + this.toolTip1.SetToolTip(this.label52, resources.GetString("label52.ToolTip")); // // TabAC2 // + resources.ApplyResources(this.TabAC2, "TabAC2"); this.TabAC2.Controls.Add(this.groupBox17); this.TabAC2.Controls.Add(this.groupBox5); this.TabAC2.Controls.Add(this.groupBox18); @@ -1025,50 +1214,155 @@ this.TabAC2.Controls.Add(this.groupBox23); this.TabAC2.Controls.Add(this.groupBox24); this.TabAC2.Controls.Add(this.groupBox25); - resources.ApplyResources(this.TabAC2, "TabAC2"); this.TabAC2.Name = "TabAC2"; + this.toolTip1.SetToolTip(this.TabAC2, resources.GetString("TabAC2.ToolTip")); + // + // groupBox17 + // + resources.ApplyResources(this.groupBox17, "groupBox17"); + this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX); + this.groupBox17.Controls.Add(this.label27); + this.groupBox17.Controls.Add(this.ACRO_PIT_I); + this.groupBox17.Controls.Add(this.label29); + this.groupBox17.Controls.Add(this.ACRO_PIT_P); + this.groupBox17.Controls.Add(this.label33); + this.groupBox17.Name = "groupBox17"; + this.groupBox17.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox17, resources.GetString("groupBox17.ToolTip")); + // + // ACRO_PIT_IMAX + // + resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX"); + this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX"; + this.toolTip1.SetToolTip(this.ACRO_PIT_IMAX, resources.GetString("ACRO_PIT_IMAX.ToolTip")); + // + // label27 + // + resources.ApplyResources(this.label27, "label27"); + this.label27.Name = "label27"; + this.toolTip1.SetToolTip(this.label27, resources.GetString("label27.ToolTip")); + // + // ACRO_PIT_I + // + resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I"); + this.ACRO_PIT_I.Name = "ACRO_PIT_I"; + this.toolTip1.SetToolTip(this.ACRO_PIT_I, resources.GetString("ACRO_PIT_I.ToolTip")); + // + // label29 + // + resources.ApplyResources(this.label29, "label29"); + this.label29.Name = "label29"; + this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); + // + // ACRO_PIT_P + // + resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P"); + this.ACRO_PIT_P.Name = "ACRO_PIT_P"; + this.toolTip1.SetToolTip(this.ACRO_PIT_P, resources.GetString("ACRO_PIT_P.ToolTip")); + // + // label33 + // + resources.ApplyResources(this.label33, "label33"); + this.label33.Name = "label33"; + this.toolTip1.SetToolTip(this.label33, resources.GetString("label33.ToolTip")); // // groupBox5 // + resources.ApplyResources(this.groupBox5, "groupBox5"); this.groupBox5.Controls.Add(this.label14); this.groupBox5.Controls.Add(this.THR_RATE_IMAX); this.groupBox5.Controls.Add(this.THR_RATE_I); this.groupBox5.Controls.Add(this.label20); this.groupBox5.Controls.Add(this.THR_RATE_P); this.groupBox5.Controls.Add(this.label25); - resources.ApplyResources(this.groupBox5, "groupBox5"); this.groupBox5.Name = "groupBox5"; this.groupBox5.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox5, resources.GetString("groupBox5.ToolTip")); // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; + this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // THR_RATE_IMAX // resources.ApplyResources(this.THR_RATE_IMAX, "THR_RATE_IMAX"); this.THR_RATE_IMAX.Name = "THR_RATE_IMAX"; + this.toolTip1.SetToolTip(this.THR_RATE_IMAX, resources.GetString("THR_RATE_IMAX.ToolTip")); // // THR_RATE_I // resources.ApplyResources(this.THR_RATE_I, "THR_RATE_I"); this.THR_RATE_I.Name = "THR_RATE_I"; + this.toolTip1.SetToolTip(this.THR_RATE_I, resources.GetString("THR_RATE_I.ToolTip")); // // label20 // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; + this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // THR_RATE_P // resources.ApplyResources(this.THR_RATE_P, "THR_RATE_P"); this.THR_RATE_P.Name = "THR_RATE_P"; + this.toolTip1.SetToolTip(this.THR_RATE_P, resources.GetString("THR_RATE_P.ToolTip")); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; + this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); + // + // groupBox18 + // + resources.ApplyResources(this.groupBox18, "groupBox18"); + this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX); + this.groupBox18.Controls.Add(this.label40); + this.groupBox18.Controls.Add(this.ACRO_RLL_I); + this.groupBox18.Controls.Add(this.label44); + this.groupBox18.Controls.Add(this.ACRO_RLL_P); + this.groupBox18.Controls.Add(this.label48); + this.groupBox18.Name = "groupBox18"; + this.groupBox18.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox18, resources.GetString("groupBox18.ToolTip")); + // + // ACRO_RLL_IMAX + // + resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX"); + this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX"; + this.toolTip1.SetToolTip(this.ACRO_RLL_IMAX, resources.GetString("ACRO_RLL_IMAX.ToolTip")); + // + // label40 + // + resources.ApplyResources(this.label40, "label40"); + this.label40.Name = "label40"; + this.toolTip1.SetToolTip(this.label40, resources.GetString("label40.ToolTip")); + // + // ACRO_RLL_I + // + resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I"); + this.ACRO_RLL_I.Name = "ACRO_RLL_I"; + this.toolTip1.SetToolTip(this.ACRO_RLL_I, resources.GetString("ACRO_RLL_I.ToolTip")); + // + // label44 + // + resources.ApplyResources(this.label44, "label44"); + this.label44.Name = "label44"; + this.toolTip1.SetToolTip(this.label44, resources.GetString("label44.ToolTip")); + // + // ACRO_RLL_P + // + resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P"); + this.ACRO_RLL_P.Name = "ACRO_RLL_P"; + this.toolTip1.SetToolTip(this.ACRO_RLL_P, resources.GetString("ACRO_RLL_P.ToolTip")); + // + // label48 + // + resources.ApplyResources(this.label48, "label48"); + this.label48.Name = "label48"; + this.toolTip1.SetToolTip(this.label48, resources.GetString("label48.ToolTip")); // // CHK_lockrollpitch // @@ -1076,11 +1370,13 @@ this.CHK_lockrollpitch.Checked = true; this.CHK_lockrollpitch.CheckState = System.Windows.Forms.CheckState.Checked; this.CHK_lockrollpitch.Name = "CHK_lockrollpitch"; + this.toolTip1.SetToolTip(this.CHK_lockrollpitch, resources.GetString("CHK_lockrollpitch.ToolTip")); this.CHK_lockrollpitch.UseVisualStyleBackColor = true; this.CHK_lockrollpitch.CheckedChanged += new System.EventHandler(this.CHK_lockrollpitch_CheckedChanged); // // groupBox4 // + resources.ApplyResources(this.groupBox4, "groupBox4"); this.groupBox4.Controls.Add(this.WP_SPEED_MAX); this.groupBox4.Controls.Add(this.label9); this.groupBox4.Controls.Add(this.NAV_LAT_IMAX); @@ -1089,52 +1385,61 @@ this.groupBox4.Controls.Add(this.label15); this.groupBox4.Controls.Add(this.NAV_LAT_P); this.groupBox4.Controls.Add(this.label16); - resources.ApplyResources(this.groupBox4, "groupBox4"); this.groupBox4.Name = "groupBox4"; this.groupBox4.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox4, resources.GetString("groupBox4.ToolTip")); // // WP_SPEED_MAX // resources.ApplyResources(this.WP_SPEED_MAX, "WP_SPEED_MAX"); this.WP_SPEED_MAX.Name = "WP_SPEED_MAX"; + this.toolTip1.SetToolTip(this.WP_SPEED_MAX, resources.GetString("WP_SPEED_MAX.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; + this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // NAV_LAT_IMAX // resources.ApplyResources(this.NAV_LAT_IMAX, "NAV_LAT_IMAX"); this.NAV_LAT_IMAX.Name = "NAV_LAT_IMAX"; + this.toolTip1.SetToolTip(this.NAV_LAT_IMAX, resources.GetString("NAV_LAT_IMAX.ToolTip")); // // label13 // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; + this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // NAV_LAT_I // resources.ApplyResources(this.NAV_LAT_I, "NAV_LAT_I"); this.NAV_LAT_I.Name = "NAV_LAT_I"; + this.toolTip1.SetToolTip(this.NAV_LAT_I, resources.GetString("NAV_LAT_I.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; + this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // NAV_LAT_P // resources.ApplyResources(this.NAV_LAT_P, "NAV_LAT_P"); this.NAV_LAT_P.Name = "NAV_LAT_P"; + this.toolTip1.SetToolTip(this.NAV_LAT_P, resources.GetString("NAV_LAT_P.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; + this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // groupBox6 // + resources.ApplyResources(this.groupBox6, "groupBox6"); this.groupBox6.Controls.Add(this.XTRK_ANGLE_CD1); this.groupBox6.Controls.Add(this.label10); this.groupBox6.Controls.Add(this.XTRACK_IMAX); @@ -1143,388 +1448,453 @@ this.groupBox6.Controls.Add(this.label17); this.groupBox6.Controls.Add(this.XTRACK_P); this.groupBox6.Controls.Add(this.label18); - resources.ApplyResources(this.groupBox6, "groupBox6"); this.groupBox6.Name = "groupBox6"; this.groupBox6.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox6, resources.GetString("groupBox6.ToolTip")); // // XTRK_ANGLE_CD1 // resources.ApplyResources(this.XTRK_ANGLE_CD1, "XTRK_ANGLE_CD1"); this.XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD1"; + this.toolTip1.SetToolTip(this.XTRK_ANGLE_CD1, resources.GetString("XTRK_ANGLE_CD1.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; + this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); // // XTRACK_IMAX // resources.ApplyResources(this.XTRACK_IMAX, "XTRACK_IMAX"); this.XTRACK_IMAX.Name = "XTRACK_IMAX"; + this.toolTip1.SetToolTip(this.XTRACK_IMAX, resources.GetString("XTRACK_IMAX.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; + this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // XTRACK_I // resources.ApplyResources(this.XTRACK_I, "XTRACK_I"); this.XTRACK_I.Name = "XTRACK_I"; + this.toolTip1.SetToolTip(this.XTRACK_I, resources.GetString("XTRACK_I.ToolTip")); // // label17 // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; + this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // XTRACK_P // resources.ApplyResources(this.XTRACK_P, "XTRACK_P"); this.XTRACK_P.Name = "XTRACK_P"; + this.toolTip1.SetToolTip(this.XTRACK_P, resources.GetString("XTRACK_P.ToolTip")); // // label18 // resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; + this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip")); // // groupBox7 // + resources.ApplyResources(this.groupBox7, "groupBox7"); this.groupBox7.Controls.Add(this.THR_ALT_IMAX); this.groupBox7.Controls.Add(this.label19); this.groupBox7.Controls.Add(this.THR_ALT_I); this.groupBox7.Controls.Add(this.label21); this.groupBox7.Controls.Add(this.THR_ALT_P); this.groupBox7.Controls.Add(this.label22); - resources.ApplyResources(this.groupBox7, "groupBox7"); this.groupBox7.Name = "groupBox7"; this.groupBox7.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox7, resources.GetString("groupBox7.ToolTip")); // // THR_ALT_IMAX // resources.ApplyResources(this.THR_ALT_IMAX, "THR_ALT_IMAX"); this.THR_ALT_IMAX.Name = "THR_ALT_IMAX"; + this.toolTip1.SetToolTip(this.THR_ALT_IMAX, resources.GetString("THR_ALT_IMAX.ToolTip")); // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; + this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip")); // // THR_ALT_I // resources.ApplyResources(this.THR_ALT_I, "THR_ALT_I"); this.THR_ALT_I.Name = "THR_ALT_I"; + this.toolTip1.SetToolTip(this.THR_ALT_I, resources.GetString("THR_ALT_I.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; + this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // THR_ALT_P // resources.ApplyResources(this.THR_ALT_P, "THR_ALT_P"); this.THR_ALT_P.Name = "THR_ALT_P"; + this.toolTip1.SetToolTip(this.THR_ALT_P, resources.GetString("THR_ALT_P.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; + this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // groupBox19 // + resources.ApplyResources(this.groupBox19, "groupBox19"); this.groupBox19.Controls.Add(this.HLD_LAT_IMAX); this.groupBox19.Controls.Add(this.label28); this.groupBox19.Controls.Add(this.HLD_LAT_I); this.groupBox19.Controls.Add(this.label30); this.groupBox19.Controls.Add(this.HLD_LAT_P); this.groupBox19.Controls.Add(this.label31); - resources.ApplyResources(this.groupBox19, "groupBox19"); this.groupBox19.Name = "groupBox19"; this.groupBox19.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox19, resources.GetString("groupBox19.ToolTip")); // // HLD_LAT_IMAX // resources.ApplyResources(this.HLD_LAT_IMAX, "HLD_LAT_IMAX"); this.HLD_LAT_IMAX.Name = "HLD_LAT_IMAX"; + this.toolTip1.SetToolTip(this.HLD_LAT_IMAX, resources.GetString("HLD_LAT_IMAX.ToolTip")); // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; + this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // HLD_LAT_I // resources.ApplyResources(this.HLD_LAT_I, "HLD_LAT_I"); this.HLD_LAT_I.Name = "HLD_LAT_I"; + this.toolTip1.SetToolTip(this.HLD_LAT_I, resources.GetString("HLD_LAT_I.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; + this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // HLD_LAT_P // resources.ApplyResources(this.HLD_LAT_P, "HLD_LAT_P"); this.HLD_LAT_P.Name = "HLD_LAT_P"; + this.toolTip1.SetToolTip(this.HLD_LAT_P, resources.GetString("HLD_LAT_P.ToolTip")); // // label31 // resources.ApplyResources(this.label31, "label31"); this.label31.Name = "label31"; + this.toolTip1.SetToolTip(this.label31, resources.GetString("label31.ToolTip")); // // groupBox20 // + resources.ApplyResources(this.groupBox20, "groupBox20"); this.groupBox20.Controls.Add(this.STB_YAW_IMAX); this.groupBox20.Controls.Add(this.label32); this.groupBox20.Controls.Add(this.STB_YAW_I); this.groupBox20.Controls.Add(this.label34); this.groupBox20.Controls.Add(this.STB_YAW_P); this.groupBox20.Controls.Add(this.label35); - resources.ApplyResources(this.groupBox20, "groupBox20"); this.groupBox20.Name = "groupBox20"; this.groupBox20.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox20, resources.GetString("groupBox20.ToolTip")); // // STB_YAW_IMAX // resources.ApplyResources(this.STB_YAW_IMAX, "STB_YAW_IMAX"); this.STB_YAW_IMAX.Name = "STB_YAW_IMAX"; + this.toolTip1.SetToolTip(this.STB_YAW_IMAX, resources.GetString("STB_YAW_IMAX.ToolTip")); // // label32 // resources.ApplyResources(this.label32, "label32"); this.label32.Name = "label32"; + this.toolTip1.SetToolTip(this.label32, resources.GetString("label32.ToolTip")); // // STB_YAW_I // resources.ApplyResources(this.STB_YAW_I, "STB_YAW_I"); this.STB_YAW_I.Name = "STB_YAW_I"; + this.toolTip1.SetToolTip(this.STB_YAW_I, resources.GetString("STB_YAW_I.ToolTip")); // // label34 // resources.ApplyResources(this.label34, "label34"); this.label34.Name = "label34"; + this.toolTip1.SetToolTip(this.label34, resources.GetString("label34.ToolTip")); // // STB_YAW_P // resources.ApplyResources(this.STB_YAW_P, "STB_YAW_P"); this.STB_YAW_P.Name = "STB_YAW_P"; + this.toolTip1.SetToolTip(this.STB_YAW_P, resources.GetString("STB_YAW_P.ToolTip")); // // label35 // resources.ApplyResources(this.label35, "label35"); this.label35.Name = "label35"; + this.toolTip1.SetToolTip(this.label35, resources.GetString("label35.ToolTip")); // // groupBox21 // + resources.ApplyResources(this.groupBox21, "groupBox21"); this.groupBox21.Controls.Add(this.STB_PIT_IMAX); this.groupBox21.Controls.Add(this.label36); this.groupBox21.Controls.Add(this.STB_PIT_I); this.groupBox21.Controls.Add(this.label41); this.groupBox21.Controls.Add(this.STB_PIT_P); this.groupBox21.Controls.Add(this.label42); - resources.ApplyResources(this.groupBox21, "groupBox21"); this.groupBox21.Name = "groupBox21"; this.groupBox21.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox21, resources.GetString("groupBox21.ToolTip")); // // STB_PIT_IMAX // resources.ApplyResources(this.STB_PIT_IMAX, "STB_PIT_IMAX"); this.STB_PIT_IMAX.Name = "STB_PIT_IMAX"; + this.toolTip1.SetToolTip(this.STB_PIT_IMAX, resources.GetString("STB_PIT_IMAX.ToolTip")); // // label36 // resources.ApplyResources(this.label36, "label36"); this.label36.Name = "label36"; + this.toolTip1.SetToolTip(this.label36, resources.GetString("label36.ToolTip")); // // STB_PIT_I // resources.ApplyResources(this.STB_PIT_I, "STB_PIT_I"); this.STB_PIT_I.Name = "STB_PIT_I"; + this.toolTip1.SetToolTip(this.STB_PIT_I, resources.GetString("STB_PIT_I.ToolTip")); // // label41 // resources.ApplyResources(this.label41, "label41"); this.label41.Name = "label41"; + this.toolTip1.SetToolTip(this.label41, resources.GetString("label41.ToolTip")); // // STB_PIT_P // resources.ApplyResources(this.STB_PIT_P, "STB_PIT_P"); this.STB_PIT_P.Name = "STB_PIT_P"; + this.toolTip1.SetToolTip(this.STB_PIT_P, resources.GetString("STB_PIT_P.ToolTip")); // // label42 // resources.ApplyResources(this.label42, "label42"); this.label42.Name = "label42"; + this.toolTip1.SetToolTip(this.label42, resources.GetString("label42.ToolTip")); // // groupBox22 // + resources.ApplyResources(this.groupBox22, "groupBox22"); this.groupBox22.Controls.Add(this.STB_RLL_IMAX); this.groupBox22.Controls.Add(this.label43); this.groupBox22.Controls.Add(this.STB_RLL_I); this.groupBox22.Controls.Add(this.label45); this.groupBox22.Controls.Add(this.STB_RLL_P); this.groupBox22.Controls.Add(this.label46); - resources.ApplyResources(this.groupBox22, "groupBox22"); this.groupBox22.Name = "groupBox22"; this.groupBox22.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox22, resources.GetString("groupBox22.ToolTip")); // // STB_RLL_IMAX // resources.ApplyResources(this.STB_RLL_IMAX, "STB_RLL_IMAX"); this.STB_RLL_IMAX.Name = "STB_RLL_IMAX"; + this.toolTip1.SetToolTip(this.STB_RLL_IMAX, resources.GetString("STB_RLL_IMAX.ToolTip")); // // label43 // resources.ApplyResources(this.label43, "label43"); this.label43.Name = "label43"; + this.toolTip1.SetToolTip(this.label43, resources.GetString("label43.ToolTip")); // // STB_RLL_I // resources.ApplyResources(this.STB_RLL_I, "STB_RLL_I"); this.STB_RLL_I.Name = "STB_RLL_I"; + this.toolTip1.SetToolTip(this.STB_RLL_I, resources.GetString("STB_RLL_I.ToolTip")); // // label45 // resources.ApplyResources(this.label45, "label45"); this.label45.Name = "label45"; + this.toolTip1.SetToolTip(this.label45, resources.GetString("label45.ToolTip")); // // STB_RLL_P // resources.ApplyResources(this.STB_RLL_P, "STB_RLL_P"); this.STB_RLL_P.Name = "STB_RLL_P"; + this.toolTip1.SetToolTip(this.STB_RLL_P, resources.GetString("STB_RLL_P.ToolTip")); // // label46 // resources.ApplyResources(this.label46, "label46"); this.label46.Name = "label46"; + this.toolTip1.SetToolTip(this.label46, resources.GetString("label46.ToolTip")); // // groupBox23 // + resources.ApplyResources(this.groupBox23, "groupBox23"); this.groupBox23.Controls.Add(this.RATE_YAW_IMAX); this.groupBox23.Controls.Add(this.label47); this.groupBox23.Controls.Add(this.RATE_YAW_I); this.groupBox23.Controls.Add(this.label77); this.groupBox23.Controls.Add(this.RATE_YAW_P); this.groupBox23.Controls.Add(this.label82); - resources.ApplyResources(this.groupBox23, "groupBox23"); this.groupBox23.Name = "groupBox23"; this.groupBox23.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox23, resources.GetString("groupBox23.ToolTip")); // // RATE_YAW_IMAX // resources.ApplyResources(this.RATE_YAW_IMAX, "RATE_YAW_IMAX"); this.RATE_YAW_IMAX.Name = "RATE_YAW_IMAX"; + this.toolTip1.SetToolTip(this.RATE_YAW_IMAX, resources.GetString("RATE_YAW_IMAX.ToolTip")); // // label47 // resources.ApplyResources(this.label47, "label47"); this.label47.Name = "label47"; + this.toolTip1.SetToolTip(this.label47, resources.GetString("label47.ToolTip")); // // RATE_YAW_I // resources.ApplyResources(this.RATE_YAW_I, "RATE_YAW_I"); this.RATE_YAW_I.Name = "RATE_YAW_I"; + this.toolTip1.SetToolTip(this.RATE_YAW_I, resources.GetString("RATE_YAW_I.ToolTip")); // // label77 // resources.ApplyResources(this.label77, "label77"); this.label77.Name = "label77"; + this.toolTip1.SetToolTip(this.label77, resources.GetString("label77.ToolTip")); // // RATE_YAW_P // resources.ApplyResources(this.RATE_YAW_P, "RATE_YAW_P"); this.RATE_YAW_P.Name = "RATE_YAW_P"; + this.toolTip1.SetToolTip(this.RATE_YAW_P, resources.GetString("RATE_YAW_P.ToolTip")); // // label82 // resources.ApplyResources(this.label82, "label82"); this.label82.Name = "label82"; + this.toolTip1.SetToolTip(this.label82, resources.GetString("label82.ToolTip")); // // groupBox24 // + resources.ApplyResources(this.groupBox24, "groupBox24"); this.groupBox24.Controls.Add(this.RATE_PIT_IMAX); this.groupBox24.Controls.Add(this.label84); this.groupBox24.Controls.Add(this.RATE_PIT_I); this.groupBox24.Controls.Add(this.label86); this.groupBox24.Controls.Add(this.RATE_PIT_P); this.groupBox24.Controls.Add(this.label87); - resources.ApplyResources(this.groupBox24, "groupBox24"); this.groupBox24.Name = "groupBox24"; this.groupBox24.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox24, resources.GetString("groupBox24.ToolTip")); // // RATE_PIT_IMAX // resources.ApplyResources(this.RATE_PIT_IMAX, "RATE_PIT_IMAX"); this.RATE_PIT_IMAX.Name = "RATE_PIT_IMAX"; + this.toolTip1.SetToolTip(this.RATE_PIT_IMAX, resources.GetString("RATE_PIT_IMAX.ToolTip")); // // label84 // resources.ApplyResources(this.label84, "label84"); this.label84.Name = "label84"; + this.toolTip1.SetToolTip(this.label84, resources.GetString("label84.ToolTip")); // // RATE_PIT_I // resources.ApplyResources(this.RATE_PIT_I, "RATE_PIT_I"); this.RATE_PIT_I.Name = "RATE_PIT_I"; + this.toolTip1.SetToolTip(this.RATE_PIT_I, resources.GetString("RATE_PIT_I.ToolTip")); // // label86 // resources.ApplyResources(this.label86, "label86"); this.label86.Name = "label86"; + this.toolTip1.SetToolTip(this.label86, resources.GetString("label86.ToolTip")); // // RATE_PIT_P // resources.ApplyResources(this.RATE_PIT_P, "RATE_PIT_P"); this.RATE_PIT_P.Name = "RATE_PIT_P"; + this.toolTip1.SetToolTip(this.RATE_PIT_P, resources.GetString("RATE_PIT_P.ToolTip")); // // label87 // resources.ApplyResources(this.label87, "label87"); this.label87.Name = "label87"; + this.toolTip1.SetToolTip(this.label87, resources.GetString("label87.ToolTip")); // // groupBox25 // + resources.ApplyResources(this.groupBox25, "groupBox25"); this.groupBox25.Controls.Add(this.RATE_RLL_IMAX); this.groupBox25.Controls.Add(this.label88); this.groupBox25.Controls.Add(this.RATE_RLL_I); this.groupBox25.Controls.Add(this.label90); this.groupBox25.Controls.Add(this.RATE_RLL_P); this.groupBox25.Controls.Add(this.label91); - resources.ApplyResources(this.groupBox25, "groupBox25"); this.groupBox25.Name = "groupBox25"; this.groupBox25.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox25, resources.GetString("groupBox25.ToolTip")); // // RATE_RLL_IMAX // resources.ApplyResources(this.RATE_RLL_IMAX, "RATE_RLL_IMAX"); this.RATE_RLL_IMAX.Name = "RATE_RLL_IMAX"; + this.toolTip1.SetToolTip(this.RATE_RLL_IMAX, resources.GetString("RATE_RLL_IMAX.ToolTip")); // // label88 // resources.ApplyResources(this.label88, "label88"); this.label88.Name = "label88"; + this.toolTip1.SetToolTip(this.label88, resources.GetString("label88.ToolTip")); // // RATE_RLL_I // resources.ApplyResources(this.RATE_RLL_I, "RATE_RLL_I"); this.RATE_RLL_I.Name = "RATE_RLL_I"; + this.toolTip1.SetToolTip(this.RATE_RLL_I, resources.GetString("RATE_RLL_I.ToolTip")); // // label90 // resources.ApplyResources(this.label90, "label90"); this.label90.Name = "label90"; + this.toolTip1.SetToolTip(this.label90, resources.GetString("label90.ToolTip")); // // RATE_RLL_P // resources.ApplyResources(this.RATE_RLL_P, "RATE_RLL_P"); this.RATE_RLL_P.Name = "RATE_RLL_P"; + this.toolTip1.SetToolTip(this.RATE_RLL_P, resources.GetString("RATE_RLL_P.ToolTip")); // // label91 // resources.ApplyResources(this.label91, "label91"); this.label91.Name = "label91"; + this.toolTip1.SetToolTip(this.label91, resources.GetString("label91.ToolTip")); // // TabPlanner // + resources.ApplyResources(this.TabPlanner, "TabPlanner"); this.TabPlanner.Controls.Add(this.label26); this.TabPlanner.Controls.Add(this.CMB_videoresolutions); this.TabPlanner.Controls.Add(this.label12); @@ -1568,25 +1938,28 @@ this.TabPlanner.Controls.Add(this.BUT_Joystick); this.TabPlanner.Controls.Add(this.BUT_videostop); this.TabPlanner.Controls.Add(this.BUT_videostart); - resources.ApplyResources(this.TabPlanner, "TabPlanner"); this.TabPlanner.Name = "TabPlanner"; + this.toolTip1.SetToolTip(this.TabPlanner, resources.GetString("TabPlanner.ToolTip")); // // label26 // resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; + this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // CMB_videoresolutions // + resources.ApplyResources(this.CMB_videoresolutions, "CMB_videoresolutions"); this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videoresolutions.FormattingEnabled = true; - resources.ApplyResources(this.CMB_videoresolutions, "CMB_videoresolutions"); this.CMB_videoresolutions.Name = "CMB_videoresolutions"; + this.toolTip1.SetToolTip(this.CMB_videoresolutions, resources.GetString("CMB_videoresolutions.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; + this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // CHK_GDIPlus // @@ -1600,11 +1973,13 @@ // resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; + this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // CHK_loadwponconnect // resources.ApplyResources(this.CHK_loadwponconnect, "CHK_loadwponconnect"); this.CHK_loadwponconnect.Name = "CHK_loadwponconnect"; + this.toolTip1.SetToolTip(this.CHK_loadwponconnect, resources.GetString("CHK_loadwponconnect.ToolTip")); this.CHK_loadwponconnect.UseVisualStyleBackColor = true; this.CHK_loadwponconnect.CheckedChanged += new System.EventHandler(this.CHK_loadwponconnect_CheckedChanged); // @@ -1612,15 +1987,16 @@ // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; + this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // NUM_tracklength // + resources.ApplyResources(this.NUM_tracklength, "NUM_tracklength"); this.NUM_tracklength.Increment = new decimal(new int[] { 100, 0, 0, 0}); - resources.ApplyResources(this.NUM_tracklength, "NUM_tracklength"); this.NUM_tracklength.Maximum = new decimal(new int[] { 2000, 0, @@ -1644,6 +2020,7 @@ // resources.ApplyResources(this.CHK_speechaltwarning, "CHK_speechaltwarning"); this.CHK_speechaltwarning.Name = "CHK_speechaltwarning"; + this.toolTip1.SetToolTip(this.CHK_speechaltwarning, resources.GetString("CHK_speechaltwarning.ToolTip")); this.CHK_speechaltwarning.UseVisualStyleBackColor = true; this.CHK_speechaltwarning.CheckedChanged += new System.EventHandler(this.CHK_speechaltwarning_CheckedChanged); // @@ -1651,13 +2028,15 @@ // resources.ApplyResources(this.label108, "label108"); this.label108.Name = "label108"; + this.toolTip1.SetToolTip(this.label108, resources.GetString("label108.ToolTip")); // // CHK_resetapmonconnect // + resources.ApplyResources(this.CHK_resetapmonconnect, "CHK_resetapmonconnect"); this.CHK_resetapmonconnect.Checked = true; this.CHK_resetapmonconnect.CheckState = System.Windows.Forms.CheckState.Checked; - resources.ApplyResources(this.CHK_resetapmonconnect, "CHK_resetapmonconnect"); this.CHK_resetapmonconnect.Name = "CHK_resetapmonconnect"; + this.toolTip1.SetToolTip(this.CHK_resetapmonconnect, resources.GetString("CHK_resetapmonconnect.ToolTip")); this.CHK_resetapmonconnect.UseVisualStyleBackColor = true; this.CHK_resetapmonconnect.CheckedChanged += new System.EventHandler(this.CHK_resetapmonconnect_CheckedChanged); // @@ -1665,6 +2044,7 @@ // resources.ApplyResources(this.CHK_mavdebug, "CHK_mavdebug"); this.CHK_mavdebug.Name = "CHK_mavdebug"; + this.toolTip1.SetToolTip(this.CHK_mavdebug, resources.GetString("CHK_mavdebug.ToolTip")); this.CHK_mavdebug.UseVisualStyleBackColor = true; this.CHK_mavdebug.CheckedChanged += new System.EventHandler(this.CHK_mavdebug_CheckedChanged); // @@ -1672,9 +2052,11 @@ // resources.ApplyResources(this.label107, "label107"); this.label107.Name = "label107"; + this.toolTip1.SetToolTip(this.label107, resources.GetString("label107.ToolTip")); // // CMB_raterc // + resources.ApplyResources(this.CMB_raterc, "CMB_raterc"); this.CMB_raterc.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_raterc.FormattingEnabled = true; this.CMB_raterc.Items.AddRange(new object[] { @@ -1682,32 +2064,37 @@ resources.GetString("CMB_raterc.Items1"), resources.GetString("CMB_raterc.Items2"), resources.GetString("CMB_raterc.Items3")}); - resources.ApplyResources(this.CMB_raterc, "CMB_raterc"); this.CMB_raterc.Name = "CMB_raterc"; + this.toolTip1.SetToolTip(this.CMB_raterc, resources.GetString("CMB_raterc.ToolTip")); this.CMB_raterc.SelectedIndexChanged += new System.EventHandler(this.CMB_raterc_SelectedIndexChanged); // // label104 // resources.ApplyResources(this.label104, "label104"); this.label104.Name = "label104"; + this.toolTip1.SetToolTip(this.label104, resources.GetString("label104.ToolTip")); // // label103 // resources.ApplyResources(this.label103, "label103"); this.label103.Name = "label103"; + this.toolTip1.SetToolTip(this.label103, resources.GetString("label103.ToolTip")); // // label102 // resources.ApplyResources(this.label102, "label102"); this.label102.Name = "label102"; + this.toolTip1.SetToolTip(this.label102, resources.GetString("label102.ToolTip")); // // label101 // resources.ApplyResources(this.label101, "label101"); this.label101.Name = "label101"; + this.toolTip1.SetToolTip(this.label101, resources.GetString("label101.ToolTip")); // // CMB_ratestatus // + resources.ApplyResources(this.CMB_ratestatus, "CMB_ratestatus"); this.CMB_ratestatus.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_ratestatus.FormattingEnabled = true; this.CMB_ratestatus.Items.AddRange(new object[] { @@ -1715,12 +2102,13 @@ resources.GetString("CMB_ratestatus.Items1"), resources.GetString("CMB_ratestatus.Items2"), resources.GetString("CMB_ratestatus.Items3")}); - resources.ApplyResources(this.CMB_ratestatus, "CMB_ratestatus"); this.CMB_ratestatus.Name = "CMB_ratestatus"; + this.toolTip1.SetToolTip(this.CMB_ratestatus, resources.GetString("CMB_ratestatus.ToolTip")); this.CMB_ratestatus.SelectedIndexChanged += new System.EventHandler(this.CMB_ratestatus_SelectedIndexChanged); // // CMB_rateposition // + resources.ApplyResources(this.CMB_rateposition, "CMB_rateposition"); this.CMB_rateposition.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_rateposition.FormattingEnabled = true; this.CMB_rateposition.Items.AddRange(new object[] { @@ -1728,12 +2116,13 @@ resources.GetString("CMB_rateposition.Items1"), resources.GetString("CMB_rateposition.Items2"), resources.GetString("CMB_rateposition.Items3")}); - resources.ApplyResources(this.CMB_rateposition, "CMB_rateposition"); this.CMB_rateposition.Name = "CMB_rateposition"; + this.toolTip1.SetToolTip(this.CMB_rateposition, resources.GetString("CMB_rateposition.ToolTip")); this.CMB_rateposition.SelectedIndexChanged += new System.EventHandler(this.CMB_rateposition_SelectedIndexChanged); // // CMB_rateattitude // + resources.ApplyResources(this.CMB_rateattitude, "CMB_rateattitude"); this.CMB_rateattitude.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_rateattitude.FormattingEnabled = true; this.CMB_rateattitude.Items.AddRange(new object[] { @@ -1741,55 +2130,63 @@ resources.GetString("CMB_rateattitude.Items1"), resources.GetString("CMB_rateattitude.Items2"), resources.GetString("CMB_rateattitude.Items3")}); - resources.ApplyResources(this.CMB_rateattitude, "CMB_rateattitude"); this.CMB_rateattitude.Name = "CMB_rateattitude"; + this.toolTip1.SetToolTip(this.CMB_rateattitude, resources.GetString("CMB_rateattitude.ToolTip")); this.CMB_rateattitude.SelectedIndexChanged += new System.EventHandler(this.CMB_rateattitude_SelectedIndexChanged); // // label99 // resources.ApplyResources(this.label99, "label99"); this.label99.Name = "label99"; + this.toolTip1.SetToolTip(this.label99, resources.GetString("label99.ToolTip")); // // label98 // resources.ApplyResources(this.label98, "label98"); this.label98.Name = "label98"; + this.toolTip1.SetToolTip(this.label98, resources.GetString("label98.ToolTip")); // // label97 // resources.ApplyResources(this.label97, "label97"); this.label97.Name = "label97"; + this.toolTip1.SetToolTip(this.label97, resources.GetString("label97.ToolTip")); // // CMB_speedunits // + resources.ApplyResources(this.CMB_speedunits, "CMB_speedunits"); this.CMB_speedunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_speedunits.FormattingEnabled = true; - resources.ApplyResources(this.CMB_speedunits, "CMB_speedunits"); this.CMB_speedunits.Name = "CMB_speedunits"; + this.toolTip1.SetToolTip(this.CMB_speedunits, resources.GetString("CMB_speedunits.ToolTip")); this.CMB_speedunits.SelectedIndexChanged += new System.EventHandler(this.CMB_speedunits_SelectedIndexChanged); // // CMB_distunits // + resources.ApplyResources(this.CMB_distunits, "CMB_distunits"); this.CMB_distunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_distunits.FormattingEnabled = true; - resources.ApplyResources(this.CMB_distunits, "CMB_distunits"); this.CMB_distunits.Name = "CMB_distunits"; + this.toolTip1.SetToolTip(this.CMB_distunits, resources.GetString("CMB_distunits.ToolTip")); this.CMB_distunits.SelectedIndexChanged += new System.EventHandler(this.CMB_distunits_SelectedIndexChanged); // // label96 // resources.ApplyResources(this.label96, "label96"); this.label96.Name = "label96"; + this.toolTip1.SetToolTip(this.label96, resources.GetString("label96.ToolTip")); // // label95 // resources.ApplyResources(this.label95, "label95"); this.label95.Name = "label95"; + this.toolTip1.SetToolTip(this.label95, resources.GetString("label95.ToolTip")); // // CHK_speechbattery // resources.ApplyResources(this.CHK_speechbattery, "CHK_speechbattery"); this.CHK_speechbattery.Name = "CHK_speechbattery"; + this.toolTip1.SetToolTip(this.CHK_speechbattery, resources.GetString("CHK_speechbattery.ToolTip")); this.CHK_speechbattery.UseVisualStyleBackColor = true; this.CHK_speechbattery.CheckedChanged += new System.EventHandler(this.CHK_speechbattery_CheckedChanged); // @@ -1797,6 +2194,7 @@ // resources.ApplyResources(this.CHK_speechcustom, "CHK_speechcustom"); this.CHK_speechcustom.Name = "CHK_speechcustom"; + this.toolTip1.SetToolTip(this.CHK_speechcustom, resources.GetString("CHK_speechcustom.ToolTip")); this.CHK_speechcustom.UseVisualStyleBackColor = true; this.CHK_speechcustom.CheckedChanged += new System.EventHandler(this.CHK_speechcustom_CheckedChanged); // @@ -1804,6 +2202,7 @@ // resources.ApplyResources(this.CHK_speechmode, "CHK_speechmode"); this.CHK_speechmode.Name = "CHK_speechmode"; + this.toolTip1.SetToolTip(this.CHK_speechmode, resources.GetString("CHK_speechmode.ToolTip")); this.CHK_speechmode.UseVisualStyleBackColor = true; this.CHK_speechmode.CheckedChanged += new System.EventHandler(this.CHK_speechmode_CheckedChanged); // @@ -1811,6 +2210,7 @@ // resources.ApplyResources(this.CHK_speechwaypoint, "CHK_speechwaypoint"); this.CHK_speechwaypoint.Name = "CHK_speechwaypoint"; + this.toolTip1.SetToolTip(this.CHK_speechwaypoint, resources.GetString("CHK_speechwaypoint.ToolTip")); this.CHK_speechwaypoint.UseVisualStyleBackColor = true; this.CHK_speechwaypoint.CheckedChanged += new System.EventHandler(this.CHK_speechwaypoint_CheckedChanged); // @@ -1818,42 +2218,48 @@ // resources.ApplyResources(this.label94, "label94"); this.label94.Name = "label94"; + this.toolTip1.SetToolTip(this.label94, resources.GetString("label94.ToolTip")); // // CMB_osdcolor // + resources.ApplyResources(this.CMB_osdcolor, "CMB_osdcolor"); this.CMB_osdcolor.DrawMode = System.Windows.Forms.DrawMode.OwnerDrawFixed; this.CMB_osdcolor.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_osdcolor.FormattingEnabled = true; - resources.ApplyResources(this.CMB_osdcolor, "CMB_osdcolor"); this.CMB_osdcolor.Name = "CMB_osdcolor"; + this.toolTip1.SetToolTip(this.CMB_osdcolor, resources.GetString("CMB_osdcolor.ToolTip")); this.CMB_osdcolor.DrawItem += new System.Windows.Forms.DrawItemEventHandler(this.CMB_osdcolor_DrawItem); this.CMB_osdcolor.SelectedIndexChanged += new System.EventHandler(this.CMB_osdcolor_SelectedIndexChanged); // // CMB_language // + resources.ApplyResources(this.CMB_language, "CMB_language"); this.CMB_language.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_language.FormattingEnabled = true; - resources.ApplyResources(this.CMB_language, "CMB_language"); this.CMB_language.Name = "CMB_language"; + this.toolTip1.SetToolTip(this.CMB_language, resources.GetString("CMB_language.ToolTip")); // // label93 // resources.ApplyResources(this.label93, "label93"); this.label93.Name = "label93"; + this.toolTip1.SetToolTip(this.label93, resources.GetString("label93.ToolTip")); // // CHK_enablespeech // resources.ApplyResources(this.CHK_enablespeech, "CHK_enablespeech"); this.CHK_enablespeech.Name = "CHK_enablespeech"; + this.toolTip1.SetToolTip(this.CHK_enablespeech, resources.GetString("CHK_enablespeech.ToolTip")); this.CHK_enablespeech.UseVisualStyleBackColor = true; this.CHK_enablespeech.CheckedChanged += new System.EventHandler(this.CHK_enablespeech_CheckedChanged); // // CHK_hudshow // + resources.ApplyResources(this.CHK_hudshow, "CHK_hudshow"); this.CHK_hudshow.Checked = true; this.CHK_hudshow.CheckState = System.Windows.Forms.CheckState.Checked; - resources.ApplyResources(this.CHK_hudshow, "CHK_hudshow"); this.CHK_hudshow.Name = "CHK_hudshow"; + this.toolTip1.SetToolTip(this.CHK_hudshow, resources.GetString("CHK_hudshow.ToolTip")); this.CHK_hudshow.UseVisualStyleBackColor = true; this.CHK_hudshow.CheckedChanged += new System.EventHandler(this.CHK_hudshow_CheckedChanged); // @@ -1861,13 +2267,15 @@ // resources.ApplyResources(this.label92, "label92"); this.label92.Name = "label92"; + this.toolTip1.SetToolTip(this.label92, resources.GetString("label92.ToolTip")); // // CMB_videosources // + resources.ApplyResources(this.CMB_videosources, "CMB_videosources"); this.CMB_videosources.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videosources.FormattingEnabled = true; - resources.ApplyResources(this.CMB_videosources, "CMB_videosources"); this.CMB_videosources.Name = "CMB_videosources"; + this.toolTip1.SetToolTip(this.CMB_videosources, resources.GetString("CMB_videosources.ToolTip")); this.CMB_videosources.SelectedIndexChanged += new System.EventHandler(this.CMB_videosources_SelectedIndexChanged); this.CMB_videosources.MouseClick += new System.Windows.Forms.MouseEventHandler(this.CMB_videosources_MouseClick); // @@ -1875,6 +2283,7 @@ // resources.ApplyResources(this.BUT_Joystick, "BUT_Joystick"); this.BUT_Joystick.Name = "BUT_Joystick"; + this.toolTip1.SetToolTip(this.BUT_Joystick, resources.GetString("BUT_Joystick.ToolTip")); this.BUT_Joystick.UseVisualStyleBackColor = true; this.BUT_Joystick.Click += new System.EventHandler(this.BUT_Joystick_Click); // @@ -1882,6 +2291,7 @@ // resources.ApplyResources(this.BUT_videostop, "BUT_videostop"); this.BUT_videostop.Name = "BUT_videostop"; + this.toolTip1.SetToolTip(this.BUT_videostop, resources.GetString("BUT_videostop.ToolTip")); this.BUT_videostop.UseVisualStyleBackColor = true; this.BUT_videostop.Click += new System.EventHandler(this.BUT_videostop_Click); // @@ -1889,6 +2299,7 @@ // resources.ApplyResources(this.BUT_videostart, "BUT_videostart"); this.BUT_videostart.Name = "BUT_videostart"; + this.toolTip1.SetToolTip(this.BUT_videostart, resources.GetString("BUT_videostart.ToolTip")); this.BUT_videostart.UseVisualStyleBackColor = true; this.BUT_videostart.Click += new System.EventHandler(this.BUT_videostart_Click); // @@ -1896,12 +2307,14 @@ // resources.ApplyResources(this.TabSetup, "TabSetup"); this.TabSetup.Name = "TabSetup"; + this.toolTip1.SetToolTip(this.TabSetup, resources.GetString("TabSetup.ToolTip")); this.TabSetup.UseVisualStyleBackColor = true; // // label109 // resources.ApplyResources(this.label109, "label109"); this.label109.Name = "label109"; + this.toolTip1.SetToolTip(this.label109, resources.GetString("label109.ToolTip")); // // BUT_rerequestparams // @@ -1939,93 +2352,10 @@ // resources.ApplyResources(this.BUT_compare, "BUT_compare"); this.BUT_compare.Name = "BUT_compare"; + this.toolTip1.SetToolTip(this.BUT_compare, resources.GetString("BUT_compare.ToolTip")); this.BUT_compare.UseVisualStyleBackColor = true; this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click); // - // groupBox17 - // - this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX); - this.groupBox17.Controls.Add(this.label27); - this.groupBox17.Controls.Add(this.ACRO_PIT_I); - this.groupBox17.Controls.Add(this.label29); - this.groupBox17.Controls.Add(this.ACRO_PIT_P); - this.groupBox17.Controls.Add(this.label33); - resources.ApplyResources(this.groupBox17, "groupBox17"); - this.groupBox17.Name = "groupBox17"; - this.groupBox17.TabStop = false; - // - // ACRO_PIT_IMAX - // - resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX"); - this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX"; - // - // label27 - // - resources.ApplyResources(this.label27, "label27"); - this.label27.Name = "label27"; - // - // ACRO_PIT_I - // - resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I"); - this.ACRO_PIT_I.Name = "ACRO_PIT_I"; - // - // label29 - // - resources.ApplyResources(this.label29, "label29"); - this.label29.Name = "label29"; - // - // ACRO_PIT_P - // - resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P"); - this.ACRO_PIT_P.Name = "ACRO_PIT_P"; - // - // label33 - // - resources.ApplyResources(this.label33, "label33"); - this.label33.Name = "label33"; - // - // groupBox18 - // - this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX); - this.groupBox18.Controls.Add(this.label40); - this.groupBox18.Controls.Add(this.ACRO_RLL_I); - this.groupBox18.Controls.Add(this.label44); - this.groupBox18.Controls.Add(this.ACRO_RLL_P); - this.groupBox18.Controls.Add(this.label48); - resources.ApplyResources(this.groupBox18, "groupBox18"); - this.groupBox18.Name = "groupBox18"; - this.groupBox18.TabStop = false; - // - // ACRO_RLL_IMAX - // - resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX"); - this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX"; - // - // label40 - // - resources.ApplyResources(this.label40, "label40"); - this.label40.Name = "label40"; - // - // ACRO_RLL_I - // - resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I"); - this.ACRO_RLL_I.Name = "ACRO_RLL_I"; - // - // label44 - // - resources.ApplyResources(this.label44, "label44"); - this.label44.Name = "label44"; - // - // ACRO_RLL_P - // - resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P"); - this.ACRO_RLL_P.Name = "ACRO_RLL_P"; - // - // label48 - // - resources.ApplyResources(this.label48, "label48"); - this.label48.Name = "label48"; - // // Configuration // resources.ApplyResources(this, "$this"); @@ -2039,39 +2369,125 @@ this.Controls.Add(this.BUT_load); this.Controls.Add(this.Params); this.Name = "Configuration"; + this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.Load += new System.EventHandler(this.Configuration_Load); ((System.ComponentModel.ISupportInitialize)(this.Params)).EndInit(); this.ConfigTabs.ResumeLayout(false); this.TabAPM2.ResumeLayout(false); this.groupBox3.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).EndInit(); this.groupBox1.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).EndInit(); this.groupBox2.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).EndInit(); this.groupBox15.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).EndInit(); this.groupBox16.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).EndInit(); this.groupBox14.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).EndInit(); this.groupBox13.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).EndInit(); this.groupBox12.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).EndInit(); this.groupBox11.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).EndInit(); this.groupBox10.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).EndInit(); this.groupBox9.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).EndInit(); this.groupBox8.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).EndInit(); this.TabAC2.ResumeLayout(false); this.TabAC2.PerformLayout(); + this.groupBox17.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_P)).EndInit(); this.groupBox5.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).EndInit(); + this.groupBox18.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_P)).EndInit(); this.groupBox4.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).EndInit(); this.groupBox6.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD1)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRACK_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRACK_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.XTRACK_P)).EndInit(); this.groupBox7.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).EndInit(); this.groupBox19.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).EndInit(); this.groupBox20.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).EndInit(); this.groupBox21.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).EndInit(); this.groupBox22.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).EndInit(); this.groupBox23.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).EndInit(); this.groupBox24.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).EndInit(); this.groupBox25.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).EndInit(); this.TabPlanner.ResumeLayout(false); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit(); - this.groupBox17.ResumeLayout(false); - this.groupBox18.ResumeLayout(false); this.ResumeLayout(false); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx index c5e12aff50..7b9725cee3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx @@ -117,6313 +117,7051 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Top, Bottom, Left - - - - True - - - Command - - - 150 - - - True - - - Value - - - 80 - - - True - - - Default - - - False - - - mavScale - - - False - - - True - - - RawValue - - - False - - - - 3, 3 - - - 150 - - - 269, 409 - - - 58 - - - Params - - - System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - Top, Bottom, Left, Right - - - 111, 82 - - - 78, 20 - - - 11 - THR_FS_VALUE - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 0 - - - NoControl - - - 6, 86 - - - 50, 13 - - - 12 - - - FS Value - - - label5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - THR_MAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 2 - - - NoControl - - - 6, 63 - - - 27, 13 - - - 13 - - - Max - - - label6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - THR_MIN - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 4 - - - NoControl - - - 6, 40 - - - 24, 13 - - - 14 - - - Min - - - label7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - TRIM_THROTTLE - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 6 - - - NoControl - - - 6, 17 - - - 36, 13 - - - 15 - - - Cruise - - - label8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 7 - - - 405, 217 - - - 195, 108 - - - 0 - - - Throttle 0-100% - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 0 - - - 111, 82 - - - 78, 20 - - - 0 - - - ARSPD_RATIO - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 0 - - - NoControl - - - 6, 87 - - - 32, 13 - - - 1 - - - Ratio - - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 1 - - - 111, 59 - - - 78, 20 - - - 2 - - - ARSPD_FBW_MAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 2 - - - NoControl - - - 6, 59 - - - 53, 13 - - - 3 - - - FBW max - - - label2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 3 - - - 111, 36 - - - 78, 20 - - - 4 - - - ARSPD_FBW_MIN - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 4 - - - NoControl - - - 6, 40 - - - 50, 13 - - - 5 - - - FBW min - - - label3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - TRIM_ARSPD_CM - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 6 - - - NoControl - - - 6, 17 - - - 64, 13 - - - 6 - - - Cruise - - - label4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 7 - - - 406, 325 - - - 195, 108 - - - 1 - - - Airspeed m/s - - - groupBox1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - LIM_PITCH_MIN - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 0 - - - NoControl - - - 6, 63 - - - 51, 13 - - - 10 - - - Pitch Min - - - label39 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 1 - - - 111, 36 - - - 78, 20 - - - 7 - - - LIM_PITCH_MAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 2 - - - NoControl - - - 6, 40 - - - 54, 13 - - - 11 - - - Pitch Max - - - label38 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 3 - - - 111, 13 - - - 78, 20 - - - 5 - - - LIM_ROLL_CD - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 4 - - - NoControl - - - 6, 17 - - - 55, 13 - - - 12 - - - Bank Max - - - label37 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 5 - - - 205, 325 - - - 195, 108 - - - 2 - - - Navigation Angles - - - groupBox2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 2 - - - 111, 36 - - - 78, 20 - - - 7 - - - XTRK_ANGLE_CD - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox15 - - - 0 - - - NoControl - - - 6, 40 - - - 61, 13 - - - 8 - - - Entry Angle - - - label79 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox15 - - - 1 - - - 111, 13 - - - 78, 20 - - - 5 - - - XTRK_GAIN_SC - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox15 - - - 2 - - - NoControl - - - 6, 17 - - - 52, 13 - - - 9 - - - Gain (cm) - - - label80 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox15 - - - 3 - - - 4, 325 - - - 195, 108 - - - 3 - - - Xtrack Pids - - - groupBox15 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 3 - - - 111, 13 - - - 78, 20 - - - 13 - - - KFF_PTCH2THR - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox16 - - - 0 - - - NoControl - - - 6, 17 - - - 36, 13 - - - 14 - - - P to T - - - label83 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox16 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - KFF_RDDRMIX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox16 - - - 2 - - - NoControl - - - 6, 63 - - - 61, 13 - - - 15 - - - Rudder Mix - - - label78 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox16 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - KFF_PTCHCOMP - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox16 - - - 4 - - - NoControl - - - 6, 40 - - - 61, 13 - - - 16 - - - Pitch Comp - - - label81 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox16 - - - 5 - - - 205, 217 - - - 195, 108 - - - 4 - - - Other Mix's - - - groupBox16 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 4 - - - 111, 82 - - - 78, 20 - - - 11 - - - ENRGY2THR_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 12 - - - INT_MAX - - - label73 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - ENRGY2THR_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 13 - - - D - - - label74 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - ENRGY2THR_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label75 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - ENRGY2THR_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 15 - - - P - - - label76 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox14 - - - 7 - - - 4, 217 - - - 195, 108 - - - 5 - - - Energy/Alt Pid - - - groupBox14 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 5 - - - 111, 82 - - - 78, 20 - - - 0 - - - ALT2PTCH_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 1 - - - INT_MAX - - - label69 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 1 - - - 111, 59 - - - 78, 20 - - - 2 - - - ALT2PTCH_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 3 - - - D - - - label70 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 3 - - - 111, 36 - - - 78, 20 - - - 4 - - - ALT2PTCH_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label71 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 5 - - - 111, 13 - - - 78, 20 - - - 6 - - - ALT2PTCH_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 7 - - - P - - - label72 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox13 - - - 7 - - - 406, 109 - - - 195, 108 - - - 6 - - - Nav Pitch Alt Pid - - - groupBox13 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 6 - - - 111, 82 - - - 78, 20 - - - 0 - - - ARSP2PTCH_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 1 - - - INT_MAX - - - label65 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 1 - - - 111, 59 - - - 78, 20 - - - 2 - - - ARSP2PTCH_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 3 - - - D - - - label66 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 3 - - - 111, 36 - - - 78, 20 - - - 4 - - - ARSP2PTCH_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label67 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 5 - - - 111, 13 - - - 78, 20 - - - 6 - - - ARSP2PTCH_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 7 - - - P - - - label68 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 7 - - - 205, 109 - - - 195, 108 - - - 7 - - - Nav Pitch AS Pid - - - groupBox12 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 7 - - - 111, 82 - - - 78, 20 - - - 11 - - - HDNG2RLL_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 12 - - - INT_MAX - - - label61 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - HDNG2RLL_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 13 - - - D - - - label62 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - HDNG2RLL_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label63 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - HDNG2RLL_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 15 - - - P - - - label64 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 7 - - - 4, 109 - - - 195, 108 - - - 8 - - - Nav Roll Pid - - - groupBox11 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 8 - - - 111, 82 - - - 78, 20 - - - 11 - - - YW2SRV_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 12 - - - INT_MAX - - - label57 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - YW2SRV_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 13 - - - D - - - label58 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - YW2SRV_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label59 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - YW2SRV_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 15 - - - P - - - label60 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 7 - - - 406, 1 - - - 195, 108 - - - 9 - - - Servo Yaw Pid - - - groupBox10 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 9 - - - 111, 82 - - - 78, 20 - - - 11 - - - PTCH2SRV_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 12 - - - INT_MAX - - - label53 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - PTCH2SRV_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 13 - - - D - - - label54 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - PTCH2SRV_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label55 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - PTCH2SRV_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 15 - - - P - - - label56 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox9 - - - 7 - - - 205, 1 - - - 195, 108 - - - 10 - - - Servo Pitch Pid - - - groupBox9 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 10 - - - 111, 82 - - - 78, 20 - - - 11 - - - RLL2SRV_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 0 - - - NoControl - - - 6, 86 - - - 54, 13 - - - 12 - - - INT_MAX - - - label49 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 1 - - - 111, 59 - - - 78, 20 - - - 9 - - - RLL2SRV_D - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 2 - - - NoControl - - - 6, 63 - - - 15, 13 - - - 13 - - - D - - - label50 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 3 - - - 111, 36 - - - 78, 20 - - - 7 - - - RLL2SRV_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label51 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 5 - - - 111, 13 - - - 78, 20 - - - 5 - - - RLL2SRV_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 6 - - - NoControl - - - 6, 17 - - - 14, 13 - - - 15 - - - P - - - label52 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - 7 - - - 4, 1 - - - 195, 108 - - - 11 - - - Servo Roll Pid - - - groupBox8 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 11 - - - 4, 22 - - - 0, 0, 0, 0 - - - 722, 434 - - - 0 - - - APM 2.x - - - TabAPM2 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ConfigTabs - - - 0 - - - 80, 63 - - - 78, 20 - - - 0 - - - ACRO_PIT_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 1 - - - IMAX - - - label27 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 1 - - - 80, 37 - - - 78, 20 - - - 4 - - - ACRO_PIT_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label29 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 3 - - - 80, 13 - - - 78, 20 - - - 6 - - - ACRO_PIT_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 7 - - - P - - - label33 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 5 - - - 182, 337 - - - 170, 91 - - - 13 - - - Acro Pitch - - - groupBox17 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 16 - - - IMAX - - - label14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 0 - - - 80, 63 - - - 78, 20 - - - 11 - - - THR_RATE_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 1 - - - 80, 37 - - - 78, 20 - - - 7 - - - THR_RATE_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 3 - - - 80, 13 - - - 78, 20 - - - 5 - - - THR_RATE_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 5 - - - 6, 221 - - - 170, 110 - - - 16 - - - Throttle Rate - - - groupBox5 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 1 - - - 80, 63 - - - 78, 20 - - - 0 - - - ACRO_RLL_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 0 - - - NoControl - - - 6, 66 - - - 68, 13 - - - 1 - - - IMAX - - - label40 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 1 - - - 80, 37 - - - 78, 20 - - - 4 - - - ACRO_RLL_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label44 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 3 - - - 80, 13 - - - 78, 20 - - - 6 - - - ACRO_RLL_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 7 - - - P - - - label48 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 5 - - - 6, 337 - - - 170, 91 - - - 14 - - - Acro Roll - - - groupBox18 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 2 - - - True - - - 3, 198 - - - 154, 17 - - - 13 - - - Lock Pitch and Roll Values - - - CHK_lockrollpitch - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 3 - - - 80, 86 - - - 78, 20 - - - 16 - - - WP_SPEED_MAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 0 - - - NoControl - - - 6, 89 - - - 54, 13 - - - 17 - - - m/s - - - label9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 1 - - - 80, 63 - - - 78, 20 - - - 11 - - - NAV_LAT_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 2 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 12 - - - IMAX - - - label13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 3 - - - 80, 37 - - - 78, 20 - - - 7 - - - NAV_LAT_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 5 - - - 80, 13 - - - 78, 20 - - - 5 - - - NAV_LAT_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 6 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label16 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 7 - - - 534, 107 - - - 170, 108 - - - 0 - - - Nav WP - - - groupBox4 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 4 - - - 80, 86 - - - 78, 20 - - - 18 - - - XTRK_ANGLE_CD1 - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 0 - - - NoControl - - - 6, 89 - - - 82, 13 - - - 19 - - - Error Max - - - label10 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 1 - - - 80, 63 - - - 78, 20 - - - 11 - - - XTRACK_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 2 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 12 - - - IMAX - - - label11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 3 - - - 80, 37 - - - 78, 20 - - - 7 - - - XTRACK_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 4 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 5 - - - 80, 13 - - - 78, 20 - - - 5 - - - XTRACK_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 6 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label18 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox6 - - - 7 - - - 358, 221 - - - 170, 110 - - - 2 - - - Crosstrack Correction - - - groupBox6 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 5 - - - 80, 63 - - - 78, 20 - - - 11 - - - THR_ALT_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox7 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 12 - - - IMAX - - - label19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox7 - - - 1 - - - 80, 37 - - - 78, 20 - - - 7 - - - THR_ALT_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox7 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label21 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox7 - - - 3 - - - 80, 13 - - - 78, 20 - - - 5 - - - THR_ALT_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox7 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label22 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox7 - - - 5 - - - 182, 221 - - - 170, 110 - - - 3 - - - Altitude Hold - - - groupBox7 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 6 - - - 80, 61 - - - 78, 20 - - - 11 - - - HLD_LAT_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - 0 - - - NoControl - - - 6, 64 - - - 65, 13 - - - 12 - - - IMAX - - - label28 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - 1 - - - 80, 37 - - - 78, 20 - - - 7 - - - HLD_LAT_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - 3 - - - 80, 13 - - - 78, 20 - - - 5 - - - HLD_LAT_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label31 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - 5 - - - 531, 6 - - - 170, 95 - - - 6 - - - Loiter - - - groupBox19 - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabAC2 + + + 29 - - 7 + + groupBox14 - - 80, 63 - - - 78, 20 - - - 11 - - - STB_YAW_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox20 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 12 - - - IMAX - - - label32 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox20 - - - 1 - - - 80, 37 - - - 78, 20 - - - 7 - - - STB_YAW_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox20 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label34 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox20 - - - 3 - - - 80, 13 - - - 78, 20 - - - 5 - - - STB_YAW_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox20 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label35 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox20 - - - 5 - - - 358, 6 - - - 170, 95 - - - 7 - - - Stabilize Yaw - - - groupBox20 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 8 - - - 80, 63 - - - 78, 20 - - - 11 - - - STB_PIT_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox21 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 12 - - - IMAX - - - label36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox21 - - - 1 - - - 80, 37 - - - 78, 20 - - - 7 - - - STB_PIT_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox21 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label41 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox21 - - - 3 - - - 80, 13 - - - 78, 20 - - - 5 - - - STB_PIT_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox21 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label42 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox21 - - - 5 - - - 182, 6 - - - 170, 95 - - - 8 - - - Stabilize Pitch - - - groupBox21 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 9 - - - 80, 63 - - - 78, 20 - - - 11 - - - STB_RLL_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 12 - - - IMAX - - - label43 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 1 - - - 80, 37 - - - 78, 20 - - - 7 - - - STB_RLL_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 14 - - - I - - - label45 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 3 - - - 80, 13 - - - 78, 20 - - - 5 - - - STB_RLL_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 15 - - - P - - - label46 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 5 - - - 6, 6 - - - 170, 95 - - - 9 - - - Stabilize Roll - - - groupBox22 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 10 - - - 80, 63 - - - 78, 20 - - - 0 - - - RATE_YAW_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 1 - - - IMAX - - - label47 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 1 - - - 80, 37 - - - 78, 20 - - - 4 - - - RATE_YAW_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label77 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 3 - - - 80, 13 - - - 78, 20 - - - 6 - - - RATE_YAW_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 7 - - - P - - - label82 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - 5 - - - 358, 107 - - - 170, 91 - - - 10 - - - Rate Yaw - - - groupBox23 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 11 - - - 80, 63 - - - 78, 20 - - - 0 - - - RATE_PIT_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox24 - - - 0 - - - NoControl - - - 6, 66 - - - 65, 13 - - - 1 - - - IMAX - - - label84 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox24 - - - 1 - - - 80, 37 - - - 78, 20 - - - 4 - - - RATE_PIT_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox24 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label86 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox24 - - - 3 - - - 80, 13 - - - 78, 20 - - - 6 - - - RATE_PIT_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox24 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 7 - - - P - - - label87 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox24 - - - 5 - - - 182, 107 - - - 170, 91 - - - 11 - - - Rate Pitch - - - groupBox24 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 12 - - - 80, 63 - - - 78, 20 - - - 0 - - - RATE_RLL_IMAX - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - 0 - - - NoControl - - - 6, 66 - - - 68, 13 - - - 1 - - - IMAX - - - label88 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - 1 - - - 80, 37 - - - 78, 20 - - - 4 - - - RATE_RLL_I - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - 2 - - - NoControl - - - 6, 40 - - - 10, 13 - - - 5 - - - I - - - label90 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - 3 - - - 80, 13 - - - 78, 20 - - - 6 - - - RATE_RLL_P - - - System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - 4 - - - NoControl - - - 6, 16 - - - 14, 13 - - - 7 - - - P - - - label91 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox25 - - - 5 - - - 6, 107 - - - 170, 91 - - - 12 - - - Rate Roll - - - groupBox25 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 13 - - - 4, 22 - - - 3, 3, 3, 3 - - + + 722, 434 - - 1 - - - AC2 - - - TabAC2 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ConfigTabs - - - 1 - - - NoControl - - - 30, 50 - - - 100, 23 - - - 41 - - - Video Format - - - label26 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 0 - - - 139, 47 - - - 408, 21 - - - 0 - - - CMB_videoresolutions - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 1 - - - NoControl - - - 30, 340 - - - 61, 13 - - - 39 - - - HUD - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 2 - - - NoControl - - - 139, 340 - - - 177, 17 - - - 40 - - - GDI+ (old type) - - - 17, 17 - - - OpenGL = Disabled -GDI+ = Enabled - - - CHK_GDIPlus + + label50 System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabPlanner + + P - + + ConfigTabs + + + groupBox10 + + + I + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 3 - - NoControl + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 30, 318 + + - + + INT_MAX + + + 78, 20 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 1 + + + 390, 11 + + + + + + RATE_YAW_IMAX + + + label22 + + + label51 + + + groupBox15 + + + 5 + + + 6, 16 + + + Setup + + + 3 + + 61, 13 - - 37 + + INT_MAX - - Waypoints + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 170, 91 + + + + + + + + + RATE_RLL_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 87 + + + + + + XTRK_ANGLE_CD1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + + NoControl + + + label56 + + + 111, 59 + + + groupBox16 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + THR_RATE_P + + + 80, 63 + + + 5 + + + 27, 244 + + + 13 + + + groupBox21 + + + + + + groupBox5 + + + 69, 13 + + + 80, 13 + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + WP_SPEED_MAX + + + GDI+ (old type) + + + groupBox24 + + + + + + label57 + + + + + + 111, 36 + + + 7 + + + 65, 13 + + + P + + + Default + + + groupBox8 + + + NoControl + + + 3, 416 + + + 22, 13 + + + label29 + + + 3, 3, 3, 3 + + + groupBox24 + + + 80, 21 + + + IMAX + + + P + + + INT_MAX + + + I + + + 136, 244 + + + Dist Units + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 80, 37 + + + 6, 221 + + + NoControl + + + 722, 434 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + NoControl + + + 408, 21 + + + groupBox18 + + + FBW max + + + 65, 13 + + + CHK_hudshow + + + 78, 20 + + + groupBox12 + + + STB_PIT_I + + + 15 + + + 3 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 9 + + + groupBox5 + + + label52 + + + 80, 13 + + + 78, 20 + + + label102 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + YW2SRV_IMAX + + + 4, 109 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 20 + + + 78, 20 + + + 5 + + + 11 + + + 40 + + + 111, 36 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + 16 + + + groupBox7 + + + + + + TabPlanner + + + 78, 20 + + + 65, 13 + + + label53 + + + RATE_PIT_IMAX + + + 531, 6 + + + groupBox23 + + + 0 + + + 0 + + + 4 + + + 2 + + + label94 + + + 7 + + + 6 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 43, 13 + + + label58 + + + TabAC2 + + + 11 + + + ACRO_RLL_P + + + UI Language + + + groupBox1 + + + groupBox16 + + + + + + + + + NAV_LAT_I + + + 111, 13 + + + 205, 1 + + + 1 + + + label95 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 730, 460 + + + 7 + + + groupBox17 + + + label59 + + + TabAPM2 label24 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 4 - - + NoControl - - 139, 317 - - - 177, 17 - - - 38 - - - Load Waypoints on connect? - - - CHK_loadwponconnect - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 5 - - - NoControl - - - 30, 292 - - - 103, 18 - - - 36 - - - Track Length - - - label23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 6 - - - 139, 291 - - - 67, 20 - - - 35 - - - On the Flight Data Tab - - - NUM_tracklength - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 7 - - - NoControl - - - 579, 107 - - - 102, 17 - - - 34 - - - Alt Warning - - - CHK_speechaltwarning - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 8 - - - NoControl - - - 30, 269 - - - 61, 13 - - + 0 - - APM Reset + + 111, 36 - - label108 + + - + + groupBox25 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabPlanner + + False - - 9 + + 6 - + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 0 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 20 + + + HDNG2RLL_P + + + 78, 20 + + NoControl - - 139, 267 - - - 163, 17 - - - 1 - - - Reset APM on USB Connect - - - CHK_resetapmonconnect - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 10 - - - Bottom, Left - - - NoControl - - - 33, 411 - - - 144, 17 - - - 2 - - - Mavlink Message Debug - - - CHK_mavdebug - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - + 11 NoControl - - 590, 244 + + groupBox17 - - 22, 13 + + 139, 340 - - 3 + + 170, 91 - - RC + + 25 - - label107 + + - + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 154, 17 + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabPlanner - - - 12 - - - 0 - - - 1 - - - 3 - - - 10 - - - 621, 240 - - - 80, 21 - - - 4 - - - CMB_raterc - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 13 - - - NoControl - - - 425, 244 - - - 69, 13 - - - 5 - - - Mode/Status - - - label104 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 14 - - - NoControl - - - 280, 244 - - - 44, 13 - - - 6 - - - Position - - - label103 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox9 TabPlanner - - 15 + + 78, 20 - + + + + + 103, 19 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2 + + NoControl - - 136, 244 + + groupBox20 - - 43, 13 + + label3 + + + + + + + + + label90 + + + + + + 111, 13 + + + NoControl + + + TabPlanner + + + label46 + + + 2 + + + 7 + + + Write changed params to device + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 12 + + + groupBox9 + + + groupBox7 + + + NoControl + + + Bottom, Left + + + + + + + + + 12 + + + label91 + + + ENRGY2THR_P + + + 65, 13 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 66 + + + 80, 37 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + CHK_GDIPlus + + + 4 + + + label7 + + + 78, 20 + + + + + + 11 + + + + + + 56, 17 + + + groupBox12 + + + 4 + + + label96 + + + TabPlanner + + + 6, 40 + + + 6 + + + NoControl + + + 0, 0, 0, 0 + + + 14 + + + 16 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + TabPlanner + + + groupBox17 + + + 111, 36 + + + groupBox19 + + + 18 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 20 + + + 177, 17 + + + HLD_LAT_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 138, 21 + + + 5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + + + + 5 + + + 15 + + + groupBox10 + + + groupBox8 + + + TabPlanner 7 - - Attitude + + 4 - - label102 + + 52, 13 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 5 - - TabPlanner + + 15, 13 - - 16 - - + NoControl - - 27, 244 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 84, 13 + + 182, 6 - - 8 + + NoControl - - Telemetry Rates + + + + + + + + + + + + + + 1 + + + groupBox8 + + + 1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 10, 13 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Cruise + + + + + + groupBox25 + + + 3 + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 111, 59 + + + 3 + + + 87, 17 + + + 10 + + + toolTip1 + + + 111, 82 + + + IMAX + + + 6, 63 + + + groupBox9 + + + groupBox9 + + + 111, 36 + + + RLL2SRV_IMAX + + + 12 + + + ARSP2PTCH_P + + + 27 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 5 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 80, 86 + + + 5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 5 + + + 27, 13 + + + Nav Pitch AS Pid + + + 245, 107 + + + 590, 244 + + + label93 + + + 80, 63 + + + groupBox12 + + + RLL2SRV_I label101 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 11 - - TabPlanner + + CHK_mavdebug - - 17 + + 78, 20 - + + 139, 317 + + + 7 + + + 78, 20 + + + CMB_rateposition + + + 6, 16 + + + 4 + + + 5 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 20 + + + CMB_ratestatus + + + 39 + + + groupBox17 + + + 5 + + + 10, 13 + + + CHK_speechwaypoint + + + + + 0 - + + CHK_speechaltwarning + + + + + + NoControl + + + 14, 13 + + + NUM_tracklength + + + BUT_Joystick + + + label23 + + + TabAC2 + + + 6, 17 + + + + + + 65, 13 + + + 579, 107 + + + IMAX + + + 139, 158 + + + 78, 20 + + + 2 + + + I + + + + + + 68, 13 + + + 80, 13 + + + groupBox18 + + + groupBox8 + + + 0 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 9 + + + 0 + + + NoControl + + + label107 + + + 61, 13 + + + groupBox3 + + + + + + + + + NoControl + + + Energy/Alt Pid + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + + + + 78, 20 + + + Load + + + groupBox9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + 3 + + + 111, 82 + + + 195, 108 + + + + + + 0 + + + 358, 6 + + + 0 + + + + + + Enable HUD Overlay + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 205, 217 + + + 0 + + + ENRGY2THR_D + + + 15 + + + + + + + + + groupBox10 + + + 6, 86 + + + 80, 37 + + + NAV_LAT_P + + + + + + + + + 139, 131 + + + groupBox23 + + + 722, 434 + + + 50, 13 + + + 78, 20 + + + label64 + + + 30, 162 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + + + + 65, 13 + + + TabAC2 + + + 14, 13 + + + + + + 14, 13 + + + 0 + + + Enable Speech + + + P to T + + + groupBox10 + + + 78, 20 + + + groupBox3 + + + 334, 240 + + + + + + BUT_writePIDS + + + Save params to file + + + 78, 20 + + + label65 + + + + + + 111, 13 + + + 10, 13 + + + + + + 3 + + + Reload params from device + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 1 + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Waypoint + + + 0 + + + 80, 37 + + + 7 + + + 7 + + + 75, 23 + + + 80, 21 + + + 6, 16 + + + 5 + + + 111, 13 + + + 30 + + + + + + 103, 19 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 195, 108 + + + 78, 20 + + + + + + TabPlanner + + + 24 + + + NoControl + + + IMAX + + + 406, 325 + + + P + + + + + + 6 + + + IMAX + + + P + + + 5 + + + TabAPM2 + + + NoControl + + + P + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14, 13 + + + 4, 22 + + + NoControl + + + label60 + + + 170, 95 + + + 14, 13 + + + 139, 187 + + + TabAPM2 + + + 78, 20 + + + 2 + + + TabPlanner + + + 10 + + + 5 + + + + + + 3 + + + label61 + + + 20 + + + IMAX + + + I + + + + + + 150 + + + D + + + RATE_YAW_I + + + 8 + + + 3 + + + groupBox21 + + + Stabilize Roll + + + 6, 17 + + + 4, 22 + + + True + + + 78, 20 + + + + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 30, 50 + + + 5 + + + HDNG2RLL_D + + + 111, 59 + + + NoControl + + + 14 + + + 10, 13 + + + NoControl + + + 2 + + + 205, 109 + + + 5 + + + 139, 80 + + + 11 + + + 5 + + + + + + 3, 198 + + + NoControl + + + IMAX + + + NoControl + + + 1 + + + 111, 82 + + + groupBox6 + + + 44, 13 + + + APM 2.x + + + 6, 40 + + + label67 + + + P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15 + + + P + + + P + + + 1 + + + P + + + 195, 108 + + + 12 + + + 78, 20 + + + 5 + + + 15 + + + THR_ALT_I + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 17 + + + 2 + + + TRIM_THROTTLE + + + groupBox4 + + + $this + + + I + + + groupBox6 + + + 10, 13 + + + 6, 17 + + + groupBox21 + + + 58 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 40 + + + 4 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 195, 108 + + + + + + 111, 13 + + + 195, 108 + + + TabAC2 + + + NoControl + + + D + + + 1 + + + groupBox4 + + + 6, 17 + + + + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 80 + + + + + + 6, 64 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15, 13 + + + 6, 17 + + + 65, 13 + + + + + + + + + groupBox18 + + + 9 + + + 2 + + + 30, 269 + + + groupBox14 + + + 195, 108 + + + 6, 66 + + + 78, 20 + + + label99 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 80, 37 + + + TabPlanner + + + 10, 13 + + + label27 + + + 170, 108 + + + 78, 20 + + + 4 + + + 24 + + + 14 + + + 7 + + + 5 + + + NoControl + + + Rudder Mix + + + XTRK_GAIN_SC + + + + + + NoControl + + + Video Device + + + 4 + + + 14 + + + TabPlanner + + + 75, 23 + + + TabAPM2 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 10 + + + 170, 110 + + + 1 + + + INT_MAX + + + 10, 13 + + + label68 + + + 6, 40 + + + 188, 240 + + + ENRGY2THR_I + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + STB_PIT_P + + + 283, 209 + + + NoControl + + + 6 + + + ARSP2PTCH_D + + + groupBox5 + + + 6, 40 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + HLD_LAT_P + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 5 + + + 30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 170, 110 + + + 61, 13 + + + 44, 13 + + + label69 + + + groupBox7 + + + 6, 66 + + + 182, 337 + + + groupBox5 + + + 15, 13 + + + NoControl + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + NoControl + + + + + + + + + THR_MIN + + + 65 + + + 170, 110 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 78, 20 + + + + + + + + + 6, 66 + + + 4 + + + Command + + + 5 + + + 13 + + + groupBox11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 40 + + + 6, 16 + + + 80, 37 + + + 4 + + + 6 + + + TabAPM2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + NoControl + + + 5 + + + 0, 0 + + + 11 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + 34 + + + 0 + + + groupBox5 + + + 111, 36 + + + groupBox23 + + + groupBox6 + + + 4 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15, 13 + + + ConfigTabs + + + 2 + + + + + + TabAC2 + + + 4 + + + Top, Bottom, Left, Right + + + Ratio + + + 11 + + + groupBox16 + + + 65, 13 + + + groupBox8 + + + 1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + ConfigTabs + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ALT2PTCH_I + + + + + + + + + 4 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 28 + + + NoControl + + + + + + 14, 13 + + + + + + + + + 102, 17 + + + ARSP2PTCH_I + + + groupBox1 + + + 15 + + + 11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 278, 0 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 6, 40 + + + 6, 40 + + + NoControl + + + 111, 36 + + + + + + THR_ALT_IMAX + + + 12 + + + 6, 40 + + + 7 + + + 3 + + + + + + NoControl + + + 14 + + + 33 + + + 15 + + + 6, 16 + + + + + + TabAPM2 + + + Track Length + + + 80, 13 + + + 3 + + + CMB_distunits + + + groupBox14 + + + label4 + + + groupBox15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 31 + + + 7 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14, 13 + + + NoControl + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + groupBox13 + + + label2 + + + 12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + YW2SRV_I + + + 6, 66 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 12 + + + 15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 402, 13 + + + 2 + + + Max + + + Min + + + label6 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 63 + + + 61, 13 + + + 111, 82 + + + P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 32 + + + label8 + + + groupBox19 + + + 30, 318 + + + 125, 17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 78, 20 + + + 14, 13 + + + 80, 63 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + groupBox13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 7 + + + 30, 189 + + + + + + 111, 59 + + + groupBox1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 22 + + + 2 + + + 10, 13 + + + + + + Nav Pitch Alt Pid + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 0 + + + groupBox21 + + + 2 + + + I + + + 6, 66 + + + Servo Roll Pid + + + 12 + + + RLL2SRV_P + + + 12 + + + ACRO_PIT_I + + + 30, 16 + + + YW2SRV_D + + + 7 + + + groupBox7 + + + 0 + + + 80, 13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 20 + + + 11 + + + mavScale + + + NoControl + + + + + + NoControl + + + Servo Pitch Pid + + + TabPlanner + + + Start + + + label44 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 13 + + + 9 + + + Bottom, Left + + + 1 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + PTCH2SRV_D + + + + + + m/s + + + 195, 108 + + + P + + + Telemetry Rates + + + label45 + + + 6, 63 + + + groupBox15 + + + 111, 82 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + I + + + + + + 78, 20 + + + TabPlanner + + + 1 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + NoControl + + + groupBox4 + + + 18 + + + 78, 20 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 30, 217 + + + 15 + + + HDNG2RLL_IMAX + + + 6, 66 + + + NoControl + + + 78, 20 + + + 10, 13 + + + + + + Nav Roll Pid + + + 3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + IMAX + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + STB_PIT_IMAX + + + 5 + + + 30, 135 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label97 + + + + + + 6 + + + 80, 37 + + + + + + 10, 13 + + + 25 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Stabilize Pitch + + + 6, 86 + + + 78, 20 + + + ENRGY2THR_IMAX + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 31 + + + TabPlanner + + + groupBox4 + + + groupBox20 + + + label40 + 3 10 - - 499, 240 + + 4 - - 80, 21 + + 6 - + + 13 + + + 23 + + + groupBox2 + + + groupBox1 + + + NoControl + + + 3, 3 + + + groupBox6 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 4 + + + TabAC2 + + + groupBox6 + + + + + + 280, 244 + + + + + + NoControl + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 16 + + + HUD + + + 0 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 40 + + + TabAC2 + + + 10, 13 + + + 7 + + + 0 + + + 0 + + + CHK_enablespeech + + + 10, 13 + + + NoControl + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NAV_LAT_IMAX + + + 54, 13 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 52, 13 + + + I + + + 111, 59 + + + 50, 13 + + + 4, 217 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + INT_MAX + + + + + + 2 + + + Bottom, Left + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + Joystick Setup + + + label47 + + + NoControl + + + 6 + + + Save + + + + + + ALT2PTCH_D + + + 6, 63 + + + TabPlanner + + + 6 + + 9 - - CMB_ratestatus + + Bottom, Left - + + 14, 13 + + + Airspeed m/s + + + 102, 17 + + + label98 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl + + + 0, 0, 0, 0 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 6, 86 + + + 6 + + + 3 + + + 78, 20 + + + 10 + + + 6 + + + 139, 47 + + + 6, 16 + + + 2 + + + NoControl + + + + + + Navigation Angles + + + groupBox24 + + + 5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + RawValue + + + False + + + CHK_speechcustom + + + groupBox20 + + + 16 + + + 4 + + + 78, 20 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + XTRK_ANGLE_CD + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 7 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 6 + + + 17 + + + P + + + label42 + + + groupBox19 + + + D + + + 3 + + + CHK_loadwponconnect + + + 6, 66 + + + Loiter + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + Throttle 0-100% + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 15 + + + groupBox1 + + + 378, 107 + + + 205, 325 + + + 6, 40 + + + NoControl + + + Nav WP + + + 65, 13 + + + label43 + + + 0 + + + 78, 20 + + + 65, 13 + + + + + + Alt Warning + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 111, 82 + + + + + + NoControl + + + label48 + + + Throttle Rate + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 36, 13 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 40 + + + 78, 20 + + + 7 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label108 + + + ConfigTabs + + + 12 + + + + + + 14 + + + 111, 36 + + + 78, 20 + + + I + + + 33 + + + groupBox14 + + + label49 + + + groupBox10 + + + Crosstrack Correction + + + 35 + + + + + + + + + + + + P + + + 30, 83 + + + groupBox19 + + + NoControl + + + 16 + + + + + + TabAC2 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 15 + + + 8 + + + 26 + + + Altitude Hold + + + 57, 13 + + + groupBox1 + + + 12 + + + 4, 22 + + + 6, 63 + + + INT_MAX + + + 17 + + + groupBox19 + + + TabPlanner + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + Lock Pitch and Roll Values + + + + + + 103, 18 + + + 13 + + + NoControl + + + NoControl + + + groupBox24 + + + 40 + + + 80, 63 + + + 71, 17 + + + 5 + + + 2 + + + 111, 82 + + + groupBox21 + + + label109 + + + 80, 63 + + + 0 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + CMB_videoresolutions + + + NoControl + + + groupBox13 + + + + + + 3 + + + groupBox6 + + + 1 + + + NoControl + + + groupBox2 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 80, 13 + + + groupBox11 + + + INT_MAX + + + 54, 13 + + + 30, 111 + + + + + + 4, 22 + + + 4 + + + label33 + + + 6, 40 + + + 0 + + + NoControl + + + Value + + + NoControl + + + ARSPD_FBW_MIN + + + 14 + + + 7 + + + + + + 0 + + + 14 + + + 78, 20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Reset APM on USB Connect + + + ALT2PTCH_IMAX + + + 5 + + + 170, 91 + + + 7 + TabPlanner - - 18 + + 78, 20 - - 0 - - + 1 - + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + + + + 11 + + + 80, 61 + + + 1 + + + 78, 20 + + + YW2SRV_P + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 59 + + + 17 + + + 13 + + + groupBox8 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + 31, 438 + + + 78, 20 + + + 80, 37 + + + ARSPD_FBW_MAX + + + Compare Params + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + 3 - - 10 + + 78, 20 - - 334, 240 + + label41 - - 80, 21 + + 2 - - 10 + + groupBox20 - - CMB_rateposition + + CMB_speedunits - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 195, 108 - + + + + + 722, 434 + + + + + + 22 + + + groupBox23 + + + THR_RATE_I + + + groupBox3 + + + + + + + + + + + + 5 + + + 1 + + + 111, 59 + + + 15, 13 + + + 13 + + + groupBox17 + + + 4, 325 + + + 11 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + PTCH2SRV_P + + + 78, 20 + + + 78, 20 + + + + + + NoControl + + + 28 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 5 + + + 144, 17 + + + 78, 20 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + groupBox10 + + + 358, 221 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 4 + + + groupBox2 + + + 78, 20 + + + + + + STB_YAW_P + + + 499, 240 + + + 1 + + + + + TabPlanner - - 19 + + 111, 13 + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 20 + + + 10 + + + D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 621, 240 + + + 322, 107 + + + groupBox2 + + + groupBox11 + + + 2 + + + NoControl + + + groupBox2 + + + + + + IMAX + + + 4 + + + 6, 86 0 - + + 7 + + + 6, 17 + + + XTRACK_I + + + 7 + + + + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2 + + + + + + 2 + + + 11 + + + 4 + + + NoControl + + + groupBox18 + + + Joystick + + + 169, 441 + + + 14 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 7 + + + NoControl + + + 15 + + + 54, 13 + + + 9 + + + 80, 37 + + + groupBox12 + + + 7 + + + CMB_raterc + + + groupBox24 + + + KFF_PTCH2THR + + + PTCH2SRV_IMAX + + + Bottom, Left + + + Top, Bottom, Left + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 8 + + + $this + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 27 + + + KFF_PTCHCOMP + + + 9 + + + 19 + + + 4 + + + 78, 20 + + + NoControl + + 1 - + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14 + + + On the Flight Data Tab + + + + + + 6, 107 + + + 45, 13 + + + groupBox24 + + + 5 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 20 + + + 138, 21 + + + groupBox3 + + + 9 + + + groupBox20 + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 4 + + + 4 + + + 41 + + + 0 + + + NoControl + + + Gain (cm) + + + 6 + + + NoControl + + + RATE_PIT_P + + + groupBox4 + + + + + + 5 + + + 7 + + + 65, 13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 6, 40 + + + + + + + + + Rate Pitch + + + 80, 13 + + + LIM_PITCH_MIN + + + TabPlanner + + + + + + 61, 13 + + + 80, 21 + + + APM Reset + + + 1 + + + 6, 16 + + + 7 + + + 63 + + + 10 + + + 13 + + + Battery Warning + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + IMAX + + + 7 + + + 21 + + + groupBox22 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 5 + + + 5 + + + groupBox2 + + + TabPlanner + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 67, 20 + + + + + + 14, 13 + + + + + + TabPlanner + + + 14 + + + 0 + + + 75, 19 + + + 1 + + + 30, 292 + + + 3, 3, 3, 3 + + + TabAC2 + + + 111, 13 + + + TabPlanner + + + 38 + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15 + + + 80, 63 + + + 1 + + + 4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 3 10 - - 188, 240 + + 42 - - 80, 21 + + 0, 0 - + + NoControl + + + groupBox17 + + + 2 + + + + + + label18 + + + 15, 13 + + + 111, 13 + + + 3 + + + NoControl + + + NoControl + + + 5 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + label14 + + + NoControl + + + 14, 13 + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 11 - - CMB_rateattitude + + 5 + + + Cruise + + + + + + 0 + + + 1 + + + 100, 23 + + + 78, 20 + + + 78, 20 + + + + + + TabPlanner + + + 5 + + + I + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + Mode/Status + + + 2 + + + 11 + + + 80, 37 + + + 6 + + + NoControl + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 80, 13 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label84 + + + groupBox6 + + + 7 + + + + + + 78, 20 + + + groupBox18 + + + label73 + + + 53, 13 + + + Servo Yaw Pid + + + 78, 20 + + + 4 + + + P + + + + + + Pitch Max + + + TabAPM2 + + + D + + + groupBox23 + + + label103 + + + 6 + + + groupBox14 + + + + + + 1 + + + + + + 11 + + + 38 + + + + + + 78, 20 + + + 9 + + + 3 + + + Stabilize Yaw + + + 3 + + + groupBox20 + + + label34 + + + NoControl + + + 14, 13 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + groupBox15 + + + BUT_videostart + + + 5 + + + IMAX + + + 78, 20 + + + 35 + + + 3 + + + NoControl + + + 10, 13 + + + groupBox4 + + + 6 + + + 32, 13 + + + 5 + + + 4 + + + STB_RLL_P + + + label35 + + + TabPlanner + + + $this + + + 406, 109 + + + I + + + label62 + + + 4 + + + 1 + + + STB_YAW_IMAX + + + 177, 17 + + + NoControl + + + + + + 5 + + + TabPlanner + + + CMB_osdcolor + + + 3 + + + 0 + + + + + + + + + 78, 20 + + + 7 + + + 182, 107 + + + 14, 13 + + + label80 + + + + + + TabPlanner + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 63 + + + groupBox4 + + + 7 + + + 78, 20 + + + groupBox18 + + + + + + NoControl + + + 5 + + + groupBox14 + + + 5 + + + 11 + + + + + + Speed Units + + + NoControl + + + label81 + + + 1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 86 + + + + + + + + + BUT_save + + + 3 + + + + + + groupBox20 + + + 14 + + + P + + + CHK_speechbattery + + + I + + + 26 + + + label30 + + + RawValue + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + False + + + $this + + + Configuration + + + 82, 13 + + + groupBox11 + + + 78, 20 + + + groupBox1 + + + 23 + + + groupBox13 + + + label31 + + + THR_MAX + + + 61, 13 + + + 14, 13 + + + TabPlanner + + + 54, 13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 36, 13 + + + STB_RLL_IMAX + + + 80, 13 + + + 78, 20 + + + label87 + + + 6, 40 + + + 75, 19 + + + Load param's from file + + + 6, 89 + + + 1 + + + ACRO_PIT_P + + + 80, 63 + + + 4 + + + TabPlanner + + + label36 + + + TabPlanner + + + ARSP2PTCH_IMAX + + + groupBox9 + + + 78, 20 + + + + + + groupBox25 + + + 4 + + + Time Interval + + + Other Mix's + + + 0 + + + + + + Acro Roll + + + Mode + + + groupBox23 + + + + + + 405, 217 + + + TabAC2 + + + 11 + + + 7 + + + 80, 13 + + + label12 + + + 0 + + + label37 + + + 5 + + + 1 + + + TabPlanner + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + I + + + Attitude + + + P + + + 1 + + + RC + + + 6, 86 + + + 3 + + + 80, 63 + + + NoControl + + + label82 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 54, 13 + + + 1 + + + groupBox21 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Speech + + + + + + 0 + + + 9 + + + + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14, 13 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + THR_RATE_IMAX + + + 1 + + + 1008, 461 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + Error Max + + + label83 + + + 3 + + + 0 + + + 0 + + + NoControl System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabPlanner + + 195, 108 - - 20 + + 7 - + + + + + 6 + + + 6 + + + 6, 40 + + + 7 + + + 6 + + + 111, 59 + + + label32 + + + label19 + + + groupBox13 + + + 1 + + + label88 + + + 78, 20 + + + groupBox22 + + NoControl - - 283, 209 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 402, 13 + + + + + NoControl + + + 2 + + + 170, 95 + + + 163, 17 + + + groupBox3 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + 170, 91 + + + groupBox14 + + + label15 + + + groupBox4 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 86 + + + RATE_RLL_P + + + 195, 108 + + + 5 + + + 21 + + + groupBox9 + + + 534, 107 + + + TabPlanner + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 64 + + + 4 + + + 13 + + + label38 + + + groupBox1 + + + $this + + + 111, 59 + + + groupBox16 + + + 4 + + + 12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + TabPlanner + + + 195, 108 + + + groupBox6 + + + 0 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 100, 23 + + + XTRACK_IMAX + + + label39 + + + + + + 6, 16 + + + 78, 20 + + + NoControl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14 + + + 6 + + + groupBox15 + + + 14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + RATE_YAW_P + + + + + + groupBox4 + + + + + + 1 + + + 6, 40 + + + + + + Default + + + 12 + + + TabAPM2 + + + LIM_PITCH_MAX + + + + + + label10 + + + 0 + + + groupBox8 + + + 3 + + + + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 99, 23 + + + 80, 63 + + + NoControl + + + + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14 + + + THR_ALT_P + + + TabPlanner + + + 6 + + + label11 + + + 6, 17 + + + groupBox7 + + + 14 + + + + + + + + + 6, 16 + + + label1 + + + + + + 80, 63 + + + 111, 82 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + P + + + label16 + + + + + + 3 + + + 80, 21 + + + 6, 16 + + + ConfigTabs + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 182, 221 + + + 0 + + + + + + 7 + + + 4 + + + 13 + + + 4, 1 + + + 30, 340 + + + D + + + 9 + + + 12 + + + 8 + + + NoControl + + + label5 + + + groupBox14 + + + 111, 59 + + + 6, 17 + + + NoControl + + + 170, 95 + + + 10, 13 + + + + + + TabAPM2 + + + + + + 4 + + + 6, 40 + + + 2 + + + 6, 40 + + + 14, 13 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Refresh Params + + + CHK_lockrollpitch + + + HDNG2RLL_I 12 + + + + + + + + 6, 16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 10, 13 + + + 19 + + + CMB_language + + + label9 + + + RATE_PIT_I + + + NoControl + + + 7 + + + 12 + + + 471, 11 + + + groupBox12 + + + groupBox3 + + + groupBox16 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0, 0, 0, 0 + + + 1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Write Params + + + 78, 20 + + + 80, 13 + + + IMAX + + + 68, 13 + + + 6, 17 + + + + + + NoControl + + + 80, 37 + + + + + + 2 + + + XTRACK_P + + + 14 + + + NoControl + + + 4 + + + TabPlanner + + + + + + 4 + + + I + + + 425, 244 + + + Value + + + 139, 291 + + + KFF_RDDRMIX + + + 36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Video Format + + + 0 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + label13 + + + 41 + + + mavScale + + + groupBox16 + + + TabAC2 + + + 80, 86 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabSetup + + + NoControl + + + 78, 20 + + + I + + + P + + + 2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + I + + + 111, 13 + + + 2 + + + 0 + + + 14, 13 + + + groupBox3 + + + 3 + + + + + + 78, 20 + + + 5 + + + 6, 66 + + + 5 + + + Waypoints + + + + + + 15 + + + 10, 13 + + + 138, 21 + + + $this + + + 80, 37 + + + + + + groupBox22 + + + TabPlanner + + + 78, 20 + + + + + + 78, 20 + + + 6, 17 + + + 1 + + + TabAC2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Command + + + 78, 20 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 10 + + + 29 + + + 2 + + + groupBox11 + + + + + + NoControl + + + 6, 16 + + + 2 + + + Pitch Comp + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 19 + + + 5 + + + FBW min + + + NoControl + + + D + + + 51, 13 + + + + + + 6, 66 + + + + + + CMB_rateattitude + + + + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + HLD_LAT_I + + + 6, 40 + + + 6, 40 + + + 7 + + + I + + + + + + groupBox12 + + + 80, 13 + + + 11 + + + 2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 40 + + + 111, 13 + + + + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 6, 63 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 82, 416 + + + + + + 5 + + + 78, 20 + + + Bank Max + + + AC2 + + + groupBox9 + + + 78, 20 + + + + + + 78, 20 + + + 0 + + + 103, 19 + + + groupBox14 + + + groupBox13 + + + + + + 2 + + + 1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + P + + + 54, 13 + + + 6 + + + 0 + + + + + + 69, 13 + + + 6, 63 + + + Rate Yaw + + + 13 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + TabAC2 + + + FS Value + + + 5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 10, 13 + + + 12 + + + + + + 5 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + groupBox16 + + + 111, 36 + + + + + + 7 + + + 15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 7 + + + + + + 10, 13 + + + BUT_videostop + + + CHK_resetapmonconnect + + + + + + 14, 13 + + + 245, 21 + + + 15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 11 + + + 78, 20 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + 3 + + + 2 + + + 6, 40 + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 55, 13 + + + ARSPD_RATIO + + + Params + + + groupBox19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 37 + + + 0 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + groupBox5 + + + 0 + + + 7 + + + + + + TabPlanner + + + ACRO_PIT_IMAX + + + TabPlanner + + + NoControl + + + 6, 89 + + + groupBox25 + + + + + + NoControl + + + + + + + + + IMAX + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Pitch Min + + + 269, 409 + + + 358, 107 + + + I + + + NoControl + + + TabAPM2 + + + ACRO_RLL_I + + + 7 + + + 0, 0, 0, 0 + + + + + + 78, 20 + + + NoControl + + + Stop + + + 18 + + + 169, 416 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 111, 13 + + + 78, 20 + + + 1 + + + 2 + + + 4 + + + label74 + + + 78, 20 + + + RATE_RLL_I + + + NoControl + + + 78, 20 + + + 7 + + + 6, 66 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 14, 13 + + + 54, 13 + + + CMB_videosources + + + Acro Pitch + + + groupBox12 + + + TabPlanner + + + groupBox13 + + + label75 + + + ACRO_RLL_IMAX + + + 3 + + + NoControl + + + 5 + + + 6, 40 + + + + + + + + + 139, 214 + + + 6, 63 + + + 5 + + + 2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 16 + + + 6, 66 + + + TabPlanner + + + 33, 411 + + + 6, 17 + + + 7 + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 12 + + + 16 + + + 111, 59 + + + + + + CHK_speechmode + + + 111, 59 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2 + + + Entry Angle + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + NOTE: The Configuration Tab will NOT display these units, as those are raw values. - - label99 + + - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TabPlanner + + - - 21 + + 84, 13 - - NoControl - - - 30, 217 - - - 65, 13 - - - 13 - - - Speed Units - - - label98 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 22 - - - NoControl - - - 30, 189 - - - 52, 13 - - - 14 - - - Dist Units - - - label97 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 23 - - - 139, 214 - - - 138, 21 - - - 15 - - - CMB_speedunits - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 24 - - - 139, 187 - - - 138, 21 - - - 16 - - - CMB_distunits - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 25 - - - NoControl - - - 30, 162 - - - 45, 13 - - - 17 - - - Joystick - - - label96 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 26 - - - NoControl - - - 30, 111 - - - 44, 13 - - - 18 - - - Speech - - - label95 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 27 - - - NoControl - - - 471, 107 - - - 102, 17 - - - 19 - - - Battery Warning - - - CHK_speechbattery - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 28 - - - NoControl - - - 378, 107 - - - 87, 17 - - - 20 - - - Time Interval - - - CHK_speechcustom - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 29 - - - NoControl - - - 322, 107 - - - 56, 17 - - - 21 - - - Mode - - - CHK_speechmode - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 30 - - - NoControl - - - 245, 107 - - - 71, 17 - - - 22 - - - Waypoint - - - CHK_speechwaypoint - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 31 - - - NoControl - - - 30, 83 - - - 57, 13 - - - 23 - - - OSD Color - - - label94 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 32 - - - 139, 80 - - - 138, 21 - - - 24 - - - CMB_osdcolor - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 33 - - - 139, 131 - - - 138, 21 - - - 25 - - - CMB_language - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 34 - - - NoControl - - - 30, 135 - - - 69, 13 - - - 26 - - - UI Language - - - label93 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 35 - - - NoControl - - - 139, 107 - - - 99, 17 - - - 27 - - - Enable Speech - - - CHK_enablespeech - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 36 - - - NoControl - - - 552, 15 - - - 125, 17 - - - 28 - - - Enable HUD Overlay - - - CHK_hudshow - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 37 - - - NoControl - - - 30, 16 - - - 100, 23 - - - 29 - - - Video Device - - - label92 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 38 - - - 139, 13 - - - 245, 21 - - - 30 - - - CMB_videosources - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - 39 - - - NoControl - - - 139, 158 - - - 99, 23 - - - 31 - - - Joystick Setup - - - BUT_Joystick - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - TabPlanner - - - 40 - - - NoControl - - - 471, 11 - - - 75, 23 - - - 32 - - - Stop - - - BUT_videostop - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - TabPlanner - - - 41 - - - NoControl - - - 390, 11 - - - 75, 23 - - - 33 - - - Start - - - BUT_videostart - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - TabPlanner - - - 42 - - - 4, 22 - - - 3, 3, 3, 3 - - - 722, 434 - - + 2 - - Planner - - - TabPlanner - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ConfigTabs - - - 2 - - - 4, 22 - - - 722, 434 - - - 3 - - - Setup - - - TabSetup - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ConfigTabs - - - 3 - - - 52, 18 - - - 278, 0 - - - 0, 0, 0, 0 - - - 0, 0 - - - 730, 460 - - - 62 - - - ConfigTabs - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - 0, 0 - - - 100, 23 - - - 0 - - - label109 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Bottom, Left - - - NoControl - - - 169, 441 - - - 103, 19 - - - 0 - - - Refresh Params - - - Reload params from device - - - BUT_rerequestparams - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 1 - - - Bottom, Left - - - NoControl - - - 169, 416 - - - 103, 19 - - - 63 - - - Write Params - - - Write changed params to device - - - BUT_writePIDS - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 3 - - - Bottom, Left - - - NoControl - - - 82, 416 - - - 0, 0, 0, 0 - - - 75, 19 - - - 64 - - - Save - - - Save params to file - - - BUT_save - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - 4 - - Bottom, Left + + 4 - - NoControl - - - 3, 416 - - - 0, 0, 0, 0 - - - 75, 19 - - - 65 - - - Load - - - Load param's from file - - - BUT_load - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - + $this - - 5 + + - - Bottom, Left + + 8 - + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - 31, 438 + + Position - - 103, 19 + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 66 + + 80, 63 - - Compare Params + + + + + 8 + + + 0 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6 + + + LIM_ROLL_CD + + + groupBox10 + + + label66 + + + label70 + + + groupBox13 + + + + + + 6, 40 + + + System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + OpenGL = Disabled +GDI+ = Enabled + + + 6 + + + 54, 13 + + + BUT_rerequestparams + + + 8 + + + 111, 82 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2 + + + NoControl + + + Xtrack Pids + + + NoControl + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 24, 13 + + + label71 + + + 39 + + + 552, 15 + + + groupBox11 BUT_compare - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + 139, 107 - - $this + + NoControl - + + Planner + + + 6, 63 + + + TabPlanner + + + I + + + 5 + + 0 + + 13 + + + groupBox21 + + + OSD Color + + + + + + Rate Roll + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label25 + + + 80, 37 + + + label76 + + + 6, 86 + + + 406, 1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 1 + + + NoControl + + + 100, 23 + + + 37 + + + NoControl + + + 6, 6 + + + 111, 36 + + + + + + 64, 13 + + + 111, 36 + + + 11 + + + Mavlink Message Debug + + + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 111, 13 + + + 6, 337 + + + BUT_load + + + label77 + + + 9 + + + 3 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 2 + + + 9 + + + 78, 20 + + + NoControl + + + NoControl + + + 5 + + + 195, 108 + + + + + + groupBox7 + + + Bottom, Left + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 6, 66 + + + RLL2SRV_D + + + 32 + + + + + + 9 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + 170, 95 + + + label20 + + + 15, 13 + + + 6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label92 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label63 + + + TRIM_ARSPD_CM + + + + + + 111, 36 + + + 7 + + + 170, 91 + + + 10, 13 + + + NoControl + + + label21 + + + 13 + + + groupBox9 + + + label72 + + + label54 + + + 471, 107 + + + 10 + + + TabPlanner + + + + + + groupBox11 + + + groupBox11 + + + 99, 17 + + + groupBox6 + + + TabPlanner + + + 1 + + + PTCH2SRV_I + + + groupBox24 + + + 139, 267 + + + Load Waypoints on connect? + + + STB_RLL_I + + + label26 + + + label55 + + + groupBox25 + + + 14 + + + NoControl + + + 78, 20 + + + 34 + + + 3 + + + 14, 13 + + + groupBox8 + + + + + + 62 + + + + + + 5 + + + + + + 150 + + + groupBox25 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label78 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 138, 21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 54, 13 + + + STB_YAW_I + + + groupBox22 + + + label104 + + + 5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + + + + 139, 13 + + + 80, 13 + + + 80, 63 + + + 9 + + + label79 + + + groupBox3 + + + TabAC2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label86 + + + groupBox3 + + + + + + ALT2PTCH_P + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15 + + + 65, 13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 10, 13 + + + 10 + + + groupBox13 + + + I + + + groupBox22 + + + 52, 18 + + + True + True - - 6, 13 + + 17, 17 - - 1008, 461 + + True - - Command + + True - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Value - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Default - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - mavScale - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - RawValue - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - toolTip1 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Configuration - - - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + True ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.zh-Hans.resx index e34b3c3479..abda20d918 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.zh-Hans.resx @@ -730,6 +730,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 122, 17 @@ -805,19 +868,19 @@ - + - + - + @@ -982,6 +1045,15 @@ + + 视频格式 + + + + + + + 抬头显示 @@ -1261,6 +1333,9 @@ + + + 刷新参数 @@ -1273,10 +1348,17 @@ 加载 + + 比较参数 + + + + ..\Resources\MAVParam.zh-Hans.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index bddd7f9853..7dc0455310 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -10,9 +10,6 @@ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightData)); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle(); - this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components); - this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); - this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.MainH = new System.Windows.Forms.SplitContainer(); this.SubMainLeft = new System.Windows.Forms.SplitContainer(); this.hud1 = new hud.HUD(); @@ -55,6 +52,9 @@ this.lbl_winddir = new ArdupilotMega.MyLabel(); this.lbl_windvel = new ArdupilotMega.MyLabel(); this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl(); + this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components); + this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.panel1 = new System.Windows.Forms.Panel(); this.TXT_lat = new ArdupilotMega.MyLabel(); this.Zoomlevel = new System.Windows.Forms.NumericUpDown(); @@ -68,7 +68,6 @@ this.ZedGraphTimer = new System.Windows.Forms.Timer(this.components); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.label6 = new ArdupilotMega.MyLabel(); - this.contextMenuStrip1.SuspendLayout(); this.MainH.Panel1.SuspendLayout(); this.MainH.Panel2.SuspendLayout(); this.MainH.SuspendLayout(); @@ -87,30 +86,11 @@ this.splitContainer1.Panel1.SuspendLayout(); this.splitContainer1.Panel2.SuspendLayout(); this.splitContainer1.SuspendLayout(); + this.contextMenuStrip1.SuspendLayout(); this.panel1.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).BeginInit(); this.SuspendLayout(); // - // contextMenuStrip1 - // - this.contextMenuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { - this.goHereToolStripMenuItem, - this.pointCameraHereToolStripMenuItem}); - this.contextMenuStrip1.Name = "contextMenuStrip1"; - resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1"); - // - // goHereToolStripMenuItem - // - this.goHereToolStripMenuItem.Name = "goHereToolStripMenuItem"; - resources.ApplyResources(this.goHereToolStripMenuItem, "goHereToolStripMenuItem"); - this.goHereToolStripMenuItem.Click += new System.EventHandler(this.goHereToolStripMenuItem_Click); - // - // pointCameraHereToolStripMenuItem - // - this.pointCameraHereToolStripMenuItem.Name = "pointCameraHereToolStripMenuItem"; - resources.ApplyResources(this.pointCameraHereToolStripMenuItem, "pointCameraHereToolStripMenuItem"); - this.pointCameraHereToolStripMenuItem.Click += new System.EventHandler(this.pointCameraHereToolStripMenuItem_Click); - // // MainH // this.MainH.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; @@ -1118,6 +1098,26 @@ this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown); this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove); // + // contextMenuStrip1 + // + this.contextMenuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { + this.goHereToolStripMenuItem, + this.pointCameraHereToolStripMenuItem}); + this.contextMenuStrip1.Name = "contextMenuStrip1"; + resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1"); + // + // goHereToolStripMenuItem + // + this.goHereToolStripMenuItem.Name = "goHereToolStripMenuItem"; + resources.ApplyResources(this.goHereToolStripMenuItem, "goHereToolStripMenuItem"); + this.goHereToolStripMenuItem.Click += new System.EventHandler(this.goHereToolStripMenuItem_Click); + // + // pointCameraHereToolStripMenuItem + // + this.pointCameraHereToolStripMenuItem.Name = "pointCameraHereToolStripMenuItem"; + resources.ApplyResources(this.pointCameraHereToolStripMenuItem, "pointCameraHereToolStripMenuItem"); + this.pointCameraHereToolStripMenuItem.Click += new System.EventHandler(this.pointCameraHereToolStripMenuItem_Click); + // // panel1 // this.panel1.Controls.Add(this.TXT_lat); @@ -1246,7 +1246,6 @@ this.Load += new System.EventHandler(this.FlightData_Load); this.Resize += new System.EventHandler(this.FlightData_Resize); this.ParentChanged += new System.EventHandler(this.FlightData_ParentChanged); - this.contextMenuStrip1.ResumeLayout(false); this.MainH.Panel1.ResumeLayout(false); this.MainH.Panel2.ResumeLayout(false); this.MainH.ResumeLayout(false); @@ -1266,6 +1265,7 @@ this.splitContainer1.Panel1.ResumeLayout(false); this.splitContainer1.Panel2.ResumeLayout(false); this.splitContainer1.ResumeLayout(false); + this.contextMenuStrip1.ResumeLayout(false); this.panel1.ResumeLayout(false); this.panel1.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).EndInit(); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index 845fa8bfd8..c7658555de 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -117,35 +117,11 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 290, 17 - - - - 174, 22 - - - Fly To Here - - - 174, 22 - - - Point Camera Here - - - 175, 48 - - - contextMenuStrip1 - - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - Fill + 0, 0 @@ -208,7 +184,7 @@ hud1 - hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null SubMainLeft.Panel1 @@ -253,7 +229,7 @@ BUT_joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -283,7 +259,7 @@ BUT_quickmanual - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -313,7 +289,7 @@ BUT_quickrtl - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -343,7 +319,7 @@ BUT_quickauto - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -397,7 +373,7 @@ BUT_setwp - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -448,7 +424,7 @@ BUT_setmode - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -478,7 +454,7 @@ BUT_clear_track - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -529,7 +505,7 @@ BUT_Homealt - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -559,7 +535,7 @@ BUT_RAWSensor - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -589,7 +565,7 @@ BUTrestartmission - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -619,7 +595,7 @@ BUTactiondo - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabActions @@ -673,7 +649,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabGauges @@ -703,7 +679,7 @@ Gheading - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabGauges @@ -733,7 +709,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabGauges @@ -766,7 +742,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabGauges @@ -847,7 +823,7 @@ lbl_logpercent - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabTLogs @@ -898,7 +874,7 @@ BUT_log2kml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabTLogs @@ -949,7 +925,7 @@ BUT_playlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabTLogs @@ -976,7 +952,7 @@ BUT_loadtelem - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1162,7 +1138,7 @@ lbl_winddir - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1192,7 +1168,7 @@ lbl_windvel - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1200,6 +1176,30 @@ 1 + + 290, 17 + + + 174, 22 + + + Fly To Here + + + 174, 22 + + + Point Camera Here + + + 175, 48 + + + contextMenuStrip1 + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + Fill @@ -1427,7 +1427,7 @@ TXT_lat - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null panel1 @@ -1484,7 +1484,7 @@ label1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null panel1 @@ -1514,7 +1514,7 @@ TXT_long - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null panel1 @@ -1544,7 +1544,7 @@ TXT_alt - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null panel1 @@ -1745,7 +1745,7 @@ label6 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null $this @@ -1765,18 +1765,6 @@ 1008, 461 - - goHereToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - pointCameraHereToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - recordHudToAVIToolStripMenuItem @@ -1795,6 +1783,18 @@ System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + goHereToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + pointCameraHereToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + dataGridViewImageColumn1 @@ -1823,6 +1823,6 @@ FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.zh-Hans.resx index c1ea1bb089..b029c7331b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.zh-Hans.resx @@ -123,6 +123,9 @@ + + + @@ -4212,18 +4215,15 @@ + + + - - 停止记录 - - - - 播放/暂停 @@ -4236,12 +4236,6 @@ - - 开始记录 - - - - 遥测记录 @@ -4260,64 +4254,10 @@ - - 80, 13 - - + - - 474, 7 - - - 440, 10 - - - 31, 13 - - - 缩放 - - - - - - 90, 10 - - - 80, 13 - - - - - - 170, 10 - - - 80, 13 - - - - - - 339, 9 - - - 98, 17 - - - 自动平移地图 - - - 250, 9 - - - 74, 17 - - - 舵机调整 - - + @@ -4468,10 +4408,70 @@ - + - + + + + + 80, 13 + + + + + + 474, 7 + + + 440, 10 + + + 31, 13 + + + 缩放 + + + + + + 90, 10 + + + 80, 13 + + + + + + 170, 10 + + + 80, 13 + + + + + + 339, 9 + + + 98, 17 + + + 自动平移地图 + + + 250, 9 + + + 74, 17 + + + 舵机调整 + + diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx index 51ec819c4a..4c3ddace09 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx @@ -186,9 +186,9 @@ 30 - + True - + Command @@ -198,9 +198,9 @@ 150 - + True - + P1 @@ -210,9 +210,9 @@ 40 - + True - + P2 @@ -222,9 +222,9 @@ 40 - + True - + P3 @@ -234,9 +234,9 @@ 40 - + True - + P4 @@ -246,9 +246,9 @@ 40 - + True - + Lat @@ -258,9 +258,9 @@ 40 - + True - + Lon @@ -270,9 +270,9 @@ 40 - + True - + Alt @@ -282,9 +282,9 @@ 40 - + True - + Delete @@ -294,9 +294,9 @@ 50 - + True - + Up @@ -306,9 +306,9 @@ 30 - + True - + Down @@ -1128,9 +1128,9 @@ 42 - + 172, 17 - + Change the current map type @@ -1536,9 +1536,9 @@ Top, Bottom, Left, Right - + 17, 17 - + 167, 22 @@ -1915,9 +1915,9 @@ 1 - + True - + 6, 13 @@ -2107,4 +2107,7 @@ System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + ..\Resources\MAVCmd.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.zh-Hans.resx index 8dbcd27254..909d93387f 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.zh-Hans.resx @@ -767,4 +767,8 @@ + + + ..\Resources\MAVCmd.zh-Hans.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs index db612a34dd..0b7a3993ba 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs @@ -125,6 +125,7 @@ // resources.ApplyResources(this.CHKREV_roll, "CHKREV_roll"); this.CHKREV_roll.Name = "CHKREV_roll"; + this.toolTip1.SetToolTip(this.CHKREV_roll, resources.GetString("CHKREV_roll.ToolTip")); this.CHKREV_roll.UseVisualStyleBackColor = true; this.CHKREV_roll.CheckedChanged += new System.EventHandler(this.CHKREV_roll_CheckedChanged); // @@ -132,6 +133,7 @@ // resources.ApplyResources(this.CHKREV_pitch, "CHKREV_pitch"); this.CHKREV_pitch.Name = "CHKREV_pitch"; + this.toolTip1.SetToolTip(this.CHKREV_pitch, resources.GetString("CHKREV_pitch.ToolTip")); this.CHKREV_pitch.UseVisualStyleBackColor = true; this.CHKREV_pitch.CheckedChanged += new System.EventHandler(this.CHKREV_pitch_CheckedChanged); // @@ -139,11 +141,13 @@ // resources.ApplyResources(this.CHKREV_rudder, "CHKREV_rudder"); this.CHKREV_rudder.Name = "CHKREV_rudder"; + this.toolTip1.SetToolTip(this.CHKREV_rudder, resources.GetString("CHKREV_rudder.ToolTip")); this.CHKREV_rudder.UseVisualStyleBackColor = true; this.CHKREV_rudder.CheckedChanged += new System.EventHandler(this.CHKREV_rudder_CheckedChanged); // // GPSrate // + resources.ApplyResources(this.GPSrate, "GPSrate"); this.GPSrate.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.GPSrate.FormattingEnabled = true; this.GPSrate.Items.AddRange(new object[] { @@ -155,8 +159,8 @@ resources.GetString("GPSrate.Items5"), resources.GetString("GPSrate.Items6"), resources.GetString("GPSrate.Items7")}); - resources.ApplyResources(this.GPSrate, "GPSrate"); this.GPSrate.Name = "GPSrate"; + this.toolTip1.SetToolTip(this.GPSrate, resources.GetString("GPSrate.ToolTip")); this.GPSrate.SelectedIndexChanged += new System.EventHandler(this.GPSrate_SelectedIndexChanged); this.GPSrate.KeyDown += new System.Windows.Forms.KeyEventHandler(this.GPSrate_KeyDown); this.GPSrate.Leave += new System.EventHandler(this.GPSrate_Leave); @@ -165,6 +169,7 @@ // resources.ApplyResources(this.ConnectComPort, "ConnectComPort"); this.ConnectComPort.Name = "ConnectComPort"; + this.toolTip1.SetToolTip(this.ConnectComPort, resources.GetString("ConnectComPort.ToolTip")); this.ConnectComPort.UseVisualStyleBackColor = true; this.ConnectComPort.Click += new System.EventHandler(this.ConnectComPort_Click); // @@ -172,6 +177,7 @@ // resources.ApplyResources(this.OutputLog, "OutputLog"); this.OutputLog.Name = "OutputLog"; + this.toolTip1.SetToolTip(this.OutputLog, resources.GetString("OutputLog.ToolTip")); this.OutputLog.TextChanged += new System.EventHandler(this.OutputLog_TextChanged); // // TXT_roll @@ -179,24 +185,28 @@ resources.ApplyResources(this.TXT_roll, "TXT_roll"); this.TXT_roll.Name = "TXT_roll"; this.TXT_roll.resize = false; + this.toolTip1.SetToolTip(this.TXT_roll, resources.GetString("TXT_roll.ToolTip")); // // TXT_pitch // resources.ApplyResources(this.TXT_pitch, "TXT_pitch"); this.TXT_pitch.Name = "TXT_pitch"; this.TXT_pitch.resize = false; + this.toolTip1.SetToolTip(this.TXT_pitch, resources.GetString("TXT_pitch.ToolTip")); // // TXT_heading // resources.ApplyResources(this.TXT_heading, "TXT_heading"); this.TXT_heading.Name = "TXT_heading"; this.TXT_heading.resize = false; + this.toolTip1.SetToolTip(this.TXT_heading, resources.GetString("TXT_heading.ToolTip")); // // TXT_wpdist // resources.ApplyResources(this.TXT_wpdist, "TXT_wpdist"); this.TXT_wpdist.Name = "TXT_wpdist"; this.TXT_wpdist.resize = false; + this.toolTip1.SetToolTip(this.TXT_wpdist, resources.GetString("TXT_wpdist.ToolTip")); // // currentStateBindingSource // @@ -207,35 +217,41 @@ resources.ApplyResources(this.TXT_bererror, "TXT_bererror"); this.TXT_bererror.Name = "TXT_bererror"; this.TXT_bererror.resize = false; + this.toolTip1.SetToolTip(this.TXT_bererror, resources.GetString("TXT_bererror.ToolTip")); // // TXT_alterror // resources.ApplyResources(this.TXT_alterror, "TXT_alterror"); this.TXT_alterror.Name = "TXT_alterror"; this.TXT_alterror.resize = false; + this.toolTip1.SetToolTip(this.TXT_alterror, resources.GetString("TXT_alterror.ToolTip")); // // TXT_lat // resources.ApplyResources(this.TXT_lat, "TXT_lat"); this.TXT_lat.Name = "TXT_lat"; this.TXT_lat.resize = false; + this.toolTip1.SetToolTip(this.TXT_lat, resources.GetString("TXT_lat.ToolTip")); // // TXT_long // resources.ApplyResources(this.TXT_long, "TXT_long"); this.TXT_long.Name = "TXT_long"; this.TXT_long.resize = false; + this.toolTip1.SetToolTip(this.TXT_long, resources.GetString("TXT_long.ToolTip")); // // TXT_alt // resources.ApplyResources(this.TXT_alt, "TXT_alt"); this.TXT_alt.Name = "TXT_alt"; this.TXT_alt.resize = false; + this.toolTip1.SetToolTip(this.TXT_alt, resources.GetString("TXT_alt.ToolTip")); // // SaveSettings // resources.ApplyResources(this.SaveSettings, "SaveSettings"); this.SaveSettings.Name = "SaveSettings"; + this.toolTip1.SetToolTip(this.SaveSettings, resources.GetString("SaveSettings.ToolTip")); this.SaveSettings.UseVisualStyleBackColor = true; this.SaveSettings.Click += new System.EventHandler(this.SaveSettings_Click); // @@ -262,27 +278,32 @@ resources.ApplyResources(this.TXT_servoroll, "TXT_servoroll"); this.TXT_servoroll.Name = "TXT_servoroll"; this.TXT_servoroll.resize = false; + this.toolTip1.SetToolTip(this.TXT_servoroll, resources.GetString("TXT_servoroll.ToolTip")); // // TXT_servopitch // resources.ApplyResources(this.TXT_servopitch, "TXT_servopitch"); this.TXT_servopitch.Name = "TXT_servopitch"; this.TXT_servopitch.resize = false; + this.toolTip1.SetToolTip(this.TXT_servopitch, resources.GetString("TXT_servopitch.ToolTip")); // // TXT_servorudder // resources.ApplyResources(this.TXT_servorudder, "TXT_servorudder"); this.TXT_servorudder.Name = "TXT_servorudder"; this.TXT_servorudder.resize = false; + this.toolTip1.SetToolTip(this.TXT_servorudder, resources.GetString("TXT_servorudder.ToolTip")); // // TXT_servothrottle // resources.ApplyResources(this.TXT_servothrottle, "TXT_servothrottle"); this.TXT_servothrottle.Name = "TXT_servothrottle"; this.TXT_servothrottle.resize = false; + this.toolTip1.SetToolTip(this.TXT_servothrottle, resources.GetString("TXT_servothrottle.ToolTip")); // // panel1 // + resources.ApplyResources(this.panel1, "panel1"); this.panel1.Controls.Add(this.label4); this.panel1.Controls.Add(this.label3); this.panel1.Controls.Add(this.label2); @@ -290,35 +311,40 @@ this.panel1.Controls.Add(this.TXT_lat); this.panel1.Controls.Add(this.TXT_long); this.panel1.Controls.Add(this.TXT_alt); - resources.ApplyResources(this.panel1, "panel1"); this.panel1.Name = "panel1"; + this.toolTip1.SetToolTip(this.panel1, resources.GetString("panel1.ToolTip")); // // label4 // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; this.label4.resize = false; + this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; this.label3.resize = false; + this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; this.label2.resize = false; + this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // label1 // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; this.label1.resize = false; + this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // panel2 // + resources.ApplyResources(this.panel2, "panel2"); this.panel2.Controls.Add(this.label30); this.panel2.Controls.Add(this.TXT_yaw); this.panel2.Controls.Add(this.label11); @@ -328,65 +354,75 @@ this.panel2.Controls.Add(this.TXT_roll); this.panel2.Controls.Add(this.TXT_pitch); this.panel2.Controls.Add(this.TXT_heading); - resources.ApplyResources(this.panel2, "panel2"); this.panel2.Name = "panel2"; + this.toolTip1.SetToolTip(this.panel2, resources.GetString("panel2.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; this.label30.resize = false; + this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // TXT_yaw // resources.ApplyResources(this.TXT_yaw, "TXT_yaw"); this.TXT_yaw.Name = "TXT_yaw"; this.TXT_yaw.resize = false; + this.toolTip1.SetToolTip(this.TXT_yaw, resources.GetString("TXT_yaw.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; this.label11.resize = false; + this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // label7 // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; this.label7.resize = false; + this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // label6 // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; this.label6.resize = false; + this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // label5 // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; this.label5.resize = false; + this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // label8 // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; this.label8.resize = false; + this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; this.label9.resize = false; + this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; this.label10.resize = false; + this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); // // panel3 // + resources.ApplyResources(this.panel3, "panel3"); this.panel3.Controls.Add(this.label16); this.panel3.Controls.Add(this.label15); this.panel3.Controls.Add(this.label14); @@ -396,41 +432,47 @@ this.panel3.Controls.Add(this.TXT_servopitch); this.panel3.Controls.Add(this.TXT_servorudder); this.panel3.Controls.Add(this.TXT_servothrottle); - resources.ApplyResources(this.panel3, "panel3"); this.panel3.Name = "panel3"; + this.toolTip1.SetToolTip(this.panel3, resources.GetString("panel3.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; this.label16.resize = false; + this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; this.label15.resize = false; + this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; this.label14.resize = false; + this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // label13 // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; this.label13.resize = false; + this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; this.label12.resize = false; + this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // panel4 // + resources.ApplyResources(this.panel4, "panel4"); this.panel4.Controls.Add(this.label20); this.panel4.Controls.Add(this.label19); this.panel4.Controls.Add(this.TXT_control_mode); @@ -442,50 +484,57 @@ this.panel4.Controls.Add(this.TXT_wpdist); this.panel4.Controls.Add(this.TXT_bererror); this.panel4.Controls.Add(this.TXT_alterror); - resources.ApplyResources(this.panel4, "panel4"); this.panel4.Name = "panel4"; + this.toolTip1.SetToolTip(this.panel4, resources.GetString("panel4.ToolTip")); // // label20 // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; this.label20.resize = false; + this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; this.label19.resize = false; + this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip")); // // TXT_control_mode // resources.ApplyResources(this.TXT_control_mode, "TXT_control_mode"); this.TXT_control_mode.Name = "TXT_control_mode"; this.TXT_control_mode.resize = false; + this.toolTip1.SetToolTip(this.TXT_control_mode, resources.GetString("TXT_control_mode.ToolTip")); // // TXT_WP // resources.ApplyResources(this.TXT_WP, "TXT_WP"); this.TXT_WP.Name = "TXT_WP"; this.TXT_WP.resize = false; + this.toolTip1.SetToolTip(this.TXT_WP, resources.GetString("TXT_WP.ToolTip")); // // label18 // resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; this.label18.resize = false; + this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip")); // // label17 // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; this.label17.resize = false; + this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // panel5 // - this.panel5.Controls.Add(this.ConnectComPort); resources.ApplyResources(this.panel5, "panel5"); + this.panel5.Controls.Add(this.ConnectComPort); this.panel5.Name = "panel5"; + this.toolTip1.SetToolTip(this.panel5, resources.GetString("panel5.ToolTip")); // // zg1 // @@ -498,6 +547,7 @@ this.zg1.ScrollMinX = 0D; this.zg1.ScrollMinY = 0D; this.zg1.ScrollMinY2 = 0D; + this.toolTip1.SetToolTip(this.zg1, resources.GetString("zg1.ToolTip")); // // timer1 // @@ -505,6 +555,7 @@ // // panel6 // + resources.ApplyResources(this.panel6, "panel6"); this.panel6.Controls.Add(this.label28); this.panel6.Controls.Add(this.label29); this.panel6.Controls.Add(this.label27); @@ -517,37 +568,42 @@ this.panel6.Controls.Add(this.TXT_ruddergain); this.panel6.Controls.Add(this.TXT_pitchgain); this.panel6.Controls.Add(this.TXT_rollgain); - resources.ApplyResources(this.panel6, "panel6"); this.panel6.Name = "panel6"; + this.toolTip1.SetToolTip(this.panel6, resources.GetString("panel6.ToolTip")); // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; this.label28.resize = false; + this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // label29 // resources.ApplyResources(this.label29, "label29"); this.label29.Name = "label29"; this.label29.resize = false; + this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); // // label27 // resources.ApplyResources(this.label27, "label27"); this.label27.Name = "label27"; this.label27.resize = false; + this.toolTip1.SetToolTip(this.label27, resources.GetString("label27.ToolTip")); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; this.label25.resize = false; + this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); // // TXT_throttlegain // resources.ApplyResources(this.TXT_throttlegain, "TXT_throttlegain"); this.TXT_throttlegain.Name = "TXT_throttlegain"; + this.toolTip1.SetToolTip(this.TXT_throttlegain, resources.GetString("TXT_throttlegain.ToolTip")); this.TXT_throttlegain.TextChanged += new System.EventHandler(this.TXT_throttlegain_TextChanged); // // label24 @@ -555,41 +611,48 @@ resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; this.label24.resize = false; + this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // label23 // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; this.label23.resize = false; + this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; this.label22.resize = false; + this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; this.label21.resize = false; + this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // TXT_ruddergain // resources.ApplyResources(this.TXT_ruddergain, "TXT_ruddergain"); this.TXT_ruddergain.Name = "TXT_ruddergain"; + this.toolTip1.SetToolTip(this.TXT_ruddergain, resources.GetString("TXT_ruddergain.ToolTip")); this.TXT_ruddergain.TextChanged += new System.EventHandler(this.TXT_ruddergain_TextChanged); // // TXT_pitchgain // resources.ApplyResources(this.TXT_pitchgain, "TXT_pitchgain"); this.TXT_pitchgain.Name = "TXT_pitchgain"; + this.toolTip1.SetToolTip(this.TXT_pitchgain, resources.GetString("TXT_pitchgain.ToolTip")); this.TXT_pitchgain.TextChanged += new System.EventHandler(this.TXT_pitchgain_TextChanged); // // TXT_rollgain // resources.ApplyResources(this.TXT_rollgain, "TXT_rollgain"); this.TXT_rollgain.Name = "TXT_rollgain"; + this.toolTip1.SetToolTip(this.TXT_rollgain, resources.GetString("TXT_rollgain.ToolTip")); this.TXT_rollgain.TextChanged += new System.EventHandler(this.TXT_rollgain_TextChanged); // // label26 @@ -597,11 +660,13 @@ resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; this.label26.resize = false; + this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // CHKdisplayall // resources.ApplyResources(this.CHKdisplayall, "CHKdisplayall"); this.CHKdisplayall.Name = "CHKdisplayall"; + this.toolTip1.SetToolTip(this.CHKdisplayall, resources.GetString("CHKdisplayall.ToolTip")); this.CHKdisplayall.UseVisualStyleBackColor = true; this.CHKdisplayall.CheckedChanged += new System.EventHandler(this.CHKdisplayall_CheckedChanged); // @@ -611,6 +676,7 @@ this.CHKgraphroll.Checked = true; this.CHKgraphroll.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphroll.Name = "CHKgraphroll"; + this.toolTip1.SetToolTip(this.CHKgraphroll, resources.GetString("CHKgraphroll.ToolTip")); this.CHKgraphroll.UseVisualStyleBackColor = true; // // CHKgraphpitch @@ -619,6 +685,7 @@ this.CHKgraphpitch.Checked = true; this.CHKgraphpitch.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphpitch.Name = "CHKgraphpitch"; + this.toolTip1.SetToolTip(this.CHKgraphpitch, resources.GetString("CHKgraphpitch.ToolTip")); this.CHKgraphpitch.UseVisualStyleBackColor = true; // // CHKgraphrudder @@ -627,6 +694,7 @@ this.CHKgraphrudder.Checked = true; this.CHKgraphrudder.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphrudder.Name = "CHKgraphrudder"; + this.toolTip1.SetToolTip(this.CHKgraphrudder, resources.GetString("CHKgraphrudder.ToolTip")); this.CHKgraphrudder.UseVisualStyleBackColor = true; // // CHKgraphthrottle @@ -635,12 +703,14 @@ this.CHKgraphthrottle.Checked = true; this.CHKgraphthrottle.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphthrottle.Name = "CHKgraphthrottle"; + this.toolTip1.SetToolTip(this.CHKgraphthrottle, resources.GetString("CHKgraphthrottle.ToolTip")); this.CHKgraphthrottle.UseVisualStyleBackColor = true; // // but_advsettings // resources.ApplyResources(this.but_advsettings, "but_advsettings"); this.but_advsettings.Name = "but_advsettings"; + this.toolTip1.SetToolTip(this.but_advsettings, resources.GetString("but_advsettings.ToolTip")); this.but_advsettings.UseVisualStyleBackColor = true; this.but_advsettings.Click += new System.EventHandler(this.but_advsettings_Click); // @@ -648,12 +718,14 @@ // resources.ApplyResources(this.chkSensor, "chkSensor"); this.chkSensor.Name = "chkSensor"; + this.toolTip1.SetToolTip(this.chkSensor, resources.GetString("chkSensor.ToolTip")); this.chkSensor.UseVisualStyleBackColor = true; // // CHK_quad // resources.ApplyResources(this.CHK_quad, "CHK_quad"); this.CHK_quad.Name = "CHK_quad"; + this.toolTip1.SetToolTip(this.CHK_quad, resources.GetString("CHK_quad.ToolTip")); this.CHK_quad.UseVisualStyleBackColor = true; this.CHK_quad.CheckedChanged += new System.EventHandler(this.CHK_quad_CheckedChanged); // @@ -661,6 +733,7 @@ // resources.ApplyResources(this.BUT_startfgquad, "BUT_startfgquad"); this.BUT_startfgquad.Name = "BUT_startfgquad"; + this.toolTip1.SetToolTip(this.BUT_startfgquad, resources.GetString("BUT_startfgquad.ToolTip")); this.BUT_startfgquad.UseVisualStyleBackColor = true; this.BUT_startfgquad.Click += new System.EventHandler(this.BUT_startfgquad_Click); // @@ -668,6 +741,7 @@ // resources.ApplyResources(this.BUT_startfgplane, "BUT_startfgplane"); this.BUT_startfgplane.Name = "BUT_startfgplane"; + this.toolTip1.SetToolTip(this.BUT_startfgplane, resources.GetString("BUT_startfgplane.ToolTip")); this.BUT_startfgplane.UseVisualStyleBackColor = true; this.BUT_startfgplane.Click += new System.EventHandler(this.BUT_startfgplane_Click); // @@ -675,6 +749,7 @@ // resources.ApplyResources(this.BUT_startxplane, "BUT_startxplane"); this.BUT_startxplane.Name = "BUT_startxplane"; + this.toolTip1.SetToolTip(this.BUT_startxplane, resources.GetString("BUT_startxplane.ToolTip")); this.BUT_startxplane.UseVisualStyleBackColor = true; this.BUT_startxplane.Click += new System.EventHandler(this.BUT_startxplane_Click); // @@ -682,6 +757,7 @@ // resources.ApplyResources(this.CHK_heli, "CHK_heli"); this.CHK_heli.Name = "CHK_heli"; + this.toolTip1.SetToolTip(this.CHK_heli, resources.GetString("CHK_heli.ToolTip")); this.CHK_heli.UseVisualStyleBackColor = true; // // RAD_aerosimrc @@ -727,6 +803,7 @@ this.Controls.Add(this.CHKREV_pitch); this.Controls.Add(this.CHKREV_roll); this.Name = "Simulation"; + this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.Load += new System.EventHandler(this.Simulation_Load); ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); this.panel1.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx index 5d542ad283..8d79ea9ad7 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx @@ -118,1983 +118,2214 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - True - - - - 213, 10 - - - 87, 17 - - - 1 - - - Reverse Roll - - - CHKREV_roll - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 29 - - - True - - - 299, 10 - - - 93, 17 - - - 2 - - - Reverse Pitch - - - CHKREV_pitch - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 28 - - - True - - - 398, 10 - - - 104, 17 - 3 - - Reverse Rudder + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - CHKREV_rudder + + + 45, 13 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + - - $this - - - 27 - - - 100 - - - 200 - - - 250 - - - 333 - - - 500 + + 1000 - - 30000 + + 126, 37 - - 99999 + + FlightGear - - 538, 36 + + 47, 13 - - 92, 21 + + label26 - - 4 - - - GPSrate - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + $this - - 26 - - - 26, 13 - 128, 23 - + + Plane IMU + + + CHKgraphthrottle + + + 24 + + 5 - - Sim Link Start/Stop + + label27 + + + Pitch + + + 25, 13 ConnectComPort - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - panel5 + + 7, 104 - - 0 + + 5 - - Lucida Console, 8.25pt + + 508, 330 - - 197, 66 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 363, 208 + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 6 + + 43 - - - - - OutputLog - - - System.Windows.Forms.RichTextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 25 - - - 67, 22 - - - 100, 20 - - - 7 - - - TXT_roll - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - - 6 - - - 67, 45 - - - 100, 20 - - - 8 - - - TXT_pitch - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - - 7 - - - 67, 70 - - - 100, 20 - - - 9 - - - TXT_heading - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - - 8 - - - 75, 24 - - - 100, 20 - - + 10 - - TXT_wpdist + + 67, 24 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + Roll - - panel4 - - + 8 - - 104, 17 - - - 75, 50 - - - 100, 20 - - - 11 - - - TXT_bererror - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 + + 41 9 - - 75, 76 + + panel1 + + + Reverse Pitch + + + Show Rudder + + + panel2 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 19 + + + panel5 + + + 67, 76 + + + 11 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 7 + + + 538, 36 + + + 75, 74 + + + 500 + + + 39 + + + Start FG Quad + + + 2 + + + 17 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + label22 + + + 6 + + + panel2 + + + 2 + + + 6 + + + 100, 20 + + + $this + + + $this + + + 100, 20 + + + $this + + + X-plane + + + TXT_heading + + + CHKdisplayall + + + label23 + + + toolTip1 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 0 + + + Longitude + + + 4 + + + panel6 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + label28 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 7, 52 + + + + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 68, 13 + + + 64, 34 + + + but_advsettings + + + 7, 78 + + + 17 + + + + Bottom, Left + + + 1 + + + 6 + + + 14 + + + 7, 27 + + + 0 + + + label29 + + + 6 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 2 + + + + + + 73, 17 + + + Can do Plane and Quad with model + + + 99999 + + + + + + Quad + + + panel2 + + + + + + 23 + + + Latitude + + + CHKREV_roll + + + $this + + + 16 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + True + + + Sensor + + + Simulation + + + 1 + + + + + + Reverse Rudder + + + label14 + + + + + + Save Settings + + + Plane GPS + + + 7 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + True + + + label15 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + TXT_servothrottle + + + 110, 709 + + + 566, 66 + + + Show Roll + + + + + + 91, 17 + + + 72, 104 + + + 0 + + + Pitch + + + 67, 102 + + + TXT_bererror + + + 207, 709 + + + 27 + + + BUT_startxplane + + + + + + 16 + + + $this + + + RAD_softFlightGear + + + 2 + + + CHKgraphroll + + + TXT_servorudder + + + 30000 + + + 5 + + + panel2 + + + 40 + + + + + + panel6 + + + panel1 + + + 23 + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + These + + + 74, 17 + + + 2 + + + True + + + Start Xplane + + + 63, 20 + + + + + + $this + + + 0 100, 20 - - 12 + + 7, 78 - - TXT_alterror + + 18 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + 4 - + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + panel3 + + + label11 + + + + + + 19 + + + 0 + + + 13, 709 + + + + + + panel3 + + + Show Pitch + + + 16 + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel3 + + + panel3 + + + 13, 294 + + + $this + + + 22 + + + 27 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 17 + + + label16 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + TXT_rollgain + + + 126, 63 + + + 6, 13 + + + panel3 + + + 213, 10 + + + 23 + + + 100, 20 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + + + + $this + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + label17 + + + $this + + + + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 8 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 566, 368 + + + + + + True + + + 12, 172 + + + $this + + + panel6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 566, 186 + + + True + + + TXT_yaw + + + + + + panel2 + + + + + + 10, 27 + + + panel6 + + + 4 + + + panel6 + + panel4 - + + Throttle + + + 69, 13 + + + label12 + + + TXT_throttlegain + + + 45, 20 + + + 6 + + + Show Throttle + + + 3 + + + 4, 78 + + + label2 + + + + + + panel5 + + + panel1 + + + label6 + + + + + + 44 + + + + + + panel4 + + + 2, 7 + + + Start FG Plane + + + 28, 13 + + + 178, 52 + + + 104, 17 + + + 48, 13 + + + ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 + + + 7 + + 10 + + 37, 13 + + + + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + panel3 + + + System.Windows.Forms.RichTextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 9 + + + Yaw + + + SIM only + + + True + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + panel2 + + + 4 + + + 299, 10 + + + True + + + $this + + + 1 + + + Altitude + + + 30 + + + label19 + + + 8 + + + Yaw + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 67, 45 + + + 5 + + + + + + NoControl + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + panel6 + + + 47 + + + Sim Link Start/Stop + + + $this + + + 25, 13 + + + True + + + + + + True + + + currentStateBindingSource + + + 10, 78 + + + Bottom, Left + + + 36 + + + 1 + + + $this + + + panel1 + + + 92, 21 + + + 7 + + + 304, 709 + + + 22, 13 + + + WPDist + + + 14 + + + 25 + + + 29 + + + WP + + + panel3 + + + 566, 146 + + + panel1 + + + 6 + + + are + + + 4, 52 + + + $this + + + GPS Refresh Rate + + + 7, 52 + + + 43, 13 + + + 178, 100 + + + 0 + + + + + + BUT_startfgquad + + + + + + panel4 + + + 7, 100 + + + 13 + + + 126, 76 + + + 197, 294 + + + 27 + + + 178, 122 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TXT_long + + + 21 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel4 + + + 13 + + + 59, 17 + + + 10000 + + + 100, 20 + + + 100, 20 + + + 45 + + + label25 + + + Heli + + + 50, 13 + + + 52, 17 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 24 + + + 50, 8 + + + panel6 + + + 9 + + + + + + 22 + + + NoControl + + + NoControl + + + 266, 40 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + CHKREV_rudder + + + $this + + + + + + 28 + + + 26 + + + panel6 + + + panel6 + + + 29 + + + 31, 13 + + + 197, 40 + + + Bottom, Left + + + 702, 283 + + + + + + 3 + + + 4, 104 + + + 59, 13 + + + True + + + 19 + + + AeroSimRC + + + + + + 722, 742 + + + 8 + + + 100, 20 + + + panel6 + + + 81, 13 + + + Bottom, Left + + + 10000 + + + 83, 13 + + + 2 + + + 75, 24 + + + 169, 13 + + + 11 + + + panel1 + + + System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + panel6 + + + panel2 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + Display All + + + 25, 13 + + + 56, 13 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + Throttle Gain + + + + 67, 23 100, 20 - - 13 - - - TXT_lat - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 4 - - - 67, 49 - - - 100, 20 - - - 14 - - - TXT_long - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 5 - - - 67, 75 - - - 100, 20 - - - 15 - - - TXT_alt - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 6 - - - 566, 330 - - - 64, 34 - - - 16 - - - Save Settings - - - SaveSettings - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 24 - - - True - - - 197, 40 - - - 61, 17 - - - 17 - - - X-plane - - - 301, 17 - - - Can Do Plane/Quad with plugin - - - RAD_softXplanes - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 23 - - - True - - - 266, 40 - - - 73, 17 - - - 18 - - - FlightGear - - - Can do Plane and Quad with model - - - RAD_softFlightGear - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 22 - - - 67, 24 - - - 100, 20 - - - 19 - - - TXT_servoroll - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 5 - - - 67, 50 - - - 100, 20 - - - 20 - - - TXT_servopitch - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 6 - - - 67, 76 - - - 100, 20 - - - 21 - - - TXT_servorudder - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 7 - - - 67, 102 - - - 100, 20 - - - 22 - - - TXT_servothrottle - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 8 - - - 60, 3 - - - 59, 13 - - - 19 - - - Plane GPS - - - label4 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 0 - - - 7, 78 - - - 42, 13 - - - 18 - - - Altitude - - - label3 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 1 - - - 7, 52 - - - 54, 13 - - - 17 - - - Longitude - - - label2 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 2 - - - 7, 26 - - - 45, 13 - - - 16 - - - Latitude - - - label1 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 3 - - - 13, 66 - - - 178, 100 - - - 23 - - - panel1 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 21 - - - 7, 100 - - - 28, 13 - - - 21 - - - Yaw + + Can do Plane/Heli/Quads label30 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + TXT_pitch - + + 3 + + + 1 + + + TXT_servoroll + + + Reverse Roll + + + Pitch Gain + + + $this + + + 10 + + + 2 + + + 26, 13 + + + 566, 330 + + + Can Do Plane/Quad with plugin + + + 0 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 67, 22 + + + True + + + 7, 29 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 67, 50 + + + 15 + + + 178, 122 + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 95, 13 + + + 3 + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + panel2 - - 0 + + panel4 + + + + + + 3 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 8 + + + 100 + + + NoControl + + + 333 + + + 363, 208 + + + panel1 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 382, 294 + + + 67, 70 + + + 7 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 75, 100 + + + + + + + + + 12 + + + 21 + + + 112, 99 + + + 31, 13 + + + chkSensor + + + 7, 77 + + + 42 + + + 24 + + + RAD_softXplanes + + + TXT_alterror + + + 19 + + + + + + + + + 45, 20 + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + Altitude ERR + + + + + + 178, 116 + + + TXT_servopitch + + + label4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label8 + + + 566, 203 + + + 46 + + + 4 + + + TXT_pitchgain + + + 12 + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null 67, 93 - + + 10, 52 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 44, 17 + + + panel2 + + + + + + GPSrate + + + $this + + + 535, 9 + + + 57, 13 + + + panel2 + + + 31 + + + + + + 9 + + + + + + 54, 13 + + + 100, 20 + + + $this + + + 74, 17 + + + BUT_startfgplane + + + 13, 5 + + + 1 + + + 87, 17 + + + $this + + + $this + + + 6 + + + 25 + + + 67, 13 + + + Roll Gain + + + + + + $this + + + 345, 40 + + 100, 20 20 - - TXT_yaw + + - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + 10000 - - panel2 + + Rudder Gain - - 1 + + Advanced IP Settings - - 60, 4 + + 64, 34 - - 57, 13 + + 75, 48 - - 19 + + Lucida Console, 8.25pt - - Plane IMU + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label11 + + 79, 17 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - - 2 - - - 7, 77 - - - 47, 13 - - - 15 - - - Heading - - - label7 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - + 3 - - 7, 52 - - - 31, 13 - - - 14 - - - Pitch - - - label6 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - - 4 - - - 7, 29 - - - 25, 13 - - - 13 - - - Roll - - - label5 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - - 5 - - - 12, 172 - - - 178, 116 - - - 24 - - - panel2 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 20 - - - 7, 27 - - - 43, 13 - - - 16 - - - WPDist - - - label8 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - - 7 + + panel3 7, 52 - - 69, 13 + + 45, 20 - - 17 + + Heading - - Bearing ERR - - - label9 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - - 6 - - - 7, 78 - - - 68, 13 - - - 18 - - - Altitude ERR - - - label10 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - + 5 - - 50, 8 - - - 83, 13 - - - 27 - - - Ardupilot Output - - - label16 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 0 - - - 10, 104 - - - 43, 13 - - - 26 - - - Throttle - - - label15 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 1 - - - 10, 78 - - - 28, 13 - - - 25 - - - Yaw - - - label14 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 2 - - - 10, 52 - - - 31, 13 - - - 24 - - - Pitch - - - label13 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 3 - - - 10, 27 - - - 25, 13 - - - 23 - - - Roll - - - label12 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel3 - - - 4 - - - 13, 294 - - - 178, 122 - - - 25 - - - panel3 - - + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + 60, 4 - - 19 + + 398, 10 - - 72, 104 + + 9 - - 34, 13 + + - - 23 + + - - Mode - - - label20 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - - 0 - - - 7, 104 - - - 25, 13 - - - 22 - - - WP - - - label19 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - - 1 - - - 112, 99 - - - 63, 20 - - - 21 - - - TXT_control_mode - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - - 2 - - - 38, 98 - - - 28, 20 - - + 20 + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + Top, Bottom, Left, Right + TXT_WP - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + 5 - - panel4 + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 3 + + 64, 34 - - 50, 8 + + NOTE: - - 81, 13 + + 7 - - 19 + + 20 - - Autopilot Status - - - label18 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel4 - - - 4 - - - 197, 294 - - - 178, 122 - - + 26 - - panel4 + + + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label10 + + + 11 + + + 10 + + + + + + 18 + + + 200 + + + 67, 49 + + + TXT_roll + + + 64, 34 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + CHKgraphpitch + + + 19 + + + 68, 13 + + + 26 + + + label1 + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 15 + + + label5 + + + $this + + + True + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + panel1 + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + 75, 23 + + + 566, 219 + + + 21 + + + $this + + + 64, 47 + + + RAD_aerosimrc + + + + + + 75, 76 + + + True + + + 23 + + + 28 + + + 7, 26 + + + 16 + + + + + + 566, 106 + + + TXT_control_mode + + + zg1 + + + 4 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 60, 3 + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + TXT_wpdist + + + 50, 8 + + + 18 + + + True + + + Simulator Authority - For diff planes + + + + + + 75, 50 + + + timer1 + + + 2 + + + label3 + + + panel4 + + + 28, 13 + + + label7 + + + $this + + + + + + 100, 20 + + + 67, 75 + + + Ardupilot Output + + + + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 456, 41 + + + + + + 15 + + + 178, 122 + + + 43, 13 + + + 21 + + + $this + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 197, 66 + + + + + + 10000 + + + 80, 17 + + + panel4 + + + 1 + + + 10, 104 + + + 4, 27 + + + 38, 98 + + + label9 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + $this 18 - - 535, 9 + + 93, 17 - - 95, 13 + + - - 27 + + - - GPS Refresh Rate - - - label17 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 17 - - - 13, 5 - - - 178, 52 - - - 28 - - - panel5 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 16 - - - - Top, Bottom, Left, Right - - - 12, 420 - - - 702, 283 - - - 29 - - - zg1 - - - ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 - - - $this - - - 15 - - - 17, 17 - - - 126, 76 - - - 48, 13 - - - 32 - - - SIM only - - - label28 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 0 - - - 126, 37 - - - 43, 13 - - - 33 - - - NOTE: - - - label29 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 1 - - - 126, 63 - - - 22, 13 - - - 31 - - - are - - - label27 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 2 - - - 4, 104 - - - 68, 13 - - - 8 - - - Throttle Gain - - - label25 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 3 - - - 75, 100 - - - 45, 20 - - - 7 - - - 10000 - - - TXT_throttlegain - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel6 - - + 4 - - 4, 78 + + panel4 - - 67, 13 - - - 6 - - - Rudder Gain - - - label24 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 5 - - - 4, 52 - - - 56, 13 - - - 5 - - - Pitch Gain - - - label23 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 6 - - - 4, 27 - - - 50, 13 - - - 4 - - - Roll Gain - - - label22 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 7 - - - 2, 7 - - - 169, 13 - - - 3 - - - Simulator Authority - For diff planes - - - label21 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel6 - - - 8 - - - 75, 74 - - - 45, 20 - - - 2 - - - 10000 - - - TXT_ruddergain - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel6 - - - 9 - - - 75, 48 - - - 45, 20 - - - 1 - - - 10000 - - - TXT_pitchgain - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel6 - - - 10 - - - 75, 23 - - - 45, 20 - - - 0 - - - 10000 - - - TXT_rollgain - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel6 - - - 11 - - - 382, 294 - - - 178, 122 - - - 30 - - - panel6 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 14 - - - 508, 330 - - - 37, 13 - - - 9 - - - These - - - label26 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 13 - - - True - - - 456, 41 - - - 74, 17 - - - 36 - - - Display All - - - CHKdisplayall - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 12 - - - Bottom, Left - - - True - - - 13, 709 - - - 74, 17 - - - 37 - - - Show Roll - - - CHKgraphroll - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 11 - - - Bottom, Left - - - True - - - 110, 709 - - - 80, 17 - - - 38 - - - Show Pitch - - - CHKgraphpitch - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - - Bottom, Left - - - True - - - 207, 709 - - - 91, 17 - - - 39 - - - Show Rudder - - - CHKgraphrudder - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 9 - - - Bottom, Left - - - True - - - 304, 709 - - - 92, 17 - - - 40 - - - Show Throttle - - - CHKgraphthrottle - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 8 - - - 566, 368 - - - 64, 47 - - - 41 - - - Advanced IP Settings - - - but_advsettings - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 7 - - - True - - - 566, 186 - - - 59, 17 - - - 42 - - - Sensor - - - chkSensor - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - True - - - NoControl - - - 566, 203 - - - 52, 17 - - - 43 - - - Quad - - - CHK_quad - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - NoControl - - - 566, 66 - - - 64, 34 - - - 44 - - - Start FG Quad - - - BUT_startfgquad - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 4 - - - NoControl - - - 566, 106 - - - 64, 34 - - - 45 - - - Start FG Plane - - - BUT_startfgplane - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 3 - - - NoControl - - - 566, 146 - - - 64, 34 - - - 46 - - - Start Xplane - - - BUT_startxplane - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - $this - - - 2 - - - True - - - NoControl - - - 566, 219 - - - 44, 17 - - - 47 - - - Heli + + TXT_alt CHK_heli - + + panel3 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + - + + 28, 20 + + + 22 + + + label24 + + + 42, 13 + + + CHK_quad + + + 25 + + 1 - - True + + - - NoControl + + label13 - - 345, 40 + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 79, 17 + + + + + + + + panel6 + + + 45, 20 + + + 38 + + + CHKgraphrudder + + + 92, 17 + + + label18 + + + 100, 20 + + + 43, 13 + + + TXT_lat + + + 100, 20 + + + 5 + + + panel4 + + + 33 + + + TXT_ruddergain + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + panel4 + + + 17 + + + 250 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 20 + + + 34, 13 + + + + + + + + + + + + CHKREV_pitch 48 - - AeroSimRC + + 6 - - Can do Plane/Heli/Quads + + 100, 20 - - RAD_aerosimrc + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + panel6 - + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + 0 + + + + + 4 + + + Mode + + + 8 + + + 8 + + + SaveSettings + + + 12, 420 + + + 32 + + + panel4 + + + Roll + + + 13, 66 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + label20 + + + 3 + + + + + + Bearing ERR + + + + + + 7 + + + 14 + + + Autopilot Status + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + OutputLog + + + 61, 17 + + + NoControl + + + label21 + + + 37 + + + 13 + + + panel4 + + + 5 + + + 17, 17 + True - - 6, 13 - - - 722, 742 - - - currentStateBindingSource - - - System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - timer1 - - - System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - toolTip1 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Simulation - - - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - + + 301, 17 + + + 104, 17 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.zh-Hans.resx index a80151577c..6261ef00b3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.zh-Hans.resx @@ -178,6 +178,9 @@ 飞机 IMU + + 朝向 + 俯仰 @@ -296,13 +299,13 @@ 31, 13 - 仅在 + 仅 在 - 178, 17 + 77, 17 - 显示所有 (重启程序- 高速 PC) + 显示所有 高级设置 @@ -313,4 +316,25 @@ 传感器 + + 56, 17 + + + 四 轴 + + + 启动 FG 四轴 + + + 启动 FG 固定翼 + + + 启动 Xplane + + + 62, 17 + + + 直升机 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs index 1f30541e5a..955fa8f8ae 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs @@ -190,6 +190,7 @@ // // tabControl1 // + resources.ApplyResources(this.tabControl1, "tabControl1"); this.tabControl1.Controls.Add(this.tabReset); this.tabControl1.Controls.Add(this.tabRadioIn); this.tabControl1.Controls.Add(this.tabModes); @@ -197,16 +198,17 @@ this.tabControl1.Controls.Add(this.tabBattery); this.tabControl1.Controls.Add(this.tabArducopter); this.tabControl1.Controls.Add(this.tabHeli); - resources.ApplyResources(this.tabControl1, "tabControl1"); this.tabControl1.Name = "tabControl1"; this.tabControl1.SelectedIndex = 0; + this.toolTip1.SetToolTip(this.tabControl1, resources.GetString("tabControl1.ToolTip")); this.tabControl1.SelectedIndexChanged += new System.EventHandler(this.tabControl1_SelectedIndexChanged); // // tabReset // - this.tabReset.Controls.Add(this.BUT_reset); resources.ApplyResources(this.tabReset, "tabReset"); + this.tabReset.Controls.Add(this.BUT_reset); this.tabReset.Name = "tabReset"; + this.toolTip1.SetToolTip(this.tabReset, resources.GetString("tabReset.ToolTip")); this.tabReset.UseVisualStyleBackColor = true; // // BUT_reset @@ -214,11 +216,13 @@ resources.ApplyResources(this.BUT_reset, "BUT_reset"); this.BUT_reset.Name = "BUT_reset"; this.BUT_reset.Tag = ""; + this.toolTip1.SetToolTip(this.BUT_reset, resources.GetString("BUT_reset.ToolTip")); this.BUT_reset.UseVisualStyleBackColor = true; this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click); // // tabRadioIn // + resources.ApplyResources(this.tabRadioIn, "tabRadioIn"); this.tabRadioIn.Controls.Add(this.CHK_revch3); this.tabRadioIn.Controls.Add(this.CHK_revch4); this.tabRadioIn.Controls.Add(this.CHK_revch2); @@ -232,14 +236,15 @@ this.tabRadioIn.Controls.Add(this.BARthrottle); this.tabRadioIn.Controls.Add(this.BARyaw); this.tabRadioIn.Controls.Add(this.BARroll); - resources.ApplyResources(this.tabRadioIn, "tabRadioIn"); this.tabRadioIn.Name = "tabRadioIn"; + this.toolTip1.SetToolTip(this.tabRadioIn, resources.GetString("tabRadioIn.ToolTip")); this.tabRadioIn.UseVisualStyleBackColor = true; // // CHK_revch3 // resources.ApplyResources(this.CHK_revch3, "CHK_revch3"); this.CHK_revch3.Name = "CHK_revch3"; + this.toolTip1.SetToolTip(this.CHK_revch3, resources.GetString("CHK_revch3.ToolTip")); this.CHK_revch3.UseVisualStyleBackColor = true; this.CHK_revch3.CheckedChanged += new System.EventHandler(this.CHK_revch3_CheckedChanged); // @@ -247,6 +252,7 @@ // resources.ApplyResources(this.CHK_revch4, "CHK_revch4"); this.CHK_revch4.Name = "CHK_revch4"; + this.toolTip1.SetToolTip(this.CHK_revch4, resources.GetString("CHK_revch4.ToolTip")); this.CHK_revch4.UseVisualStyleBackColor = true; this.CHK_revch4.CheckedChanged += new System.EventHandler(this.CHK_revch4_CheckedChanged); // @@ -254,6 +260,7 @@ // resources.ApplyResources(this.CHK_revch2, "CHK_revch2"); this.CHK_revch2.Name = "CHK_revch2"; + this.toolTip1.SetToolTip(this.CHK_revch2, resources.GetString("CHK_revch2.ToolTip")); this.CHK_revch2.UseVisualStyleBackColor = true; this.CHK_revch2.CheckedChanged += new System.EventHandler(this.CHK_revch2_CheckedChanged); // @@ -261,6 +268,7 @@ // resources.ApplyResources(this.CHK_revch1, "CHK_revch1"); this.CHK_revch1.Name = "CHK_revch1"; + this.toolTip1.SetToolTip(this.CHK_revch1, resources.GetString("CHK_revch1.ToolTip")); this.CHK_revch1.UseVisualStyleBackColor = true; this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged); // @@ -268,21 +276,23 @@ // resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio"); this.BUT_Calibrateradio.Name = "BUT_Calibrateradio"; + this.toolTip1.SetToolTip(this.BUT_Calibrateradio, resources.GetString("BUT_Calibrateradio.ToolTip")); this.BUT_Calibrateradio.UseVisualStyleBackColor = true; this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click); // // BAR8 // + resources.ApplyResources(this.BAR8, "BAR8"); this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true)); this.BAR8.Label = "Radio 8"; - resources.ApplyResources(this.BAR8, "BAR8"); this.BAR8.Maximum = 2200; this.BAR8.maxline = 0; this.BAR8.Minimum = 800; this.BAR8.minline = 0; this.BAR8.Name = "BAR8"; + this.toolTip1.SetToolTip(this.BAR8, resources.GetString("BAR8.ToolTip")); this.BAR8.Value = 1500; this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // @@ -292,111 +302,119 @@ // // BAR7 // + resources.ApplyResources(this.BAR7, "BAR7"); this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true)); this.BAR7.Label = "Radio 7"; - resources.ApplyResources(this.BAR7, "BAR7"); this.BAR7.Maximum = 2200; this.BAR7.maxline = 0; this.BAR7.Minimum = 800; this.BAR7.minline = 0; this.BAR7.Name = "BAR7"; + this.toolTip1.SetToolTip(this.BAR7, resources.GetString("BAR7.ToolTip")); this.BAR7.Value = 1500; this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BAR6 // + resources.ApplyResources(this.BAR6, "BAR6"); this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true)); this.BAR6.Label = "Radio 6"; - resources.ApplyResources(this.BAR6, "BAR6"); this.BAR6.Maximum = 2200; this.BAR6.maxline = 0; this.BAR6.Minimum = 800; this.BAR6.minline = 0; this.BAR6.Name = "BAR6"; + this.toolTip1.SetToolTip(this.BAR6, resources.GetString("BAR6.ToolTip")); this.BAR6.Value = 1500; this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BAR5 // + resources.ApplyResources(this.BAR5, "BAR5"); this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true)); this.BAR5.Label = "Radio 5"; - resources.ApplyResources(this.BAR5, "BAR5"); this.BAR5.Maximum = 2200; this.BAR5.maxline = 0; this.BAR5.Minimum = 800; this.BAR5.minline = 0; this.BAR5.Name = "BAR5"; + this.toolTip1.SetToolTip(this.BAR5, resources.GetString("BAR5.ToolTip")); this.BAR5.Value = 1500; this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BARpitch // + resources.ApplyResources(this.BARpitch, "BARpitch"); this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true)); this.BARpitch.Label = "Pitch"; - resources.ApplyResources(this.BARpitch, "BARpitch"); this.BARpitch.Maximum = 2200; this.BARpitch.maxline = 0; this.BARpitch.Minimum = 800; this.BARpitch.minline = 0; this.BARpitch.Name = "BARpitch"; + this.toolTip1.SetToolTip(this.BARpitch, resources.GetString("BARpitch.ToolTip")); this.BARpitch.Value = 1500; this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BARthrottle // + resources.ApplyResources(this.BARthrottle, "BARthrottle"); this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true)); this.BARthrottle.Label = "Throttle"; - resources.ApplyResources(this.BARthrottle, "BARthrottle"); this.BARthrottle.Maximum = 2200; this.BARthrottle.maxline = 0; this.BARthrottle.Minimum = 800; this.BARthrottle.minline = 0; this.BARthrottle.Name = "BARthrottle"; + this.toolTip1.SetToolTip(this.BARthrottle, resources.GetString("BARthrottle.ToolTip")); this.BARthrottle.Value = 1000; this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); // // BARyaw // + resources.ApplyResources(this.BARyaw, "BARyaw"); this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true)); this.BARyaw.Label = "Yaw"; - resources.ApplyResources(this.BARyaw, "BARyaw"); this.BARyaw.Maximum = 2200; this.BARyaw.maxline = 0; this.BARyaw.Minimum = 800; this.BARyaw.minline = 0; this.BARyaw.Name = "BARyaw"; + this.toolTip1.SetToolTip(this.BARyaw, resources.GetString("BARyaw.ToolTip")); this.BARyaw.Value = 1500; this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BARroll // + resources.ApplyResources(this.BARroll, "BARroll"); this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true)); this.BARroll.Label = "Roll"; - resources.ApplyResources(this.BARroll, "BARroll"); this.BARroll.Maximum = 2200; this.BARroll.maxline = 0; this.BARroll.Minimum = 800; this.BARroll.minline = 0; this.BARroll.Name = "BARroll"; + this.toolTip1.SetToolTip(this.BARroll, resources.GetString("BARroll.ToolTip")); this.BARroll.Value = 1500; this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // tabModes // + resources.ApplyResources(this.tabModes, "tabModes"); this.tabModes.Controls.Add(this.CB_simple6); this.tabModes.Controls.Add(this.CB_simple5); this.tabModes.Controls.Add(this.CB_simple4); @@ -426,190 +444,220 @@ this.tabModes.Controls.Add(this.label1); this.tabModes.Controls.Add(this.CMB_fmode1); this.tabModes.Controls.Add(this.BUT_SaveModes); - resources.ApplyResources(this.tabModes, "tabModes"); this.tabModes.Name = "tabModes"; + this.toolTip1.SetToolTip(this.tabModes, resources.GetString("tabModes.ToolTip")); this.tabModes.UseVisualStyleBackColor = true; // // CB_simple6 // resources.ApplyResources(this.CB_simple6, "CB_simple6"); this.CB_simple6.Name = "CB_simple6"; + this.toolTip1.SetToolTip(this.CB_simple6, resources.GetString("CB_simple6.ToolTip")); this.CB_simple6.UseVisualStyleBackColor = true; // // CB_simple5 // resources.ApplyResources(this.CB_simple5, "CB_simple5"); this.CB_simple5.Name = "CB_simple5"; + this.toolTip1.SetToolTip(this.CB_simple5, resources.GetString("CB_simple5.ToolTip")); this.CB_simple5.UseVisualStyleBackColor = true; // // CB_simple4 // resources.ApplyResources(this.CB_simple4, "CB_simple4"); this.CB_simple4.Name = "CB_simple4"; + this.toolTip1.SetToolTip(this.CB_simple4, resources.GetString("CB_simple4.ToolTip")); this.CB_simple4.UseVisualStyleBackColor = true; // // CB_simple3 // resources.ApplyResources(this.CB_simple3, "CB_simple3"); this.CB_simple3.Name = "CB_simple3"; + this.toolTip1.SetToolTip(this.CB_simple3, resources.GetString("CB_simple3.ToolTip")); this.CB_simple3.UseVisualStyleBackColor = true; // // CB_simple2 // resources.ApplyResources(this.CB_simple2, "CB_simple2"); this.CB_simple2.Name = "CB_simple2"; + this.toolTip1.SetToolTip(this.CB_simple2, resources.GetString("CB_simple2.ToolTip")); this.CB_simple2.UseVisualStyleBackColor = true; // // CB_simple1 // resources.ApplyResources(this.CB_simple1, "CB_simple1"); this.CB_simple1.Name = "CB_simple1"; + this.toolTip1.SetToolTip(this.CB_simple1, resources.GetString("CB_simple1.ToolTip")); this.CB_simple1.UseVisualStyleBackColor = true; // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; + this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // LBL_flightmodepwm // resources.ApplyResources(this.LBL_flightmodepwm, "LBL_flightmodepwm"); this.LBL_flightmodepwm.Name = "LBL_flightmodepwm"; + this.toolTip1.SetToolTip(this.LBL_flightmodepwm, resources.GetString("LBL_flightmodepwm.ToolTip")); // // label13 // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; + this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // lbl_currentmode // resources.ApplyResources(this.lbl_currentmode, "lbl_currentmode"); this.lbl_currentmode.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "mode", true)); this.lbl_currentmode.Name = "lbl_currentmode"; + this.toolTip1.SetToolTip(this.lbl_currentmode, resources.GetString("lbl_currentmode.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; + this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; + this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; + this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; + this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // label8 // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; + this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // label7 // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; + this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // label6 // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; + this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // CMB_fmode6 // + resources.ApplyResources(this.CMB_fmode6, "CMB_fmode6"); this.CMB_fmode6.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode6.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode6.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode6.FormattingEnabled = true; - resources.ApplyResources(this.CMB_fmode6, "CMB_fmode6"); this.CMB_fmode6.Name = "CMB_fmode6"; + this.toolTip1.SetToolTip(this.CMB_fmode6, resources.GetString("CMB_fmode6.ToolTip")); // // label5 // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; + this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // CMB_fmode5 // + resources.ApplyResources(this.CMB_fmode5, "CMB_fmode5"); this.CMB_fmode5.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode5.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode5.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode5.FormattingEnabled = true; - resources.ApplyResources(this.CMB_fmode5, "CMB_fmode5"); this.CMB_fmode5.Name = "CMB_fmode5"; + this.toolTip1.SetToolTip(this.CMB_fmode5, resources.GetString("CMB_fmode5.ToolTip")); // // label4 // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; + this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // CMB_fmode4 // + resources.ApplyResources(this.CMB_fmode4, "CMB_fmode4"); this.CMB_fmode4.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode4.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode4.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode4.FormattingEnabled = true; - resources.ApplyResources(this.CMB_fmode4, "CMB_fmode4"); this.CMB_fmode4.Name = "CMB_fmode4"; + this.toolTip1.SetToolTip(this.CMB_fmode4, resources.GetString("CMB_fmode4.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; + this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // CMB_fmode3 // + resources.ApplyResources(this.CMB_fmode3, "CMB_fmode3"); this.CMB_fmode3.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode3.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode3.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode3.FormattingEnabled = true; - resources.ApplyResources(this.CMB_fmode3, "CMB_fmode3"); this.CMB_fmode3.Name = "CMB_fmode3"; + this.toolTip1.SetToolTip(this.CMB_fmode3, resources.GetString("CMB_fmode3.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; + this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // CMB_fmode2 // + resources.ApplyResources(this.CMB_fmode2, "CMB_fmode2"); this.CMB_fmode2.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode2.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode2.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode2.FormattingEnabled = true; - resources.ApplyResources(this.CMB_fmode2, "CMB_fmode2"); this.CMB_fmode2.Name = "CMB_fmode2"; + this.toolTip1.SetToolTip(this.CMB_fmode2, resources.GetString("CMB_fmode2.ToolTip")); // // label1 // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; + this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // CMB_fmode1 // + resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1"); this.CMB_fmode1.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode1.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode1.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode1.FormattingEnabled = true; - resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1"); this.CMB_fmode1.Name = "CMB_fmode1"; + this.toolTip1.SetToolTip(this.CMB_fmode1, resources.GetString("CMB_fmode1.ToolTip")); // // BUT_SaveModes // resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes"); this.BUT_SaveModes.Name = "BUT_SaveModes"; + this.toolTip1.SetToolTip(this.BUT_SaveModes, resources.GetString("BUT_SaveModes.ToolTip")); this.BUT_SaveModes.UseVisualStyleBackColor = true; this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click); // // tabHardware // + resources.ApplyResources(this.tabHardware, "tabHardware"); this.tabHardware.BackColor = System.Drawing.Color.DarkRed; this.tabHardware.Controls.Add(this.linkLabelmagdec); this.tabHardware.Controls.Add(this.label100); @@ -620,20 +668,22 @@ this.tabHardware.Controls.Add(this.pictureBox4); this.tabHardware.Controls.Add(this.pictureBox3); this.tabHardware.Controls.Add(this.pictureBox1); - resources.ApplyResources(this.tabHardware, "tabHardware"); this.tabHardware.Name = "tabHardware"; + this.toolTip1.SetToolTip(this.tabHardware, resources.GetString("tabHardware.ToolTip")); // // linkLabelmagdec // resources.ApplyResources(this.linkLabelmagdec, "linkLabelmagdec"); this.linkLabelmagdec.Name = "linkLabelmagdec"; this.linkLabelmagdec.TabStop = true; + this.toolTip1.SetToolTip(this.linkLabelmagdec, resources.GetString("linkLabelmagdec.ToolTip")); this.linkLabelmagdec.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked); // // label100 // resources.ApplyResources(this.label100, "label100"); this.label100.Name = "label100"; + this.toolTip1.SetToolTip(this.label100, resources.GetString("label100.ToolTip")); // // TXT_declination // @@ -646,6 +696,7 @@ // resources.ApplyResources(this.CHK_enableairspeed, "CHK_enableairspeed"); this.CHK_enableairspeed.Name = "CHK_enableairspeed"; + this.toolTip1.SetToolTip(this.CHK_enableairspeed, resources.GetString("CHK_enableairspeed.ToolTip")); this.CHK_enableairspeed.UseVisualStyleBackColor = true; this.CHK_enableairspeed.CheckedChanged += new System.EventHandler(this.CHK_enableairspeed_CheckedChanged); // @@ -653,6 +704,7 @@ // resources.ApplyResources(this.CHK_enablesonar, "CHK_enablesonar"); this.CHK_enablesonar.Name = "CHK_enablesonar"; + this.toolTip1.SetToolTip(this.CHK_enablesonar, resources.GetString("CHK_enablesonar.ToolTip")); this.CHK_enablesonar.UseVisualStyleBackColor = true; this.CHK_enablesonar.CheckedChanged += new System.EventHandler(this.CHK_enablesonar_CheckedChanged); // @@ -660,37 +712,42 @@ // resources.ApplyResources(this.CHK_enablecompass, "CHK_enablecompass"); this.CHK_enablecompass.Name = "CHK_enablecompass"; + this.toolTip1.SetToolTip(this.CHK_enablecompass, resources.GetString("CHK_enablecompass.ToolTip")); this.CHK_enablecompass.UseVisualStyleBackColor = true; this.CHK_enablecompass.CheckedChanged += new System.EventHandler(this.CHK_enablecompass_CheckedChanged); // // pictureBox4 // + resources.ApplyResources(this.pictureBox4, "pictureBox4"); this.pictureBox4.BackColor = System.Drawing.Color.White; this.pictureBox4.BackgroundImage = global::ArdupilotMega.Properties.Resources.airspeed; - resources.ApplyResources(this.pictureBox4, "pictureBox4"); this.pictureBox4.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox4.Name = "pictureBox4"; this.pictureBox4.TabStop = false; + this.toolTip1.SetToolTip(this.pictureBox4, resources.GetString("pictureBox4.ToolTip")); // // pictureBox3 // + resources.ApplyResources(this.pictureBox3, "pictureBox3"); this.pictureBox3.BackColor = System.Drawing.Color.White; this.pictureBox3.BackgroundImage = global::ArdupilotMega.Properties.Resources.sonar; - resources.ApplyResources(this.pictureBox3, "pictureBox3"); this.pictureBox3.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox3.Name = "pictureBox3"; this.pictureBox3.TabStop = false; + this.toolTip1.SetToolTip(this.pictureBox3, resources.GetString("pictureBox3.ToolTip")); // // pictureBox1 // - this.pictureBox1.BackgroundImage = global::ArdupilotMega.Properties.Resources.compass; resources.ApplyResources(this.pictureBox1, "pictureBox1"); + this.pictureBox1.BackgroundImage = global::ArdupilotMega.Properties.Resources.compass; this.pictureBox1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox1.Name = "pictureBox1"; this.pictureBox1.TabStop = false; + this.toolTip1.SetToolTip(this.pictureBox1, resources.GetString("pictureBox1.ToolTip")); // // tabBattery // + resources.ApplyResources(this.tabBattery, "tabBattery"); this.tabBattery.Controls.Add(this.TXT_ampspervolt); this.tabBattery.Controls.Add(this.TXT_divider); this.tabBattery.Controls.Add(this.TXT_voltage); @@ -707,14 +764,15 @@ this.tabBattery.Controls.Add(this.TXT_battcapacity); this.tabBattery.Controls.Add(this.CMB_batmontype); this.tabBattery.Controls.Add(this.pictureBox5); - resources.ApplyResources(this.tabBattery, "tabBattery"); this.tabBattery.Name = "tabBattery"; + this.toolTip1.SetToolTip(this.tabBattery, resources.GetString("tabBattery.ToolTip")); this.tabBattery.UseVisualStyleBackColor = true; // // TXT_ampspervolt // resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt"); this.TXT_ampspervolt.Name = "TXT_ampspervolt"; + this.toolTip1.SetToolTip(this.TXT_ampspervolt, resources.GetString("TXT_ampspervolt.ToolTip")); this.TXT_ampspervolt.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_ampspervolt_Validating); this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated); // @@ -722,20 +780,23 @@ // resources.ApplyResources(this.TXT_divider, "TXT_divider"); this.TXT_divider.Name = "TXT_divider"; + this.toolTip1.SetToolTip(this.TXT_divider, resources.GetString("TXT_divider.ToolTip")); this.TXT_divider.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_divider_Validating); this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated); // // TXT_voltage // - this.TXT_voltage.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "battery_voltage", true)); resources.ApplyResources(this.TXT_voltage, "TXT_voltage"); + this.TXT_voltage.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "battery_voltage", true)); this.TXT_voltage.Name = "TXT_voltage"; this.TXT_voltage.ReadOnly = true; + this.toolTip1.SetToolTip(this.TXT_voltage, resources.GetString("TXT_voltage.ToolTip")); // // TXT_measuredvoltage // resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage"); this.TXT_measuredvoltage.Name = "TXT_measuredvoltage"; + this.toolTip1.SetToolTip(this.TXT_measuredvoltage, resources.GetString("TXT_measuredvoltage.ToolTip")); this.TXT_measuredvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_measuredvoltage_Validating); this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated); // @@ -743,6 +804,7 @@ // resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage"); this.TXT_inputvoltage.Name = "TXT_inputvoltage"; + this.toolTip1.SetToolTip(this.TXT_inputvoltage, resources.GetString("TXT_inputvoltage.ToolTip")); this.TXT_inputvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_inputvoltage_Validating); this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated); // @@ -750,52 +812,62 @@ // resources.ApplyResources(this.label35, "label35"); this.label35.Name = "label35"; + this.toolTip1.SetToolTip(this.label35, resources.GetString("label35.ToolTip")); // // label34 // resources.ApplyResources(this.label34, "label34"); this.label34.Name = "label34"; + this.toolTip1.SetToolTip(this.label34, resources.GetString("label34.ToolTip")); // // label33 // resources.ApplyResources(this.label33, "label33"); this.label33.Name = "label33"; + this.toolTip1.SetToolTip(this.label33, resources.GetString("label33.ToolTip")); // // label32 // resources.ApplyResources(this.label32, "label32"); this.label32.Name = "label32"; + this.toolTip1.SetToolTip(this.label32, resources.GetString("label32.ToolTip")); // // label31 // resources.ApplyResources(this.label31, "label31"); this.label31.Name = "label31"; + this.toolTip1.SetToolTip(this.label31, resources.GetString("label31.ToolTip")); // // textBox3 // resources.ApplyResources(this.textBox3, "textBox3"); this.textBox3.Name = "textBox3"; this.textBox3.ReadOnly = true; + this.toolTip1.SetToolTip(this.textBox3, resources.GetString("textBox3.ToolTip")); // // label29 // resources.ApplyResources(this.label29, "label29"); this.label29.Name = "label29"; + this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; + this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // TXT_battcapacity // resources.ApplyResources(this.TXT_battcapacity, "TXT_battcapacity"); this.TXT_battcapacity.Name = "TXT_battcapacity"; + this.toolTip1.SetToolTip(this.TXT_battcapacity, resources.GetString("TXT_battcapacity.ToolTip")); this.TXT_battcapacity.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_battcapacity_Validating); this.TXT_battcapacity.Validated += new System.EventHandler(this.TXT_battcapacity_Validated); // // CMB_batmontype // + resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype"); this.CMB_batmontype.FormattingEnabled = true; this.CMB_batmontype.Items.AddRange(new object[] { resources.GetString("CMB_batmontype.Items"), @@ -803,73 +875,82 @@ resources.GetString("CMB_batmontype.Items2"), resources.GetString("CMB_batmontype.Items3"), resources.GetString("CMB_batmontype.Items4")}); - resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype"); this.CMB_batmontype.Name = "CMB_batmontype"; + this.toolTip1.SetToolTip(this.CMB_batmontype, resources.GetString("CMB_batmontype.ToolTip")); this.CMB_batmontype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmontype_SelectedIndexChanged); // // pictureBox5 // + resources.ApplyResources(this.pictureBox5, "pictureBox5"); this.pictureBox5.BackColor = System.Drawing.Color.White; this.pictureBox5.BackgroundImage = global::ArdupilotMega.Properties.Resources.attocurrent; - resources.ApplyResources(this.pictureBox5, "pictureBox5"); this.pictureBox5.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox5.Name = "pictureBox5"; this.pictureBox5.TabStop = false; + this.toolTip1.SetToolTip(this.pictureBox5, resources.GetString("pictureBox5.ToolTip")); // // tabArducopter // + resources.ApplyResources(this.tabArducopter, "tabArducopter"); this.tabArducopter.Controls.Add(this.label28); this.tabArducopter.Controls.Add(this.label16); this.tabArducopter.Controls.Add(this.label15); this.tabArducopter.Controls.Add(this.pictureBoxQuadX); this.tabArducopter.Controls.Add(this.pictureBoxQuad); this.tabArducopter.Controls.Add(this.BUT_levelac2); - resources.ApplyResources(this.tabArducopter, "tabArducopter"); this.tabArducopter.Name = "tabArducopter"; + this.toolTip1.SetToolTip(this.tabArducopter, resources.GetString("tabArducopter.ToolTip")); this.tabArducopter.UseVisualStyleBackColor = true; // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; + this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; + this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; + this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // pictureBoxQuadX // + resources.ApplyResources(this.pictureBoxQuadX, "pictureBoxQuadX"); this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand; this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.frames_04; - resources.ApplyResources(this.pictureBoxQuadX, "pictureBoxQuadX"); this.pictureBoxQuadX.Name = "pictureBoxQuadX"; this.pictureBoxQuadX.TabStop = false; + this.toolTip1.SetToolTip(this.pictureBoxQuadX, resources.GetString("pictureBoxQuadX.ToolTip")); this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click); // // pictureBoxQuad // + resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad"); this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand; this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.frames_03; - resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad"); this.pictureBoxQuad.Name = "pictureBoxQuad"; this.pictureBoxQuad.TabStop = false; + this.toolTip1.SetToolTip(this.pictureBoxQuad, resources.GetString("pictureBoxQuad.ToolTip")); this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click); // // BUT_levelac2 // resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2"); this.BUT_levelac2.Name = "BUT_levelac2"; + this.toolTip1.SetToolTip(this.BUT_levelac2, resources.GetString("BUT_levelac2.ToolTip")); this.BUT_levelac2.UseVisualStyleBackColor = true; this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click); // // tabHeli // + resources.ApplyResources(this.tabHeli, "tabHeli"); this.tabHeli.Controls.Add(this.groupBox3); this.tabHeli.Controls.Add(this.label44); this.tabHeli.Controls.Add(this.label43); @@ -906,35 +987,39 @@ this.tabHeli.Controls.Add(this.HS4); this.tabHeli.Controls.Add(this.HS3); this.tabHeli.Controls.Add(this.Gservoloc); - resources.ApplyResources(this.tabHeli, "tabHeli"); this.tabHeli.Name = "tabHeli"; + this.toolTip1.SetToolTip(this.tabHeli, resources.GetString("tabHeli.ToolTip")); this.tabHeli.UseVisualStyleBackColor = true; this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click); // // groupBox3 // + resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Controls.Add(this.label46); this.groupBox3.Controls.Add(this.label45); this.groupBox3.Controls.Add(this.GYR_ENABLE_); this.groupBox3.Controls.Add(this.GYR_GAIN_); - resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Name = "groupBox3"; this.groupBox3.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox3, resources.GetString("groupBox3.ToolTip")); // // label46 // resources.ApplyResources(this.label46, "label46"); this.label46.Name = "label46"; + this.toolTip1.SetToolTip(this.label46, resources.GetString("label46.ToolTip")); // // label45 // resources.ApplyResources(this.label45, "label45"); this.label45.Name = "label45"; + this.toolTip1.SetToolTip(this.label45, resources.GetString("label45.ToolTip")); // // GYR_ENABLE_ // resources.ApplyResources(this.GYR_ENABLE_, "GYR_ENABLE_"); this.GYR_ENABLE_.Name = "GYR_ENABLE_"; + this.toolTip1.SetToolTip(this.GYR_ENABLE_, resources.GetString("GYR_ENABLE_.ToolTip")); this.GYR_ENABLE_.UseVisualStyleBackColor = true; this.GYR_ENABLE_.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged); // @@ -942,49 +1027,57 @@ // resources.ApplyResources(this.GYR_GAIN_, "GYR_GAIN_"); this.GYR_GAIN_.Name = "GYR_GAIN_"; + this.toolTip1.SetToolTip(this.GYR_GAIN_, resources.GetString("GYR_GAIN_.ToolTip")); this.GYR_GAIN_.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating); // // label44 // resources.ApplyResources(this.label44, "label44"); this.label44.Name = "label44"; + this.toolTip1.SetToolTip(this.label44, resources.GetString("label44.ToolTip")); // // label43 // resources.ApplyResources(this.label43, "label43"); this.label43.Name = "label43"; + this.toolTip1.SetToolTip(this.label43, resources.GetString("label43.ToolTip")); // // label42 // resources.ApplyResources(this.label42, "label42"); this.label42.Name = "label42"; + this.toolTip1.SetToolTip(this.label42, resources.GetString("label42.ToolTip")); // // BUT_HS4save // resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save"); this.BUT_HS4save.Name = "BUT_HS4save"; + this.toolTip1.SetToolTip(this.BUT_HS4save, resources.GetString("BUT_HS4save.ToolTip")); this.BUT_HS4save.UseVisualStyleBackColor = true; this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click); // // groupBox2 // + resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Controls.Add(this.label24); this.groupBox2.Controls.Add(this.HS4_MIN); this.groupBox2.Controls.Add(this.HS4_MAX); this.groupBox2.Controls.Add(this.label40); - resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Name = "groupBox2"; this.groupBox2.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox2, resources.GetString("groupBox2.ToolTip")); // // label24 // resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; + this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // HS4_MIN // resources.ApplyResources(this.HS4_MIN, "HS4_MIN"); this.HS4_MIN.Name = "HS4_MIN"; + this.toolTip1.SetToolTip(this.HS4_MIN, resources.GetString("HS4_MIN.ToolTip")); this.HS4_MIN.Enter += new System.EventHandler(this.HS4_MIN_Enter); this.HS4_MIN.Leave += new System.EventHandler(this.HS4_MIN_Leave); this.HS4_MIN.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -993,6 +1086,7 @@ // resources.ApplyResources(this.HS4_MAX, "HS4_MAX"); this.HS4_MAX.Name = "HS4_MAX"; + this.toolTip1.SetToolTip(this.HS4_MAX, resources.GetString("HS4_MAX.ToolTip")); this.HS4_MAX.Enter += new System.EventHandler(this.HS4_MAX_Enter); this.HS4_MAX.Leave += new System.EventHandler(this.HS4_MAX_Leave); this.HS4_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1001,40 +1095,46 @@ // resources.ApplyResources(this.label40, "label40"); this.label40.Name = "label40"; + this.toolTip1.SetToolTip(this.label40, resources.GetString("label40.ToolTip")); // // BUT_swash_manual // resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual"); this.BUT_swash_manual.Name = "BUT_swash_manual"; + this.toolTip1.SetToolTip(this.BUT_swash_manual, resources.GetString("BUT_swash_manual.ToolTip")); this.BUT_swash_manual.UseVisualStyleBackColor = true; this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click); // // groupBox1 // + resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Controls.Add(this.label41); this.groupBox1.Controls.Add(this.label21); this.groupBox1.Controls.Add(this.COL_MIN_); this.groupBox1.Controls.Add(this.COL_MID_); this.groupBox1.Controls.Add(this.COL_MAX_); this.groupBox1.Controls.Add(this.BUT_0collective); - resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Name = "groupBox1"; this.groupBox1.TabStop = false; + this.toolTip1.SetToolTip(this.groupBox1, resources.GetString("groupBox1.ToolTip")); // // label41 // resources.ApplyResources(this.label41, "label41"); this.label41.Name = "label41"; + this.toolTip1.SetToolTip(this.label41, resources.GetString("label41.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; + this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // COL_MIN_ // resources.ApplyResources(this.COL_MIN_, "COL_MIN_"); this.COL_MIN_.Name = "COL_MIN_"; + this.toolTip1.SetToolTip(this.COL_MIN_, resources.GetString("COL_MIN_.ToolTip")); this.COL_MIN_.Enter += new System.EventHandler(this.COL_MIN__Enter); this.COL_MIN_.Leave += new System.EventHandler(this.COL_MIN__Leave); this.COL_MIN_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1043,12 +1143,14 @@ // resources.ApplyResources(this.COL_MID_, "COL_MID_"); this.COL_MID_.Name = "COL_MID_"; + this.toolTip1.SetToolTip(this.COL_MID_, resources.GetString("COL_MID_.ToolTip")); this.COL_MID_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); // // COL_MAX_ // resources.ApplyResources(this.COL_MAX_, "COL_MAX_"); this.COL_MAX_.Name = "COL_MAX_"; + this.toolTip1.SetToolTip(this.COL_MAX_, resources.GetString("COL_MAX_.ToolTip")); this.COL_MAX_.Enter += new System.EventHandler(this.COL_MAX__Enter); this.COL_MAX_.Leave += new System.EventHandler(this.COL_MAX__Leave); this.COL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1057,6 +1159,7 @@ // resources.ApplyResources(this.BUT_0collective, "BUT_0collective"); this.BUT_0collective.Name = "BUT_0collective"; + this.toolTip1.SetToolTip(this.BUT_0collective, resources.GetString("BUT_0collective.ToolTip")); this.BUT_0collective.UseVisualStyleBackColor = true; this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click); // @@ -1074,6 +1177,7 @@ 0, 0}); this.HS4_TRIM.Name = "HS4_TRIM"; + this.toolTip1.SetToolTip(this.HS4_TRIM, resources.GetString("HS4_TRIM.ToolTip")); this.HS4_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1095,6 +1199,7 @@ 0, 0}); this.HS3_TRIM.Name = "HS3_TRIM"; + this.toolTip1.SetToolTip(this.HS3_TRIM, resources.GetString("HS3_TRIM.ToolTip")); this.HS3_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1116,6 +1221,7 @@ 0, 0}); this.HS2_TRIM.Name = "HS2_TRIM"; + this.toolTip1.SetToolTip(this.HS2_TRIM, resources.GetString("HS2_TRIM.ToolTip")); this.HS2_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1137,6 +1243,7 @@ 0, 0}); this.HS1_TRIM.Name = "HS1_TRIM"; + this.toolTip1.SetToolTip(this.HS1_TRIM, resources.GetString("HS1_TRIM.ToolTip")); this.HS1_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1148,58 +1255,69 @@ // resources.ApplyResources(this.label39, "label39"); this.label39.Name = "label39"; + this.toolTip1.SetToolTip(this.label39, resources.GetString("label39.ToolTip")); // // label38 // resources.ApplyResources(this.label38, "label38"); this.label38.Name = "label38"; + this.toolTip1.SetToolTip(this.label38, resources.GetString("label38.ToolTip")); // // label37 // resources.ApplyResources(this.label37, "label37"); this.label37.Name = "label37"; + this.toolTip1.SetToolTip(this.label37, resources.GetString("label37.ToolTip")); // // label36 // resources.ApplyResources(this.label36, "label36"); this.label36.Name = "label36"; + this.toolTip1.SetToolTip(this.label36, resources.GetString("label36.ToolTip")); // // label26 // resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; + this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // PIT_MAX_ // resources.ApplyResources(this.PIT_MAX_, "PIT_MAX_"); this.PIT_MAX_.Name = "PIT_MAX_"; + this.toolTip1.SetToolTip(this.PIT_MAX_, resources.GetString("PIT_MAX_.ToolTip")); this.PIT_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; + this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); // // ROL_MAX_ // resources.ApplyResources(this.ROL_MAX_, "ROL_MAX_"); this.ROL_MAX_.Name = "ROL_MAX_"; + this.toolTip1.SetToolTip(this.ROL_MAX_, resources.GetString("ROL_MAX_.ToolTip")); this.ROL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating); // // label23 // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; + this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; + this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // HS4_REV // resources.ApplyResources(this.HS4_REV, "HS4_REV"); this.HS4_REV.Name = "HS4_REV"; + this.toolTip1.SetToolTip(this.HS4_REV, resources.GetString("HS4_REV.ToolTip")); this.HS4_REV.UseVisualStyleBackColor = true; this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged); // @@ -1207,39 +1325,46 @@ // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; + this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; + this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip")); // // label18 // resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; + this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip")); // // SV3_POS_ // resources.ApplyResources(this.SV3_POS_, "SV3_POS_"); this.SV3_POS_.Name = "SV3_POS_"; + this.toolTip1.SetToolTip(this.SV3_POS_, resources.GetString("SV3_POS_.ToolTip")); this.SV3_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating); // // SV2_POS_ // resources.ApplyResources(this.SV2_POS_, "SV2_POS_"); this.SV2_POS_.Name = "SV2_POS_"; + this.toolTip1.SetToolTip(this.SV2_POS_, resources.GetString("SV2_POS_.ToolTip")); this.SV2_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating); // // SV1_POS_ // resources.ApplyResources(this.SV1_POS_, "SV1_POS_"); this.SV1_POS_.Name = "SV1_POS_"; + this.toolTip1.SetToolTip(this.SV1_POS_, resources.GetString("SV1_POS_.ToolTip")); this.SV1_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating); // // HS3_REV // resources.ApplyResources(this.HS3_REV, "HS3_REV"); this.HS3_REV.Name = "HS3_REV"; + this.toolTip1.SetToolTip(this.HS3_REV, resources.GetString("HS3_REV.ToolTip")); this.HS3_REV.UseVisualStyleBackColor = true; this.HS3_REV.CheckedChanged += new System.EventHandler(this.HS3_REV_CheckedChanged); // @@ -1247,6 +1372,7 @@ // resources.ApplyResources(this.HS2_REV, "HS2_REV"); this.HS2_REV.Name = "HS2_REV"; + this.toolTip1.SetToolTip(this.HS2_REV, resources.GetString("HS2_REV.ToolTip")); this.HS2_REV.UseVisualStyleBackColor = true; this.HS2_REV.CheckedChanged += new System.EventHandler(this.HS2_REV_CheckedChanged); // @@ -1254,6 +1380,7 @@ // resources.ApplyResources(this.HS1_REV, "HS1_REV"); this.HS1_REV.Name = "HS1_REV"; + this.toolTip1.SetToolTip(this.HS1_REV, resources.GetString("HS1_REV.ToolTip")); this.HS1_REV.UseVisualStyleBackColor = true; this.HS1_REV.CheckedChanged += new System.EventHandler(this.HS1_REV_CheckedChanged); // @@ -1261,44 +1388,47 @@ // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; + this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // HS4 // + resources.ApplyResources(this.HS4, "HS4"); this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.HS4.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.HS4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true)); this.HS4.Label = "Rudder"; - resources.ApplyResources(this.HS4, "HS4"); this.HS4.Maximum = 2200; this.HS4.maxline = 0; this.HS4.Minimum = 800; this.HS4.minline = 0; this.HS4.Name = "HS4"; + this.toolTip1.SetToolTip(this.HS4, resources.GetString("HS4.ToolTip")); this.HS4.Value = 1500; this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); this.HS4.Paint += new System.Windows.Forms.PaintEventHandler(this.HS4_Paint); // // HS3 // + resources.ApplyResources(this.HS3, "HS3"); this.HS3.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.HS3.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.HS3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true)); this.HS3.Label = "Collective"; - resources.ApplyResources(this.HS3, "HS3"); this.HS3.Maximum = 2200; this.HS3.maxline = 0; this.HS3.Minimum = 800; this.HS3.minline = 0; this.HS3.Name = "HS3"; + this.toolTip1.SetToolTip(this.HS3, resources.GetString("HS3.ToolTip")); this.HS3.Value = 1500; this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); this.HS3.Paint += new System.Windows.Forms.PaintEventHandler(this.HS3_Paint); // // Gservoloc // + resources.ApplyResources(this.Gservoloc, "Gservoloc"); this.Gservoloc.BackColor = System.Drawing.Color.Transparent; this.Gservoloc.BackgroundImage = global::ArdupilotMega.Properties.Resources.Gaugebg; - resources.ApplyResources(this.Gservoloc, "Gservoloc"); this.Gservoloc.BaseArcColor = System.Drawing.Color.Transparent; this.Gservoloc.BaseArcRadius = 60; this.Gservoloc.BaseArcStart = 90; @@ -1431,6 +1561,7 @@ this.Gservoloc.ScaleNumbersRotation = 45; this.Gservoloc.ScaleNumbersStartScaleLine = 2; this.Gservoloc.ScaleNumbersStepScaleLines = 1; + this.toolTip1.SetToolTip(this.Gservoloc, resources.GetString("Gservoloc.ToolTip")); this.Gservoloc.Value = 0F; this.Gservoloc.Value0 = -60F; this.Gservoloc.Value1 = 60F; @@ -1444,6 +1575,7 @@ this.Controls.Add(this.tabControl1); this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow; this.Name = "Setup"; + this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing); this.Load += new System.EventHandler(this.Setup_Load); this.tabControl1.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx index d1d8d1e2a1..db16ceae3d 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx @@ -117,1853 +117,2613 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl + + + 135 - - 214, 161 + + 674, 419 - - 195, 23 + + + 2, 0, 2, 0 - - - 0 + + 94 - - Reset APM Hardware to Default + + 129 - - BUT_reset + + Zero - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabReset - - - 0 - - - 4, 22 - - - 666, 393 - - - 4 - - - Reset - - - tabReset - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 0 - - - True - - - NoControl - - - 287, 158 - - - 66, 17 - - - 106 - - - Reverse - - - CHK_revch3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 0 - - - True - - - NoControl - - - 315, 310 - - - 66, 17 - - - 105 - - - Reverse - - - CHK_revch4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 1 - - - True - - - NoControl - - - 71, 158 - - - 66, 17 - - - 104 - - - Reverse - - - CHK_revch2 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 2 - - - True - - - NoControl - - - 315, 12 - - - 66, 17 - - - 103 - - - Reverse - - - CHK_revch1 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 3 - - - NoControl - - - 482, 340 - - - 134, 23 - - - 102 - - - Calibrate Radio - - - BUT_Calibrateradio - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 4 - - - 17, 17 - - - 446, 240 - - - 170, 25 - - - 101 - - - BAR8 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 5 - - - 446, 185 - - - 170, 25 + + Zoom 100 - - BAR7 + + 24, 13 - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 6 - - - 446, 130 - - - 170, 25 - - - 99 - - - BAR6 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 7 - - - 446, 75 - - + 170, 25 98 - - BAR5 + + - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 8 - - - 143, 61 - - - 47, 211 - - - 96 - - - BARpitch - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 9 - - - 359, 61 - - - 47, 211 - - - 95 - - - BARthrottle - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 10 - - - 21, 304 - - - 288, 23 - - - 94 - - - BARyaw - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 11 - - - 21, 6 - - - 288, 23 - - - 93 - - - BARroll - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabRadioIn - - - 12 - - - 4, 22 - - - 3, 3, 3, 3 - - - 666, 393 - - - 0 - - - Radio Input - - - tabRadioIn - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 1 - - - True - - - NoControl - - - 380, 235 - - - 2, 2, 2, 2 - - - 87, 17 - - - 119 - - - Simple Mode - - - CB_simple6 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 0 - - - True - - - NoControl - - - 380, 208 - - - 2, 2, 2, 2 - - - 87, 17 - - - 118 - - - Simple Mode - - - CB_simple5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 1 - - - True - - - NoControl - - - 380, 181 - - - 2, 2, 2, 2 - - - 87, 17 - - - 117 - - - Simple Mode - - - CB_simple4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 2 - - - True - - - NoControl - - - 380, 154 - - - 2, 2, 2, 2 - - - 87, 17 - - - 116 - - - Simple Mode - - - CB_simple3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 3 - - - True - - - NoControl - - - 380, 127 - - - 2, 2, 2, 2 - - - 87, 17 - - - 115 - - - Simple Mode - - - CB_simple2 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 4 - - - True - - - 380, 100 - - - 2, 2, 2, 2 - - - 87, 17 - - - 114 - - - Simple Mode - - - CB_simple1 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 5 - - - True - - - NoControl - - - 242, 67 - - - 74, 13 - - - 113 - - - Current PWM: - - - label14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 6 - - - True - - - NoControl - - - 322, 67 - - - 13, 13 - - - 112 - - - 0 - - - LBL_flightmodepwm - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 7 - - - True - - - NoControl - - - 242, 50 - - - 74, 13 - - - 111 - - - Current Mode: - - - label13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 8 - - - True - - - NoControl - - - 322, 50 - - - 42, 13 - - - 110 - - - Manual - - - lbl_currentmode - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 9 - - - True - - - NoControl - - - 506, 101 - - - 76, 13 - - - 109 - - - PWM 0 - 1230 - - - False - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 10 - - - True - - - NoControl - - - 506, 236 - - - 70, 13 - - - 108 - - - PWM 1750 + - - - False - - - label11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 11 - - - True - - - NoControl - - - 506, 209 - - - 94, 13 - - - 107 - - - PWM 1621 - 1749 - - - False - - - label10 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 12 - - - True - - - NoControl - - - 506, 182 - - - 94, 13 - - - 106 - - - PWM 1491 - 1620 - - - False - - - label9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes + + 305, 50 13 - - True - - - NoControl - - - 506, 155 - - - 94, 13 - - - 105 - - - PWM 1361 - 1490 - - - False - - - label8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 14 - - - True - - - NoControl - - - 506, 128 - - - 94, 13 - - - 104 - - - PWM 1231 - 1360 - - - False - - - label7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 15 - - - True - - - NoControl - - - 168, 236 - - - 71, 13 - - - 11 - - - Flight Mode 6 - - - label6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 16 - - - 245, 233 - - - 121, 21 - - - 10 - - - CMB_fmode6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 17 - - - True - - - NoControl - - - 168, 209 - - - 71, 13 - - - 9 - - - Flight Mode 5 - - - label5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 18 - - - 245, 206 - - - 121, 21 - - - 8 - - - CMB_fmode5 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 19 - - - True - - - NoControl - - - 168, 182 - - - 71, 13 - - - 7 - - - Flight Mode 4 - - - label4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 20 - - - 245, 179 - - - 121, 21 - - - 6 - - - CMB_fmode4 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 21 - - - True - - - NoControl - - - 168, 155 - - - 71, 13 - - - 5 - - - Flight Mode 3 - - - label3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 22 - - - 245, 152 - - - 121, 21 - - - 4 - - - CMB_fmode3 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 23 - - - True - - - NoControl - - - 168, 128 - - - 71, 13 - - - 3 - - - Flight Mode 2 - - - label2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 24 - - - 245, 125 - - - 121, 21 - - + 2 - - CMB_fmode2 + + label26 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + HS2_TRIM - - tabModes - - - 25 - - - True - - - NoControl - - - 168, 101 - - - 71, 13 - - - 1 - - - Flight Mode 1 - - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 26 - - - 245, 98 - - - 121, 21 - - - 0 - - - CMB_fmode1 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 27 - - - NoControl - - - 245, 260 - - - 121, 23 - - - 103 - - - Save Modes - - - BUT_SaveModes - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabModes - - - 28 - - - 4, 22 - - - 666, 393 - - - 3 - - - Modes - - - tabModes - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 2 - - - True - - - NoControl - - - 390, 80 - - - 104, 13 - - - 28 - - - Declination WebSite - - - linkLabelmagdec - - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 0 - - - NoControl - - - 310, 57 - - - 60, 13 - - - 23 - - - Declination - - - label100 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 1 - - - 383, 57 - - - 121, 20 - - - 20 - - - 214, 17 - - - Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 - - - TXT_declination - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 2 - - - NoControl - - - 162, 214 - - - 103, 17 - - - 24 - - - Enable Airspeed - - - CHK_enableairspeed - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 3 - - - NoControl - - - 159, 136 - - - 90, 17 - - - 25 - - - Enable Sonar - - - CHK_enablesonar - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 4 - - - NoControl - - - 162, 56 - - - 105, 17 - - - 27 - - - Enable Compass - - - CHK_enablecompass - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 5 - - - Zoom - - - NoControl - - - 78, 188 - - - 75, 75 - - - 3 - - - pictureBox4 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 6 - - - Zoom - - - NoControl - - - 78, 106 - - - 75, 75 - - - 2 - - - pictureBox3 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 7 - - - Zoom - - - - - - NoControl - - - - - - 78, 25 - - - 75, 75 - - - 0 - - - pictureBox1 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 8 - - - 4, 22 - - - 3, 3, 3, 3 - - - 666, 393 - - - 1 - - - Hardware - - - tabHardware - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 3 - - - 162, 267 - - - 2, 2, 2, 2 - - - 76, 20 - - - 38 - - - TXT_ampspervolt - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 0 - - - 162, 245 - - - 2, 2, 2, 2 - - - 76, 20 - - - 37 - - - TXT_divider - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 1 - - - 162, 224 - - - 2, 2, 2, 2 - - - 76, 20 - - - 36 - - - TXT_voltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 2 - - - 162, 202 - - - 2, 2, 2, 2 - - - 76, 20 - - - 35 - - - TXT_measuredvoltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 3 - - - 162, 180 - - - 2, 2, 2, 2 - - - 76, 20 - - - 34 - - - TXT_inputvoltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 4 - - - True - - - NoControl - - - 29, 270 - - - 2, 0, 2, 0 - - - 89, 13 - - - 33 - - - Amperes per volt: - - - label35 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 5 - - - True - - - NoControl - - - 28, 248 - - - 2, 0, 2, 0 - - - 80, 13 - - - 32 - - - Voltage divider: - - - label34 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 6 - - - True - - + NoControl 28, 227 + + label3 + + + + + + NoControl + + + 390, 80 + + + CB_simple4 + + + 69, 23 + + + SV1_POS_ + + + NoControl + + + Hardware + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + PWM 1750 + + + + Enable Compass + + + Amperes per volt: + + + tabBattery + + + NoControl + + + True + + + 119 + + + NoControl + + + 2 + + + 15, 14 + + + Flight Mode 6 + + + 13, 13 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + + + + 10 + + + label40 + + + 103, 17 + + + 2 + + + 2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 23, 248 + + + 256, 345 + + + 25 + + + 245, 179 + + + True + + + Manual + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + pictureBox5 + + + 15 + + + NoControl + + + Flight Mode 5 + + + 0 + + + label41 + + + tabModes + + + label7 + + + tabModes + + + 3 + + + + + + tabBattery + + + Swash-Servo position + + + CHK_revch4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + label42 + + + 21 + + + 103 + + + pictureBox4 + + + False + + + TXT_divider + + + 0 + + + label46 + + + 7 + + + 114 + + + + + + groupBox3 + + + tabHardware + + + True + + + 122 + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + 66, 17 + + + label22 + + + 41, 35 + + + 115 + + + Voltage divider: + + + 20 + + + tabBattery + + + 0: Disabled + + + tabHeli + + + tabArducopter + + + 29, 270 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + 5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2, 0, 2, 0 + + + PWM 1361 - 1490 + + + CMB_fmode2 + + + 16 + + + CB_simple2 + + + 506, 155 + + + tabModes + + + NoControl + + + pictureBox1 + + + 162, 180 + + + 93 + + + 14 + + + toolTip1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + Flight Mode 2 + + + 8 + + + + + + label100 + + + tabHardware + + + CHK_enablesonar + + + NoControl + + + 446, 185 + + + 1 + + + 162, 245 + + + HS4_MIN + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 168, 209 + + + 26 + + + + + + tabBattery + + + 94, 13 + + + tabHeli + + + 168, 155 + + + NoControl + + + 106 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 11 + + + tabBattery + + + 4, 22 + + + 1 + + + 87, 17 + + + textBox3 + + + False + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label29 + + + Trim + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 78, 25 + + + + + + tabHeli + + + 48, 13 + + + tabControl1 + 2, 0, 2, 0 - - 81, 13 + + NOTE: images are for presentation only +will work with hexa's etc - - 31 + + 66, 17 - - Battery voltage: + + 2 - - label33 + + Calibrate Radio - + + 2, 2, 2, 2 + + + 5 + + + True + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Flight Mode 1 + + + NoControl + + + 94 + + + True + + + 101, 225 + + + 1 + + + + + + 6 + + + NoControl + + + 380, 154 + + + + + + label14 + + + + + + tabBattery + + + 2, 2, 2, 2 + + + + + + 76, 20 + + + label43 + + + NoControl + + + 315, 310 + + + tabModes + + + Flight Mode 4 + + + + + + True + + + 288, 23 + + + True + + + + + + 13, 13 + + + 2 + + + System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2, 2, 2, 2 + + + True + + + 96 + + + 23 + + + 104 + + + 39, 20 + + + + + + 1500 + + + 2, 2, 2, 2 + + + + + + 134, 23 + + + 256, 321 + + + 104, 13 + + + 76, 20 + + + 37 + + + 2 + + + Current Mode: + + + 121, 23 + + + 42, 13 + + + Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 + + + 3 + + + + + + tabBattery + + + 57, 19 + + + 82 + + + 1 + + + NoControl + + + 71, 13 + + + NoControl + + + 107 + + + 245, 98 + + + tabArducopter + + + True + + + pictureBoxQuad + + + tabArducopter + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 8 + + + 12 + + + + tabBattery + + 10 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + True + + + 25 + + + BUT_Calibrateradio + + + 30 + + + 69, 23 + + + CMB_fmode6 + + + 134 + + + True + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 12 + + + tabBattery + + + NoControl + + + + + + 2 + + + 3 + + + 44, 20 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 43, 20 + + + 11 + + + 6 + + + + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + True + + + + + + 87, 17 + + + NoControl + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 506, 209 + + + 5 + + + + + + 25 + + + True + + + Zoom + + + 90, 17 + + + 28 + + + 108 + + + True + + + 0 + + + 1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Enable Airspeed + + + $this + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + BARthrottle + + + tabHeli + + + 168, 128 + + + 105 + + + + + + -60 + + + 126 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 9 + + + 33 + + + NoControl + + + 32 + + + label16 + + + True + + + 27, 13 + + + NoControl + + + 32 + + + groupBox1 + + + tabBattery + + + 7 + + + tabRadioIn + + + 274, 67 + + + 22 + + + + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + HS3_REV + + + 95 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 105 + + + + + + True + + + groupBox1 + + + 0 + + + 4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label17 + + + 6 + + + 169, 78 + + + 22 + + + + + + CMB_batmontype + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 23 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2, 2, 2, 2 + + + 6 + + + 92 + + + 44, 20 + + + CMB_fmode4 + + + NoControl + + + + + + + + + 93 + + + 78, 106 + + + + + + tabBattery + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + NoControl + + + ROL_MAX_ + + + 18, 45 + + + 43, 20 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 47, 211 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 4, 22 + + + tabRadioIn + + + Gain + + + Min + + + + + + 10 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15, 14 + + + tabHeli + + + tabModes + + + False + + + 110 + + + Zoom + + + 506, 101 + + + 10 + + + tabHeli + + + tabModes + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + HS3_TRIM + + + 43, 20 + + + 83, 20 + + + 118 + + + True + + + 94, 13 + + + TXT_battcapacity + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 91 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 8 + + + 3 + + + Enable + + + True + + + label2 + + + 102 + + + Zoom + + + label6 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 8 + + + tabModes + + + 24, 28 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 8 + + + 42, 13 + + + Swash Travel + + + 210, 13 + + + label13 + + + 121, 21 + + + 9 + + + BAR8 + + + 54, 13 + + + 28 + + + 35 + + + tabArducopter + + + 132 + + + 117 + + + 0 + 7 - + + Monitor + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3 + + + Level your quad to set default accel offsets + + + 19 + + + 6 + + + + + + 3 + + + 162, 56 + + + Reverse + + + 121, 21 + + + 446, 130 + + + 36 + + + 2, 0, 2, 0 + + + 4: Volts & Current + + + tabHeli + + + 24 + + + 106, 40 + + + NoControl + + True - + + 19 + + + 3 + + + True + + + 128 + + + Current PWM: + + + label31 + + + 13 + + + 23 + + + 499, 225 + + + 0 + + + tabBattery + + + 97 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + HS1_TRIM + + + + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + True + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + tabRadioIn + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + tabHeli + + + NoControl + + + 71, 13 + + + 44, 20 + + + 479, 138 + + + tabRadioIn + + + 12 + + + Top + + + + + + currentStateBindingSource + + + 383, 57 + + + 242, 67 + + + 21 + + + CHK_enableairspeed + + + 2 + + + HS1_REV + + + 76, 20 + + + tabModes + + + CHK_enablecompass + + + 132 + + + tabHeli + + + 28 + + + tabHeli + + + tabModes + + + True + + + 101, 248 + + + 29, 13 + + + 14 + + + tabModes + + + Flight Mode 3 + + + 20 + + + NoControl + + + 293, 52 + + + 87, 17 + + + 87, 17 + + + 121, 21 + + + 180 + + + 87, 17 + + + groupBox1 + + + 11 + + + NoControl + + + 131 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2 + + + tabHeli + + + 168, 101 + + + Microsoft Sans Serif, 9pt + + + NoControl + + + Rudder + + + label44 + + + + + + tabModes + + + Zoom + + + 135 + + + 674, 419 + + + 476, 23 + + + 190, 190 + + + 168, 236 + + + 94, 13 + + + 0 + + + 28, 183 + + + groupBox3 + + + Zoom + + + 482, 340 + + + 506, 128 + + + 4, 22 + + + tabModes + + + tabHeli + + + tabHeli + + + 123, 50 + + + 9 + + + 6 + + + PWM 0 - 1230 + + + True + + + 190, 190 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 15, 14 + + + True + + + tabRadioIn + + + 2 + + + True + + + Manual + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Level + + + 666, 393 + + + False + + + 2 + + + 4 + + + 242, 42 + + + CMB_fmode3 + + + 121, 21 + + + True + + + NoControl + + + TXT_measuredvoltage + + + tabHeli + + + tabHeli + + + True + + + 5 + + + 21, 304 + + + 195, 23 + + + Simple Mode + + + 113 + + + 428, 62 + + + tabModes + + + 0 + + + 75, 75 + + + 666, 393 + + + BUT_0collective + + + 5 + + + 111 + + + 235, 52 + + + label34 + + + 4 + + + tabHeli + + + + + + + + + 96 + + + Bottom + + + 359, 61 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 7 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 44, 20 + + + tabHeli + + + label33 + + + + + + 71, 13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 31 + + + 115 + + + Pitch Max + + + 109 + + + 245, 206 + + + label35 + + + True + + + + + + NoControl + + + 87, 17 + + + 112 + + + + + + 101 + + + 26 + + + groupBox2 + + + 106 + + + 71, 13 + + + 118 + + + NoControl + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + True + + + tabModes + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + 5 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 13, 13 + + + True + + + 3 + + + 0, 0 + + NoControl 28, 205 - - 2, 0, 2, 0 + + 192, 26 - - 130, 13 + + 42, 213 - - 30 + + tabModes - - Measured battery voltage: + + NoControl + + + 287, 158 + + + 75, 75 + + + 26, 13 + + + 81 + + + True + + + tabModes + + + NoControl + + + NoControl + + + 0 + + + + + + + + + PWM 1231 - 1360 + + + NoControl + + + NoControl + + + 19, 157 + + + 72, 13 + + + BUT_reset + + + 93 + + + + + + tabControl1 + + + 75, 13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + Radio Input + + + label30 + + + 42, 13 + + + + + + 121, 20 + + + 15 + + + BARyaw + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 150, 150 + + + 125 + + + 177, 46 + + + 105, 17 + + + 76, 20 + + + 18, 173 + + + Rudder Travel + + + 2, 2, 2, 2 + + + GYR_GAIN_ + + + Battery voltage: + + + NoControl + + + 27 + + + Rev + + + 1500 + + + BUT_SaveModes + + + Enable Sonar + + + True + + + 31 + + + 217, 38 + + + 1500 + + + 38 + + + 1 + + + tabModes + + + 130 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label24 + + + 137 + + + + + + 380, 127 + + + 14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + + + + SV2_POS_ + + + + + + 4 + + + label36 + + + + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 27, 23 + + + tabRadioIn + + + 27 + + + 4500 + + + tabHeli + + + CB_simple1 + + + tabHeli + + + True + + + + + + tabArducopter + + + 98 + + + CB_simple5 + + + + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + + + + 2, 2, 2, 2 + + + NoControl + + + + + + 116 + + + True + + + label37 + + + 9 + + + 27, 13 + + + 288, 23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + True + + + NoControl + + + 245, 260 + + + tabBattery + + + + + + 5 + + + HS4_TRIM + + + 16, 50 + + + pictureBox3 + + + 2, 2, 2, 2 + + + 117 + + + tabHardware + + + Servo + + + 8 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + NoControl + + + Simple Mode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + Simple Mode + + + Reset APM Hardware to Default + + + tabHardware + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Simple Mode + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2, 2, 2, 2 + + + Simple Mode + + + 15, 14 + + + 122, 271 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + ArduCopter2 + + + NoControl + + + 71, 13 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 133 + + + Position + + + tabRadioIn + + + + + + + + + 4 + + + NoControl + + + 5 + + + BAR6 + + + 119 + + + 76, 13 + + + NoControl + + + 89, 13 + + + 5 + + + 33 + + + 0 + + + 0 label32 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + - - tabBattery + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 8 + + 3, 3, 3, 3 - + + label23 + + + PWM 1621 - 1749 + + True - + + 114 + + + + + + 58, 23 + + + 127, 206 + + + tabModes + + + lbl_currentmode + + + True + + NoControl - - 28, 183 + + BUT_HS4save - - 2, 0, 2, 0 + + 0 - - 72, 13 + + True - - 29 + + - - Input voltage: + + tabControl1 - - label31 + + groupBox3 + + + BARroll + + + 76, 20 + + + label4 + + + label28 + + + 30 + + + tabHeli + + + 11, 89 + + + label8 + + + 1 + + + + + + CMB_fmode1 + + + NoControl + + + tabBattery + + + 39, 20 + + + COL_MIN_ + + + 162, 214 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + Reverse + + + tabRadioIn + + + 4 + + + + + + tabModes + + + 502, 244 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 5 + + + label38 + + + 122 + + + 89 + + + 20 + + + 133 + + + 13, 206 + + + tabHardware + + + 53, 271 + + + NoControl + + + NoControl + + + tabModes + + + Simple Mode + + + 4 + + + Roll Max + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 5 + + + 38, 23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + label39 + + + 7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tabBattery + + NoControl - - 9 - - - 31, 110 - - - 2, 2, 2, 2 - - + True - - 428, 62 + + - - 28 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + True + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 170, 25 + + + + + + Gservoloc + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + 4500 + + + 7 + + + + + + APMSetup + + + 74, 13 + + + tabHeli Voltage sensor calibration: @@ -1971,1781 +2731,1417 @@ 2. Measure battery voltage and enter it to the box below 3. From current sensor datasheet, enter amperes per volt value to the box below - - textBox3 + + 170, 25 - + + tabModes + + + 232, 23 + + + Reset + + + 3 + + + 446, 75 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tabBattery - - - 10 - - + True - - NoControl - - - 305, 50 - - - 48, 13 - - - 23 - - - Capacity - - - label29 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 11 - - - NoControl - - - 123, 50 - - - 42, 13 - - - 24 - - - Monitor - - - label30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 12 - - - 366, 47 - - - 83, 20 - - - 25 - - - TXT_battcapacity - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 13 - - - 0: Disabled - - - 1: 3 Cell - - - 2: 4 Cell - - - 3: Battery Volts - - - 4: Volts & Current - - - 177, 46 - - - 121, 21 - - - 26 - - - CMB_batmontype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 14 - - - Zoom - - - NoControl - - - 31, 21 - 75, 75 - - 2 + + HS4_MAX - - pictureBox5 + + Save Modes - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 25 - - tabBattery + + - - 15 + + 44, 20 - - 4, 22 + + 6, 13 - - 2, 2, 2, 2 + + - - 666, 393 + + tabHardware - - 6 + + tabHeli - - Battery + + 26 - - tabBattery + + 29 - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tabControl1 + + groupBox1 - - 4 + + 322, 67 - - True + + 446, 240 - - NoControl - - - 217, 38 - - - 210, 13 - - - 9 - - - Level your quad to set default accel offsets - - - label28 - - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tabArducopter + + CHK_revch1 - - 0 + + 245, 233 - - True + + Declination - + + 66, 17 + + NoControl - - 217, 333 - - - 192, 26 - - - 7 - - - NOTE: images are for presentation only -will work with hexa's etc - - - label16 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 1 - - - True - - - NoControl - - - 260, 124 - - - 102, 13 - - - 6 - - - Frame Setup (+ or x) - - - label15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 2 - - - NoControl - - - 319, 140 - - - 190, 190 - - - Zoom - - - 5 - - - pictureBoxQuadX - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Gyro tabArducopter - - 3 + + Measured battery voltage: - + + 0, 0, 0, 0 + + + tabRadioIn + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - 112, 140 + + 134 - - 190, 190 + + tabHeli - - Zoom + + 3: Battery Volts - - 4 + + 2: 4 Cell - - pictureBoxQuad + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 35, 13 - - tabArducopter + + Max - - 4 + + - + + 110 + + NoControl - - 274, 67 + + 1 - - 75, 23 - - - 8 - - - Level - - - BUT_levelac2 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabArducopter - - - 5 - - - 4, 22 - - - 666, 393 - - - 2 - - - ArduCopter2 - - - tabArducopter - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 5 - - + True NoControl - - 6, 38 - - - 29, 13 - - - 137 - - - Gain - - - label46 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 0 - - - True - - - NoControl - - - 6, 19 - - - 40, 13 - - - 136 - - - Enable - - - label45 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 1 - - - True - - - NoControl - - - 57, 19 - - - 15, 14 - - - 118 - - - GYR_ENABLE_ - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 2 - - - 41, 35 - - - 47, 20 - - - 119 - - - 1000 - - - GYR_GAIN_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 3 - - - 433, 271 - - - 101, 63 - - - 135 - - - Gyro - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 0 - - - True - - - NoControl - - - 532, 225 - - - 27, 13 - - - 134 - - - Trim - - - label44 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 1 - - - True - - - NoControl - - - 499, 225 - - - 27, 13 - - - 133 - - - Rev - - - label43 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 2 - - - True - - - 451, 245 - - - 42, 13 - - - 132 - - - Rudder - - - label42 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 3 - - - NoControl - - - 479, 138 - - - 69, 23 - - - 131 - - - Manual - - - BUT_HS4save - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabHeli - - - 4 - - - True - - - NoControl - - - 112, 23 - - - 27, 13 - - - 135 - - - Max - - - label24 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 0 - - - 21, 40 - - - 43, 20 - - - 132 - - - 1500 - - - HS4_MIN - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 1 - - - 106, 40 - - - 43, 20 - - - 133 - - - 1500 - - - HS4_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 2 - - - True - - - NoControl - - - 27, 23 - - - 24, 13 - - - 134 - - - Min - - - label40 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 3 - - - 433, 143 - - - 169, 78 - - - 130 - - - groupBox2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 5 - - - 298, 47 - - - 69, 23 - - - 0 - - - Manual - - - BUT_swash_manual - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabHeli - - - 6 - - - True - - - NoControl - - - 19, 157 - - - 40, 13 - - - 122 - - - Bottom - - - label41 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 0 - - - True - - - 24, 28 - - - 26, 13 - - - 120 - - - Top - - - label21 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 1 - - - 18, 173 - - - 43, 20 - - - 119 - - - 1500 - - - COL_MIN_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 2 - - - 17, 117 - - - 44, 20 - - - 117 - - - 1500 - - - COL_MID_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 3 - - - 18, 45 - - - 43, 20 - - - 115 - - - 1500 - - - COL_MAX_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 4 - - - NoControl - - - 11, 89 - - - 58, 23 - - - 110 - - - Zero - - - BUT_0collective - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - groupBox1 - - - 5 - - - 293, 52 - - - 80, 209 - - - 129 - - - groupBox1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 7 - - - 535, 241 - - - 44, 20 - - - 128 - - - HS4_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 8 - - - 122, 271 - - - 44, 20 - - - 127 - - - HS3_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 9 - - - 122, 245 - - - 44, 20 - - - 126 - - - HS2_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 10 - - - 122, 219 - - - 44, 20 - - - 125 - - - HS1_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 11 - - - True - - - NoControl - - - 127, 206 - - - 27, 13 - - - 124 - - - Trim - - - label39 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 12 - - - True - - - NoControl - - - 98, 206 - - - 27, 13 - - - 123 + + Rev - - label38 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 13 - - - True - - - NoControl - - - 50, 206 - - - 44, 13 - - - 122 - - - Position - - - label37 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 14 - - - True - - - NoControl - - - 13, 206 - - - 35, 13 - - - 121 - - - Servo - - - label36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 15 - - - True - - - NoControl - - - 256, 345 - - - 54, 13 - - - 117 - - - Pitch Max - - - label26 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 16 - - - 310, 342 - - - 47, 20 - - - 116 - - - 4500 - - - PIT_MAX_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 17 - - - True - - - NoControl - - - 256, 321 - - - 48, 13 - - - 115 - - - Roll Max - - - label25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 18 - - - 310, 316 - - - 47, 20 - - - 114 - - - 4500 - - - ROL_MAX_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 19 - - - True - - - NoControl - - - 476, 23 - - - 75, 13 - - - 109 - - - Rudder Travel - - - label23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 20 - - - True - - - NoControl - - - 232, 23 - - - 72, 13 - - - 101 - - - Swash Travel - - - label22 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 21 - - - True - - - NoControl - - - 502, 244 - - - 15, 14 - - - 98 - - - HS4_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 22 - - - True - - - NoControl - - - 23, 274 - - - 13, 13 - - - 97 - - - 3 - - - label20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 23 - - - True - - - NoControl - - - 23, 248 - - - 13, 13 - - - 96 - - - 2 - - - label19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 24 - - - True - - - NoControl - - - 23, 222 - - - 13, 13 - - - 95 - - - 1 - - - label18 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 25 - - - 53, 271 - - - 39, 20 - - - 94 - - - 180 - - - SV3_POS_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 26 - - - 53, 245 - - - 39, 20 - - - 93 - - - 60 - - - SV2_POS_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 27 - - - 53, 219 - - - 39, 20 - - - 92 - - - -60 - - - SV1_POS_ - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 28 - - - True - - - NoControl - - - 101, 274 - - - 15, 14 - - - 91 - - - HS3_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 29 - - - True - - - NoControl - - - 101, 248 - - - 15, 14 - - - 90 - - - HS2_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 30 - - - True - - - NoControl - - - 101, 225 - - - 15, 14 - - - 89 - - - HS1_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 31 - - - True + + Zoom NoControl - - 38, 23 + + True - - 109, 13 + + 31, 110 - - 82 + + 15, 14 - - Swash-Servo position + + NoControl - - label17 + + 121, 21 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 32 - - - 392, 50 - - - 242, 42 - - - 108 - - - HS4 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabHeli - - - 33 - - - 235, 52 - - - 42, 213 - - - 107 - - - HS3 - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabHeli - - - 34 - - - Zoom - - - Microsoft Sans Serif, 9pt - - - 16, 50 - - - 0, 0, 0, 0 - - - 150, 150 - - - 81 - - - Gservoloc - - - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - tabHeli - - - 35 - - - 4, 22 - - - 666, 393 - - - 5 - - - AC2 Heli - - - tabHeli - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 6 - - - Fill - - - 0, 0 - - - 674, 419 - - - 93 - - - tabControl1 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - + 0 - + + 170, 25 + + True - - - 6, 13 - - 674, 419 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - APMSetup + + linkLabelmagdec - - currentStateBindingSource + + 136 + + + 506, 182 + + + + + + pictureBoxQuadX + + + True + + + tabBattery + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 214, 161 + + + + + + + + + 506, 236 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 119 + + + + + + 98, 206 + + + True + + + + + + 6, 19 + + + tabRadioIn System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - toolTip1 + + 1 - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 666, 393 + + + 380, 100 + + + tabHeli + + + Fill + + + COL_MID_ + + + NoControl + + + HS4 + + + 108 + + + 4, 22 + + + 18 + + + Battery + + + Reverse + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 21, 6 + + + + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 122, 219 + + + NoControl + + + 27, 13 + + + 380, 181 + + + PIT_MAX_ + + + 451, 245 + + + Capacity + + + label15 + + + HS4_REV + + + 162, 202 + + + HS2_REV + + + True + + + 112, 140 + + + + + + HS3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 2, 2, 2, 2 + + + Reverse + + + 366, 47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 107 + + + 245, 152 + + + + + + + + + TXT_voltage + + + 53, 219 + + + SV3_POS_ + + + NoControl + + + 4 + + + 8 + + + 44, 13 + + + NoControl + + + tabBattery + + + NoControl + + + 34 + + + 117 + + + NoControl + + + 60, 13 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 6, 38 + + + 48, 13 + + + tabHeli + + + + + + 6 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + True + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + BUT_levelac2 + + + 2 + + + + + + Modes + + + Trim + + + tabHardware + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 666, 393 + + + label9 + + + + + + tabHardware + + + tabModes + + + 2, 2, 2, 2 + + + BARpitch + + + + + + TXT_inputvoltage + + + 4, 22 + + + 28 + + + 666, 393 + + + tabReset + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 15 + + + 11 + + + 109 + + + True + + + + + + 109, 13 + + + label10 + + + 2 + + + True + + + tabControl1 + + + 1 + + + 310, 316 + + + 122, 245 + + + 9 + + + 11 + + + True + + + 80, 209 + + + 78, 188 + + + label1 + + + tabControl1 + + + NoControl + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 27 + + + + + + 66, 17 + + + True + + + label11 + + + 242, 50 + + + 130, 13 + + + 380, 235 + + + tabHeli + + + 4 + + + tabHeli + + + tabHeli + + + BAR5 + + + tabHeli + + + tabModes + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + BAR7 + + + 3 + + + 535, 241 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + BUT_swash_manual + + + True + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 1000 + + + 40, 13 + + + tabModes + + + 23, 222 + + + NoControl + + + 47, 20 + + + 217, 333 + + + tabReset + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 162, 224 + + + NoControl + + + 4, 22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + CHK_revch2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 3, 3, 3, 3 + + + 24 + + + 121 + + + 101, 63 + + + 2 + + + 94, 13 + + + 168, 182 + + + 43, 20 + + + label5 + + + 50, 206 + + + True + + + 3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 24 + + + 47, 20 + + + + + + 10 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + LBL_flightmodepwm + + + True + + + NoControl + + + + + + + + + CB_simple3 + + + 75, 23 + + + + + + 116 + + + tabHeli + + + TXT_ampspervolt + + + 34 + + + tabModes + + + 666, 393 + + + 72, 13 + + + + + + CB_simple6 + + + + + + 115 + + + groupBox3 + + + 47, 211 + + + True + + + NoControl + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 245, 125 + + + 319, 140 + + + + + + 28, 248 + + + NoControl + + + 27, 13 + + + 35 + + + 315, 12 + + + + + + True + + + GYR_ENABLE_ + + + 81, 13 + + + True + + + 74, 13 + + + tabModes + + + 143, 61 + + + 80, 13 + + + NoControl + + + 433, 143 + + + + + + 21, 40 + + + 121, 21 + + + NoControl + + + TXT_declination + + + + + + tabControl1 + + + 71, 158 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 0 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + CHK_revch3 + + + + + + + + + 2, 2, 2, 2 + + + 127 + + + 3 + + + tabHeli + + + 6 + + + 104 + + + 99 + + + 2, 0, 2, 0 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + tabControl1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 310, 342 + + + 7 + + + 6 + + + tabHeli + + + label18 + + + 159, 136 + + + tabControl1 + + + AC2 Heli + + + 18 + + + + + + True + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 124 + + + + + + 1500 + + + + + + 121, 21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + + + + + + + NoControl + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 310, 57 + + + tabArducopter + + + 17, 117 + + + NoControl + + + Manual Setup - - System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 4 + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + + + 120 + + + tabModes + + + 2, 2, 2, 2 + + + 70, 13 + + + True + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 102, 13 + + + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 40, 13 + + + 666, 393 + + + 101, 274 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 123 + + + tabModes + + + 433, 271 + + + + + + Frame Setup (+ or x) + + + 1 + + + 103 + + + + + + Input voltage: + + + False + + + 17 + + + + + + tabRadioIn + + + 90 + + + + + + label19 + + + True + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + + + + 29 + + + + + + 322, 50 + + + CMB_fmode5 + + + + + + 0 + + + 75, 75 + + + 162, 267 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + True + + + NoControl + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 23 + + + + + + 101 + + + + + + 3 + + + tabHeli + + + tabBattery + + + 39, 20 + + + True + + + groupBox1 + + + 31, 21 + + + 112, 23 + + + 24 + + + 532, 225 + + + 9 + + + groupBox2 + + + 392, 50 + + + 298, 47 + + + 13, 13 + + + 60 + + + + + + NoControl + + + + + + + + + + + + label20 + + + 1 + + + 95 + + + tabHardware + + + tabHeli + + + COL_MAX_ + + + PWM 1491 - 1620 + + + + + + + + + 260, 124 + + + groupBox1 + + + Declination WebSite + + + label45 + + + 4 + + + False + + + 1 + + + 4, 22 + + + + + + 47, 20 + + + 13 + + + 0 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + 23, 274 + + + 27, 13 + + + label21 + + + 380, 208 + + + NoControl + + + 16 + + + 53, 245 + + + 1500 + + + 1: 3 Cell + + + tabHeli + + + 17 + + + 71, 13 + + + + + + True + + + 17, 17 + + + 214, 17 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.zh-Hans.resx index 4adc23f290..bd40c7f669 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.zh-Hans.resx @@ -117,12 +117,24 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 重置 APM 为默认设置 - 重置 + + 遥控输入 + + + 模式 + + + 硬件 + + + 电池 + + + 重置 APM 为默认设置 + 50, 17 @@ -151,8 +163,41 @@ 校准遥控 - - 遥控输入 + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 64, 13 @@ -205,21 +250,12 @@ 保存模式 - - 模式 - 67, 13 磁偏角网站 - - 容量 - - - 监视器 - 磁偏角 @@ -229,14 +265,56 @@ 启用声纳 - - 启用电池监视器 - 启用罗盘 - - 硬件 + + 63, 13 + + + 安培/伏特: + + + 52, 13 + + + 分 压 比: + + + 58, 13 + + + 电池电压: + + + 94, 13 + + + 测量的电池电压: + + + 58, 13 + + + 输入电压: + + + 电压传感器校准: +1. 测量APM输入电压,输入到下方的文本框中 +2. 测量电池电压,输入到下方的文本框中 +3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中 + + + 31, 13 + + + 容量 + + + 48, 13 + + + 监控器 175, 13 @@ -244,9 +322,6 @@ 设置水平面的默认加速度计偏移 - - 找平 - 261, 13 @@ -259,17 +334,95 @@ 机架设置 (+ 或 x) - - 67, 13 + + 找平 - - 陀螺仪感度 + + 31, 13 - - 86, 17 + + 感度 - - 启用陀螺仪 + + 31, 13 + + + 启用 + + + 31, 13 + + + 微调 + + + 31, 13 + + + 逆转 + + + 43, 13 + + + 方向舵 + + + 手动 + + + 31, 13 + + + 最大 + + + 31, 13 + + + 最小 + + + 手动 + + + 31, 13 + + + 最低 + + + 31, 13 + + + 最高 + + + 0度 + + + 31, 13 + + + 微调 + + + 31, 13 + + + 逆转 + + + 31, 13 + + + 位置 + + + 31, 13 + + + 舵机 55, 13 @@ -283,12 +436,6 @@ 最大侧倾 - - 55, 13 - - - 0 总螺距: - 55, 13 @@ -301,66 +448,12 @@ 斜盘水平微调 - - 55, 13 - - - 逆转舵机 - - - 59, 17 - - - 逆转 4 - - - 40, 13 - - - 舵机 3 - - - 40, 13 - - - 舵机 2 - - - 40, 13 - - - 舵机 1 - - - 59, 17 - - - 逆转 3 - - - 59, 17 - - - 逆转 2 - - - 59, 17 - - - 逆转 1 - 79, 13 斜盘舵机位置 - - 保存行程 - - - 设置0总螺距 - APM设置 From 96bd7ba480a7039001c5d419cd549c2385ae161a Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 22 Nov 2011 08:32:11 +0800 Subject: [PATCH 58/63] APM Planner 1.0.96 small tweaks Move to .net 4.0 (make sure you have .net 4 installed) - for ironpython --- Tools/ArdupilotMegaPlanner/ArduinoDetect.cs | 4 +- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 32 +- .../ArdupilotMega.csproj.user | 3 + Tools/ArdupilotMegaPlanner/Common.cs | 14 +- .../GCSViews/Configuration.Designer.cs | 700 +- .../GCSViews/Configuration.resx | 12688 ++++++++-------- .../ArdupilotMegaPlanner/GCSViews/Firmware.cs | 4 +- .../GCSViews/FlightData.Designer.cs | 50 +- .../GCSViews/FlightData.cs | 2 +- .../GCSViews/FlightData.resx | 130 +- .../GCSViews/FlightPlanner.Designer.cs | 11 + .../GCSViews/FlightPlanner.cs | 37 + .../GCSViews/FlightPlanner.resx | 169 +- .../GCSViews/Simulation.Designer.cs | 91 +- .../GCSViews/Simulation.resx | 3827 +++-- Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs | 5 + Tools/ArdupilotMegaPlanner/MAVLink.cs | 12 +- Tools/ArdupilotMegaPlanner/MainV2.cs | 45 +- Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 9 +- .../Properties/AssemblyInfo.cs | 2 +- .../Properties/Resources.Designer.cs | 2 +- Tools/ArdupilotMegaPlanner/Script.cs | 36 + .../Setup/Setup.Designer.cs | 204 +- Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 4 +- Tools/ArdupilotMegaPlanner/Setup/Setup.resx | 7150 ++++----- Tools/ArdupilotMegaPlanner/app.config | 6 +- .../Release/ArdupilotMegaPlanner.application | 7 +- .../Release/ArdupilotMegaPlanner.exe.config | 6 +- .../bin/Release/GCSViews/FlightPlanner.resx | 110 +- .../bin/Release/dataflashlog.xml | 260 +- .../bin/Release/mavcmd.xml | 532 +- Tools/ArdupilotMegaPlanner/dataflashlog.xml | 260 +- Tools/ArdupilotMegaPlanner/hires.cs | 48 + Tools/ArdupilotMegaPlanner/mavcmd.xml | 532 +- Tools/ArdupilotMegaPlanner/mykey.snk | Bin 0 -> 596 bytes 35 files changed, 13051 insertions(+), 13941 deletions(-) create mode 100644 Tools/ArdupilotMegaPlanner/Script.cs create mode 100644 Tools/ArdupilotMegaPlanner/hires.cs create mode 100644 Tools/ArdupilotMegaPlanner/mykey.snk diff --git a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs b/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs index 7b70d4036d..675eb7d885 100644 --- a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs +++ b/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs @@ -56,7 +56,7 @@ namespace ArdupilotMega System.Threading.Thread.Sleep(500); //HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters - if (!MainV2.MAC) + if (!MainV2.MONO) { ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice"); ManagementObjectSearcher searcher = new ManagementObjectSearcher(query); @@ -66,7 +66,7 @@ namespace ArdupilotMega if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010")) { - return "2560-2"; + //return "2560-2"; } } } diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 1dcf908aa2..54daa67bad 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -10,7 +10,7 @@ Properties ArdupilotMega ArdupilotMegaPlanner - v3.5 + v4.0 512 @@ -57,7 +57,7 @@ full true bin\Release\ - DEBUG;TRACE;MAVLINK10cra + TRACE;DEBUG;MAVLINK10cra prompt 4 false @@ -92,7 +92,7 @@ - mykey.pfx + mykey.snk @@ -134,6 +134,17 @@ ..\..\..\..\..\Desktop\DIYDrones\SrcSamples\bin\ICSharpCode.SharpZipLib.dll + + False + ..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython.dll + True + False + + + False + ..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython.Modules.dll + True + ..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\KMLib.dll @@ -147,6 +158,16 @@ ..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.DirectInput.dll False + + False + ..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\Microsoft.Dynamic.dll + True + + + False + ..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\Microsoft.Scripting.dll + True + False ..\..\..\..\..\Desktop\DIYDrones\opentk\trunk\Binaries\OpenTK\Release\OpenTK.dll @@ -203,6 +224,7 @@ + Form @@ -329,6 +351,7 @@ + Form @@ -523,7 +546,7 @@ - + @@ -621,7 +644,6 @@ - rem macos.bat diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user index 08b4166df5..8317d5613c 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user @@ -10,4 +10,7 @@ + + C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Release\ + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index c4d16bbab8..8823c2ea03 100644 --- a/Tools/ArdupilotMegaPlanner/Common.cs +++ b/Tools/ArdupilotMegaPlanner/Common.cs @@ -140,6 +140,9 @@ namespace ArdupilotMega public class GMapMarkerQuad : GMapMarker { + const float rad2deg = (float)(180 / Math.PI); + const float deg2rad = (float)(1.0 / rad2deg); + static readonly System.Drawing.Size SizeSt = new System.Drawing.Size(global::ArdupilotMega.Properties.Resources.quad2.Width, global::ArdupilotMega.Properties.Resources.quad2.Height); float heading = 0; float cog = -1; @@ -158,8 +161,17 @@ namespace ArdupilotMega { Matrix temp = g.Transform; g.TranslateTransform(LocalPosition.X, LocalPosition.Y); + + int length = 500; + + g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length); + //g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length); + g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length); + g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length); + + g.RotateTransform(heading); - g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quad2, global::ArdupilotMega.Properties.Resources.quad2.Width / -2, global::ArdupilotMega.Properties.Resources.quad2.Height / -2); + g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quad2, global::ArdupilotMega.Properties.Resources.quad2.Width / -2 + 2, global::ArdupilotMega.Properties.Resources.quad2.Height / -2); g.Transform = temp; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs index 5ce6f0e836..890821ed41 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs @@ -141,13 +141,6 @@ this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown(); this.label52 = new System.Windows.Forms.Label(); this.TabAC2 = new System.Windows.Forms.TabPage(); - this.groupBox17 = new System.Windows.Forms.GroupBox(); - this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown(); - this.label27 = new System.Windows.Forms.Label(); - this.ACRO_PIT_I = new System.Windows.Forms.NumericUpDown(); - this.label29 = new System.Windows.Forms.Label(); - this.ACRO_PIT_P = new System.Windows.Forms.NumericUpDown(); - this.label33 = new System.Windows.Forms.Label(); this.groupBox5 = new System.Windows.Forms.GroupBox(); this.label14 = new System.Windows.Forms.Label(); this.THR_RATE_IMAX = new System.Windows.Forms.NumericUpDown(); @@ -155,13 +148,6 @@ this.label20 = new System.Windows.Forms.Label(); this.THR_RATE_P = new System.Windows.Forms.NumericUpDown(); this.label25 = new System.Windows.Forms.Label(); - this.groupBox18 = new System.Windows.Forms.GroupBox(); - this.ACRO_RLL_IMAX = new System.Windows.Forms.NumericUpDown(); - this.label40 = new System.Windows.Forms.Label(); - this.ACRO_RLL_I = new System.Windows.Forms.NumericUpDown(); - this.label44 = new System.Windows.Forms.Label(); - this.ACRO_RLL_P = new System.Windows.Forms.NumericUpDown(); - this.label48 = new System.Windows.Forms.Label(); this.CHK_lockrollpitch = new System.Windows.Forms.CheckBox(); this.groupBox4 = new System.Windows.Forms.GroupBox(); this.WP_SPEED_MAX = new System.Windows.Forms.NumericUpDown(); @@ -289,129 +275,58 @@ this.BUT_load = new ArdupilotMega.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.BUT_compare = new ArdupilotMega.MyButton(); + this.groupBox17 = new System.Windows.Forms.GroupBox(); + this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown(); + this.label27 = new System.Windows.Forms.Label(); + this.ACRO_PIT_I = new System.Windows.Forms.NumericUpDown(); + this.label29 = new System.Windows.Forms.Label(); + this.ACRO_PIT_P = new System.Windows.Forms.NumericUpDown(); + this.label33 = new System.Windows.Forms.Label(); + this.groupBox18 = new System.Windows.Forms.GroupBox(); + this.ACRO_RLL_IMAX = new System.Windows.Forms.NumericUpDown(); + this.label40 = new System.Windows.Forms.Label(); + this.ACRO_RLL_I = new System.Windows.Forms.NumericUpDown(); + this.label44 = new System.Windows.Forms.Label(); + this.ACRO_RLL_P = new System.Windows.Forms.NumericUpDown(); + this.label48 = new System.Windows.Forms.Label(); ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit(); this.ConfigTabs.SuspendLayout(); this.TabAPM2.SuspendLayout(); this.groupBox3.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).BeginInit(); this.groupBox1.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).BeginInit(); this.groupBox2.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).BeginInit(); this.groupBox15.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).BeginInit(); this.groupBox16.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).BeginInit(); this.groupBox14.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).BeginInit(); this.groupBox13.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).BeginInit(); this.groupBox12.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).BeginInit(); this.groupBox11.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).BeginInit(); this.groupBox10.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).BeginInit(); this.groupBox9.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).BeginInit(); this.groupBox8.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).BeginInit(); this.TabAC2.SuspendLayout(); - this.groupBox17.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_P)).BeginInit(); this.groupBox5.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).BeginInit(); - this.groupBox18.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_P)).BeginInit(); this.groupBox4.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).BeginInit(); this.groupBox6.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD1)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRACK_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRACK_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRACK_P)).BeginInit(); this.groupBox7.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).BeginInit(); this.groupBox19.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).BeginInit(); this.groupBox20.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).BeginInit(); this.groupBox21.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).BeginInit(); this.groupBox22.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).BeginInit(); this.groupBox23.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).BeginInit(); this.groupBox24.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).BeginInit(); this.groupBox25.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).BeginInit(); this.TabPlanner.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit(); + this.groupBox17.SuspendLayout(); + this.groupBox18.SuspendLayout(); this.SuspendLayout(); // // Params // - resources.ApplyResources(this.Params, "Params"); this.Params.AllowUserToAddRows = false; this.Params.AllowUserToDeleteRows = false; + resources.ApplyResources(this.Params, "Params"); dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon; dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); @@ -437,7 +352,6 @@ dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True; this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2; this.Params.RowHeadersVisible = false; - this.toolTip1.SetToolTip(this.Params, resources.GetString("Params.ToolTip")); this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged); // // Command @@ -475,12 +389,10 @@ this.ConfigTabs.Controls.Add(this.TabSetup); this.ConfigTabs.Name = "ConfigTabs"; this.ConfigTabs.SelectedIndex = 0; - this.toolTip1.SetToolTip(this.ConfigTabs, resources.GetString("ConfigTabs.ToolTip")); this.ConfigTabs.SelectedIndexChanged += new System.EventHandler(this.Planner_TabIndexChanged); // // TabAPM2 // - resources.ApplyResources(this.TabAPM2, "TabAPM2"); this.TabAPM2.BackColor = System.Drawing.Color.Transparent; this.TabAPM2.Controls.Add(this.groupBox3); this.TabAPM2.Controls.Add(this.groupBox1); @@ -494,12 +406,11 @@ this.TabAPM2.Controls.Add(this.groupBox10); this.TabAPM2.Controls.Add(this.groupBox9); this.TabAPM2.Controls.Add(this.groupBox8); + resources.ApplyResources(this.TabAPM2, "TabAPM2"); this.TabAPM2.Name = "TabAPM2"; - this.toolTip1.SetToolTip(this.TabAPM2, resources.GetString("TabAPM2.ToolTip")); // // groupBox3 // - resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Controls.Add(this.THR_FS_VALUE); this.groupBox3.Controls.Add(this.label5); this.groupBox3.Controls.Add(this.THR_MAX); @@ -508,61 +419,52 @@ this.groupBox3.Controls.Add(this.label7); this.groupBox3.Controls.Add(this.TRIM_THROTTLE); this.groupBox3.Controls.Add(this.label8); + resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Name = "groupBox3"; this.groupBox3.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox3, resources.GetString("groupBox3.ToolTip")); // // THR_FS_VALUE // resources.ApplyResources(this.THR_FS_VALUE, "THR_FS_VALUE"); this.THR_FS_VALUE.Name = "THR_FS_VALUE"; - this.toolTip1.SetToolTip(this.THR_FS_VALUE, resources.GetString("THR_FS_VALUE.ToolTip")); // // label5 // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; - this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // THR_MAX // resources.ApplyResources(this.THR_MAX, "THR_MAX"); this.THR_MAX.Name = "THR_MAX"; - this.toolTip1.SetToolTip(this.THR_MAX, resources.GetString("THR_MAX.ToolTip")); // // label6 // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; - this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // THR_MIN // resources.ApplyResources(this.THR_MIN, "THR_MIN"); this.THR_MIN.Name = "THR_MIN"; - this.toolTip1.SetToolTip(this.THR_MIN, resources.GetString("THR_MIN.ToolTip")); // // label7 // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; - this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // TRIM_THROTTLE // resources.ApplyResources(this.TRIM_THROTTLE, "TRIM_THROTTLE"); this.TRIM_THROTTLE.Name = "TRIM_THROTTLE"; - this.toolTip1.SetToolTip(this.TRIM_THROTTLE, resources.GetString("TRIM_THROTTLE.ToolTip")); // // label8 // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; - this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // groupBox1 // - resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Controls.Add(this.ARSPD_RATIO); this.groupBox1.Controls.Add(this.label1); this.groupBox1.Controls.Add(this.ARSPD_FBW_MAX); @@ -571,194 +473,166 @@ this.groupBox1.Controls.Add(this.label3); this.groupBox1.Controls.Add(this.TRIM_ARSPD_CM); this.groupBox1.Controls.Add(this.label4); + resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Name = "groupBox1"; this.groupBox1.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox1, resources.GetString("groupBox1.ToolTip")); // // ARSPD_RATIO // resources.ApplyResources(this.ARSPD_RATIO, "ARSPD_RATIO"); this.ARSPD_RATIO.Name = "ARSPD_RATIO"; - this.toolTip1.SetToolTip(this.ARSPD_RATIO, resources.GetString("ARSPD_RATIO.ToolTip")); // // label1 // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; - this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // ARSPD_FBW_MAX // resources.ApplyResources(this.ARSPD_FBW_MAX, "ARSPD_FBW_MAX"); this.ARSPD_FBW_MAX.Name = "ARSPD_FBW_MAX"; - this.toolTip1.SetToolTip(this.ARSPD_FBW_MAX, resources.GetString("ARSPD_FBW_MAX.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; - this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // ARSPD_FBW_MIN // resources.ApplyResources(this.ARSPD_FBW_MIN, "ARSPD_FBW_MIN"); this.ARSPD_FBW_MIN.Name = "ARSPD_FBW_MIN"; - this.toolTip1.SetToolTip(this.ARSPD_FBW_MIN, resources.GetString("ARSPD_FBW_MIN.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; - this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // TRIM_ARSPD_CM // resources.ApplyResources(this.TRIM_ARSPD_CM, "TRIM_ARSPD_CM"); this.TRIM_ARSPD_CM.Name = "TRIM_ARSPD_CM"; - this.toolTip1.SetToolTip(this.TRIM_ARSPD_CM, resources.GetString("TRIM_ARSPD_CM.ToolTip")); // // label4 // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; - this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // groupBox2 // - resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Controls.Add(this.LIM_PITCH_MIN); this.groupBox2.Controls.Add(this.label39); this.groupBox2.Controls.Add(this.LIM_PITCH_MAX); this.groupBox2.Controls.Add(this.label38); this.groupBox2.Controls.Add(this.LIM_ROLL_CD); this.groupBox2.Controls.Add(this.label37); + resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Name = "groupBox2"; this.groupBox2.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox2, resources.GetString("groupBox2.ToolTip")); // // LIM_PITCH_MIN // resources.ApplyResources(this.LIM_PITCH_MIN, "LIM_PITCH_MIN"); this.LIM_PITCH_MIN.Name = "LIM_PITCH_MIN"; - this.toolTip1.SetToolTip(this.LIM_PITCH_MIN, resources.GetString("LIM_PITCH_MIN.ToolTip")); // // label39 // resources.ApplyResources(this.label39, "label39"); this.label39.Name = "label39"; - this.toolTip1.SetToolTip(this.label39, resources.GetString("label39.ToolTip")); // // LIM_PITCH_MAX // resources.ApplyResources(this.LIM_PITCH_MAX, "LIM_PITCH_MAX"); this.LIM_PITCH_MAX.Name = "LIM_PITCH_MAX"; - this.toolTip1.SetToolTip(this.LIM_PITCH_MAX, resources.GetString("LIM_PITCH_MAX.ToolTip")); // // label38 // resources.ApplyResources(this.label38, "label38"); this.label38.Name = "label38"; - this.toolTip1.SetToolTip(this.label38, resources.GetString("label38.ToolTip")); // // LIM_ROLL_CD // resources.ApplyResources(this.LIM_ROLL_CD, "LIM_ROLL_CD"); this.LIM_ROLL_CD.Name = "LIM_ROLL_CD"; - this.toolTip1.SetToolTip(this.LIM_ROLL_CD, resources.GetString("LIM_ROLL_CD.ToolTip")); // // label37 // resources.ApplyResources(this.label37, "label37"); this.label37.Name = "label37"; - this.toolTip1.SetToolTip(this.label37, resources.GetString("label37.ToolTip")); // // groupBox15 // - resources.ApplyResources(this.groupBox15, "groupBox15"); this.groupBox15.Controls.Add(this.XTRK_ANGLE_CD); this.groupBox15.Controls.Add(this.label79); this.groupBox15.Controls.Add(this.XTRK_GAIN_SC); this.groupBox15.Controls.Add(this.label80); + resources.ApplyResources(this.groupBox15, "groupBox15"); this.groupBox15.Name = "groupBox15"; this.groupBox15.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox15, resources.GetString("groupBox15.ToolTip")); // // XTRK_ANGLE_CD // resources.ApplyResources(this.XTRK_ANGLE_CD, "XTRK_ANGLE_CD"); this.XTRK_ANGLE_CD.Name = "XTRK_ANGLE_CD"; - this.toolTip1.SetToolTip(this.XTRK_ANGLE_CD, resources.GetString("XTRK_ANGLE_CD.ToolTip")); // // label79 // resources.ApplyResources(this.label79, "label79"); this.label79.Name = "label79"; - this.toolTip1.SetToolTip(this.label79, resources.GetString("label79.ToolTip")); // // XTRK_GAIN_SC // resources.ApplyResources(this.XTRK_GAIN_SC, "XTRK_GAIN_SC"); this.XTRK_GAIN_SC.Name = "XTRK_GAIN_SC"; - this.toolTip1.SetToolTip(this.XTRK_GAIN_SC, resources.GetString("XTRK_GAIN_SC.ToolTip")); // // label80 // resources.ApplyResources(this.label80, "label80"); this.label80.Name = "label80"; - this.toolTip1.SetToolTip(this.label80, resources.GetString("label80.ToolTip")); // // groupBox16 // - resources.ApplyResources(this.groupBox16, "groupBox16"); this.groupBox16.Controls.Add(this.KFF_PTCH2THR); this.groupBox16.Controls.Add(this.label83); this.groupBox16.Controls.Add(this.KFF_RDDRMIX); this.groupBox16.Controls.Add(this.label78); this.groupBox16.Controls.Add(this.KFF_PTCHCOMP); this.groupBox16.Controls.Add(this.label81); + resources.ApplyResources(this.groupBox16, "groupBox16"); this.groupBox16.Name = "groupBox16"; this.groupBox16.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox16, resources.GetString("groupBox16.ToolTip")); // // KFF_PTCH2THR // resources.ApplyResources(this.KFF_PTCH2THR, "KFF_PTCH2THR"); this.KFF_PTCH2THR.Name = "KFF_PTCH2THR"; - this.toolTip1.SetToolTip(this.KFF_PTCH2THR, resources.GetString("KFF_PTCH2THR.ToolTip")); // // label83 // resources.ApplyResources(this.label83, "label83"); this.label83.Name = "label83"; - this.toolTip1.SetToolTip(this.label83, resources.GetString("label83.ToolTip")); // // KFF_RDDRMIX // resources.ApplyResources(this.KFF_RDDRMIX, "KFF_RDDRMIX"); this.KFF_RDDRMIX.Name = "KFF_RDDRMIX"; - this.toolTip1.SetToolTip(this.KFF_RDDRMIX, resources.GetString("KFF_RDDRMIX.ToolTip")); // // label78 // resources.ApplyResources(this.label78, "label78"); this.label78.Name = "label78"; - this.toolTip1.SetToolTip(this.label78, resources.GetString("label78.ToolTip")); // // KFF_PTCHCOMP // resources.ApplyResources(this.KFF_PTCHCOMP, "KFF_PTCHCOMP"); this.KFF_PTCHCOMP.Name = "KFF_PTCHCOMP"; - this.toolTip1.SetToolTip(this.KFF_PTCHCOMP, resources.GetString("KFF_PTCHCOMP.ToolTip")); // // label81 // resources.ApplyResources(this.label81, "label81"); this.label81.Name = "label81"; - this.toolTip1.SetToolTip(this.label81, resources.GetString("label81.ToolTip")); // // groupBox14 // - resources.ApplyResources(this.groupBox14, "groupBox14"); this.groupBox14.Controls.Add(this.ENRGY2THR_IMAX); this.groupBox14.Controls.Add(this.label73); this.groupBox14.Controls.Add(this.ENRGY2THR_D); @@ -767,61 +641,52 @@ this.groupBox14.Controls.Add(this.label75); this.groupBox14.Controls.Add(this.ENRGY2THR_P); this.groupBox14.Controls.Add(this.label76); + resources.ApplyResources(this.groupBox14, "groupBox14"); this.groupBox14.Name = "groupBox14"; this.groupBox14.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox14, resources.GetString("groupBox14.ToolTip")); // // ENRGY2THR_IMAX // resources.ApplyResources(this.ENRGY2THR_IMAX, "ENRGY2THR_IMAX"); this.ENRGY2THR_IMAX.Name = "ENRGY2THR_IMAX"; - this.toolTip1.SetToolTip(this.ENRGY2THR_IMAX, resources.GetString("ENRGY2THR_IMAX.ToolTip")); // // label73 // resources.ApplyResources(this.label73, "label73"); this.label73.Name = "label73"; - this.toolTip1.SetToolTip(this.label73, resources.GetString("label73.ToolTip")); // // ENRGY2THR_D // resources.ApplyResources(this.ENRGY2THR_D, "ENRGY2THR_D"); this.ENRGY2THR_D.Name = "ENRGY2THR_D"; - this.toolTip1.SetToolTip(this.ENRGY2THR_D, resources.GetString("ENRGY2THR_D.ToolTip")); // // label74 // resources.ApplyResources(this.label74, "label74"); this.label74.Name = "label74"; - this.toolTip1.SetToolTip(this.label74, resources.GetString("label74.ToolTip")); // // ENRGY2THR_I // resources.ApplyResources(this.ENRGY2THR_I, "ENRGY2THR_I"); this.ENRGY2THR_I.Name = "ENRGY2THR_I"; - this.toolTip1.SetToolTip(this.ENRGY2THR_I, resources.GetString("ENRGY2THR_I.ToolTip")); // // label75 // resources.ApplyResources(this.label75, "label75"); this.label75.Name = "label75"; - this.toolTip1.SetToolTip(this.label75, resources.GetString("label75.ToolTip")); // // ENRGY2THR_P // resources.ApplyResources(this.ENRGY2THR_P, "ENRGY2THR_P"); this.ENRGY2THR_P.Name = "ENRGY2THR_P"; - this.toolTip1.SetToolTip(this.ENRGY2THR_P, resources.GetString("ENRGY2THR_P.ToolTip")); // // label76 // resources.ApplyResources(this.label76, "label76"); this.label76.Name = "label76"; - this.toolTip1.SetToolTip(this.label76, resources.GetString("label76.ToolTip")); // // groupBox13 // - resources.ApplyResources(this.groupBox13, "groupBox13"); this.groupBox13.Controls.Add(this.ALT2PTCH_IMAX); this.groupBox13.Controls.Add(this.label69); this.groupBox13.Controls.Add(this.ALT2PTCH_D); @@ -830,61 +695,52 @@ this.groupBox13.Controls.Add(this.label71); this.groupBox13.Controls.Add(this.ALT2PTCH_P); this.groupBox13.Controls.Add(this.label72); + resources.ApplyResources(this.groupBox13, "groupBox13"); this.groupBox13.Name = "groupBox13"; this.groupBox13.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox13, resources.GetString("groupBox13.ToolTip")); // // ALT2PTCH_IMAX // resources.ApplyResources(this.ALT2PTCH_IMAX, "ALT2PTCH_IMAX"); this.ALT2PTCH_IMAX.Name = "ALT2PTCH_IMAX"; - this.toolTip1.SetToolTip(this.ALT2PTCH_IMAX, resources.GetString("ALT2PTCH_IMAX.ToolTip")); // // label69 // resources.ApplyResources(this.label69, "label69"); this.label69.Name = "label69"; - this.toolTip1.SetToolTip(this.label69, resources.GetString("label69.ToolTip")); // // ALT2PTCH_D // resources.ApplyResources(this.ALT2PTCH_D, "ALT2PTCH_D"); this.ALT2PTCH_D.Name = "ALT2PTCH_D"; - this.toolTip1.SetToolTip(this.ALT2PTCH_D, resources.GetString("ALT2PTCH_D.ToolTip")); // // label70 // resources.ApplyResources(this.label70, "label70"); this.label70.Name = "label70"; - this.toolTip1.SetToolTip(this.label70, resources.GetString("label70.ToolTip")); // // ALT2PTCH_I // resources.ApplyResources(this.ALT2PTCH_I, "ALT2PTCH_I"); this.ALT2PTCH_I.Name = "ALT2PTCH_I"; - this.toolTip1.SetToolTip(this.ALT2PTCH_I, resources.GetString("ALT2PTCH_I.ToolTip")); // // label71 // resources.ApplyResources(this.label71, "label71"); this.label71.Name = "label71"; - this.toolTip1.SetToolTip(this.label71, resources.GetString("label71.ToolTip")); // // ALT2PTCH_P // resources.ApplyResources(this.ALT2PTCH_P, "ALT2PTCH_P"); this.ALT2PTCH_P.Name = "ALT2PTCH_P"; - this.toolTip1.SetToolTip(this.ALT2PTCH_P, resources.GetString("ALT2PTCH_P.ToolTip")); // // label72 // resources.ApplyResources(this.label72, "label72"); this.label72.Name = "label72"; - this.toolTip1.SetToolTip(this.label72, resources.GetString("label72.ToolTip")); // // groupBox12 // - resources.ApplyResources(this.groupBox12, "groupBox12"); this.groupBox12.Controls.Add(this.ARSP2PTCH_IMAX); this.groupBox12.Controls.Add(this.label65); this.groupBox12.Controls.Add(this.ARSP2PTCH_D); @@ -893,61 +749,52 @@ this.groupBox12.Controls.Add(this.label67); this.groupBox12.Controls.Add(this.ARSP2PTCH_P); this.groupBox12.Controls.Add(this.label68); + resources.ApplyResources(this.groupBox12, "groupBox12"); this.groupBox12.Name = "groupBox12"; this.groupBox12.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox12, resources.GetString("groupBox12.ToolTip")); // // ARSP2PTCH_IMAX // resources.ApplyResources(this.ARSP2PTCH_IMAX, "ARSP2PTCH_IMAX"); this.ARSP2PTCH_IMAX.Name = "ARSP2PTCH_IMAX"; - this.toolTip1.SetToolTip(this.ARSP2PTCH_IMAX, resources.GetString("ARSP2PTCH_IMAX.ToolTip")); // // label65 // resources.ApplyResources(this.label65, "label65"); this.label65.Name = "label65"; - this.toolTip1.SetToolTip(this.label65, resources.GetString("label65.ToolTip")); // // ARSP2PTCH_D // resources.ApplyResources(this.ARSP2PTCH_D, "ARSP2PTCH_D"); this.ARSP2PTCH_D.Name = "ARSP2PTCH_D"; - this.toolTip1.SetToolTip(this.ARSP2PTCH_D, resources.GetString("ARSP2PTCH_D.ToolTip")); // // label66 // resources.ApplyResources(this.label66, "label66"); this.label66.Name = "label66"; - this.toolTip1.SetToolTip(this.label66, resources.GetString("label66.ToolTip")); // // ARSP2PTCH_I // resources.ApplyResources(this.ARSP2PTCH_I, "ARSP2PTCH_I"); this.ARSP2PTCH_I.Name = "ARSP2PTCH_I"; - this.toolTip1.SetToolTip(this.ARSP2PTCH_I, resources.GetString("ARSP2PTCH_I.ToolTip")); // // label67 // resources.ApplyResources(this.label67, "label67"); this.label67.Name = "label67"; - this.toolTip1.SetToolTip(this.label67, resources.GetString("label67.ToolTip")); // // ARSP2PTCH_P // resources.ApplyResources(this.ARSP2PTCH_P, "ARSP2PTCH_P"); this.ARSP2PTCH_P.Name = "ARSP2PTCH_P"; - this.toolTip1.SetToolTip(this.ARSP2PTCH_P, resources.GetString("ARSP2PTCH_P.ToolTip")); // // label68 // resources.ApplyResources(this.label68, "label68"); this.label68.Name = "label68"; - this.toolTip1.SetToolTip(this.label68, resources.GetString("label68.ToolTip")); // // groupBox11 // - resources.ApplyResources(this.groupBox11, "groupBox11"); this.groupBox11.Controls.Add(this.HDNG2RLL_IMAX); this.groupBox11.Controls.Add(this.label61); this.groupBox11.Controls.Add(this.HDNG2RLL_D); @@ -956,61 +803,52 @@ this.groupBox11.Controls.Add(this.label63); this.groupBox11.Controls.Add(this.HDNG2RLL_P); this.groupBox11.Controls.Add(this.label64); + resources.ApplyResources(this.groupBox11, "groupBox11"); this.groupBox11.Name = "groupBox11"; this.groupBox11.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox11, resources.GetString("groupBox11.ToolTip")); // // HDNG2RLL_IMAX // resources.ApplyResources(this.HDNG2RLL_IMAX, "HDNG2RLL_IMAX"); this.HDNG2RLL_IMAX.Name = "HDNG2RLL_IMAX"; - this.toolTip1.SetToolTip(this.HDNG2RLL_IMAX, resources.GetString("HDNG2RLL_IMAX.ToolTip")); // // label61 // resources.ApplyResources(this.label61, "label61"); this.label61.Name = "label61"; - this.toolTip1.SetToolTip(this.label61, resources.GetString("label61.ToolTip")); // // HDNG2RLL_D // resources.ApplyResources(this.HDNG2RLL_D, "HDNG2RLL_D"); this.HDNG2RLL_D.Name = "HDNG2RLL_D"; - this.toolTip1.SetToolTip(this.HDNG2RLL_D, resources.GetString("HDNG2RLL_D.ToolTip")); // // label62 // resources.ApplyResources(this.label62, "label62"); this.label62.Name = "label62"; - this.toolTip1.SetToolTip(this.label62, resources.GetString("label62.ToolTip")); // // HDNG2RLL_I // resources.ApplyResources(this.HDNG2RLL_I, "HDNG2RLL_I"); this.HDNG2RLL_I.Name = "HDNG2RLL_I"; - this.toolTip1.SetToolTip(this.HDNG2RLL_I, resources.GetString("HDNG2RLL_I.ToolTip")); // // label63 // resources.ApplyResources(this.label63, "label63"); this.label63.Name = "label63"; - this.toolTip1.SetToolTip(this.label63, resources.GetString("label63.ToolTip")); // // HDNG2RLL_P // resources.ApplyResources(this.HDNG2RLL_P, "HDNG2RLL_P"); this.HDNG2RLL_P.Name = "HDNG2RLL_P"; - this.toolTip1.SetToolTip(this.HDNG2RLL_P, resources.GetString("HDNG2RLL_P.ToolTip")); // // label64 // resources.ApplyResources(this.label64, "label64"); this.label64.Name = "label64"; - this.toolTip1.SetToolTip(this.label64, resources.GetString("label64.ToolTip")); // // groupBox10 // - resources.ApplyResources(this.groupBox10, "groupBox10"); this.groupBox10.Controls.Add(this.YW2SRV_IMAX); this.groupBox10.Controls.Add(this.label57); this.groupBox10.Controls.Add(this.YW2SRV_D); @@ -1019,61 +857,52 @@ this.groupBox10.Controls.Add(this.label59); this.groupBox10.Controls.Add(this.YW2SRV_P); this.groupBox10.Controls.Add(this.label60); + resources.ApplyResources(this.groupBox10, "groupBox10"); this.groupBox10.Name = "groupBox10"; this.groupBox10.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox10, resources.GetString("groupBox10.ToolTip")); // // YW2SRV_IMAX // resources.ApplyResources(this.YW2SRV_IMAX, "YW2SRV_IMAX"); this.YW2SRV_IMAX.Name = "YW2SRV_IMAX"; - this.toolTip1.SetToolTip(this.YW2SRV_IMAX, resources.GetString("YW2SRV_IMAX.ToolTip")); // // label57 // resources.ApplyResources(this.label57, "label57"); this.label57.Name = "label57"; - this.toolTip1.SetToolTip(this.label57, resources.GetString("label57.ToolTip")); // // YW2SRV_D // resources.ApplyResources(this.YW2SRV_D, "YW2SRV_D"); this.YW2SRV_D.Name = "YW2SRV_D"; - this.toolTip1.SetToolTip(this.YW2SRV_D, resources.GetString("YW2SRV_D.ToolTip")); // // label58 // resources.ApplyResources(this.label58, "label58"); this.label58.Name = "label58"; - this.toolTip1.SetToolTip(this.label58, resources.GetString("label58.ToolTip")); // // YW2SRV_I // resources.ApplyResources(this.YW2SRV_I, "YW2SRV_I"); this.YW2SRV_I.Name = "YW2SRV_I"; - this.toolTip1.SetToolTip(this.YW2SRV_I, resources.GetString("YW2SRV_I.ToolTip")); // // label59 // resources.ApplyResources(this.label59, "label59"); this.label59.Name = "label59"; - this.toolTip1.SetToolTip(this.label59, resources.GetString("label59.ToolTip")); // // YW2SRV_P // resources.ApplyResources(this.YW2SRV_P, "YW2SRV_P"); this.YW2SRV_P.Name = "YW2SRV_P"; - this.toolTip1.SetToolTip(this.YW2SRV_P, resources.GetString("YW2SRV_P.ToolTip")); // // label60 // resources.ApplyResources(this.label60, "label60"); this.label60.Name = "label60"; - this.toolTip1.SetToolTip(this.label60, resources.GetString("label60.ToolTip")); // // groupBox9 // - resources.ApplyResources(this.groupBox9, "groupBox9"); this.groupBox9.Controls.Add(this.PTCH2SRV_IMAX); this.groupBox9.Controls.Add(this.label53); this.groupBox9.Controls.Add(this.PTCH2SRV_D); @@ -1082,61 +911,52 @@ this.groupBox9.Controls.Add(this.label55); this.groupBox9.Controls.Add(this.PTCH2SRV_P); this.groupBox9.Controls.Add(this.label56); + resources.ApplyResources(this.groupBox9, "groupBox9"); this.groupBox9.Name = "groupBox9"; this.groupBox9.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox9, resources.GetString("groupBox9.ToolTip")); // // PTCH2SRV_IMAX // resources.ApplyResources(this.PTCH2SRV_IMAX, "PTCH2SRV_IMAX"); this.PTCH2SRV_IMAX.Name = "PTCH2SRV_IMAX"; - this.toolTip1.SetToolTip(this.PTCH2SRV_IMAX, resources.GetString("PTCH2SRV_IMAX.ToolTip")); // // label53 // resources.ApplyResources(this.label53, "label53"); this.label53.Name = "label53"; - this.toolTip1.SetToolTip(this.label53, resources.GetString("label53.ToolTip")); // // PTCH2SRV_D // resources.ApplyResources(this.PTCH2SRV_D, "PTCH2SRV_D"); this.PTCH2SRV_D.Name = "PTCH2SRV_D"; - this.toolTip1.SetToolTip(this.PTCH2SRV_D, resources.GetString("PTCH2SRV_D.ToolTip")); // // label54 // resources.ApplyResources(this.label54, "label54"); this.label54.Name = "label54"; - this.toolTip1.SetToolTip(this.label54, resources.GetString("label54.ToolTip")); // // PTCH2SRV_I // resources.ApplyResources(this.PTCH2SRV_I, "PTCH2SRV_I"); this.PTCH2SRV_I.Name = "PTCH2SRV_I"; - this.toolTip1.SetToolTip(this.PTCH2SRV_I, resources.GetString("PTCH2SRV_I.ToolTip")); // // label55 // resources.ApplyResources(this.label55, "label55"); this.label55.Name = "label55"; - this.toolTip1.SetToolTip(this.label55, resources.GetString("label55.ToolTip")); // // PTCH2SRV_P // resources.ApplyResources(this.PTCH2SRV_P, "PTCH2SRV_P"); this.PTCH2SRV_P.Name = "PTCH2SRV_P"; - this.toolTip1.SetToolTip(this.PTCH2SRV_P, resources.GetString("PTCH2SRV_P.ToolTip")); // // label56 // resources.ApplyResources(this.label56, "label56"); this.label56.Name = "label56"; - this.toolTip1.SetToolTip(this.label56, resources.GetString("label56.ToolTip")); // // groupBox8 // - resources.ApplyResources(this.groupBox8, "groupBox8"); this.groupBox8.Controls.Add(this.RLL2SRV_IMAX); this.groupBox8.Controls.Add(this.label49); this.groupBox8.Controls.Add(this.RLL2SRV_D); @@ -1145,61 +965,52 @@ this.groupBox8.Controls.Add(this.label51); this.groupBox8.Controls.Add(this.RLL2SRV_P); this.groupBox8.Controls.Add(this.label52); + resources.ApplyResources(this.groupBox8, "groupBox8"); this.groupBox8.Name = "groupBox8"; this.groupBox8.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox8, resources.GetString("groupBox8.ToolTip")); // // RLL2SRV_IMAX // resources.ApplyResources(this.RLL2SRV_IMAX, "RLL2SRV_IMAX"); this.RLL2SRV_IMAX.Name = "RLL2SRV_IMAX"; - this.toolTip1.SetToolTip(this.RLL2SRV_IMAX, resources.GetString("RLL2SRV_IMAX.ToolTip")); // // label49 // resources.ApplyResources(this.label49, "label49"); this.label49.Name = "label49"; - this.toolTip1.SetToolTip(this.label49, resources.GetString("label49.ToolTip")); // // RLL2SRV_D // resources.ApplyResources(this.RLL2SRV_D, "RLL2SRV_D"); this.RLL2SRV_D.Name = "RLL2SRV_D"; - this.toolTip1.SetToolTip(this.RLL2SRV_D, resources.GetString("RLL2SRV_D.ToolTip")); // // label50 // resources.ApplyResources(this.label50, "label50"); this.label50.Name = "label50"; - this.toolTip1.SetToolTip(this.label50, resources.GetString("label50.ToolTip")); // // RLL2SRV_I // resources.ApplyResources(this.RLL2SRV_I, "RLL2SRV_I"); this.RLL2SRV_I.Name = "RLL2SRV_I"; - this.toolTip1.SetToolTip(this.RLL2SRV_I, resources.GetString("RLL2SRV_I.ToolTip")); // // label51 // resources.ApplyResources(this.label51, "label51"); this.label51.Name = "label51"; - this.toolTip1.SetToolTip(this.label51, resources.GetString("label51.ToolTip")); // // RLL2SRV_P // resources.ApplyResources(this.RLL2SRV_P, "RLL2SRV_P"); this.RLL2SRV_P.Name = "RLL2SRV_P"; - this.toolTip1.SetToolTip(this.RLL2SRV_P, resources.GetString("RLL2SRV_P.ToolTip")); // // label52 // resources.ApplyResources(this.label52, "label52"); this.label52.Name = "label52"; - this.toolTip1.SetToolTip(this.label52, resources.GetString("label52.ToolTip")); // // TabAC2 // - resources.ApplyResources(this.TabAC2, "TabAC2"); this.TabAC2.Controls.Add(this.groupBox17); this.TabAC2.Controls.Add(this.groupBox5); this.TabAC2.Controls.Add(this.groupBox18); @@ -1214,155 +1025,50 @@ this.TabAC2.Controls.Add(this.groupBox23); this.TabAC2.Controls.Add(this.groupBox24); this.TabAC2.Controls.Add(this.groupBox25); + resources.ApplyResources(this.TabAC2, "TabAC2"); this.TabAC2.Name = "TabAC2"; - this.toolTip1.SetToolTip(this.TabAC2, resources.GetString("TabAC2.ToolTip")); - // - // groupBox17 - // - resources.ApplyResources(this.groupBox17, "groupBox17"); - this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX); - this.groupBox17.Controls.Add(this.label27); - this.groupBox17.Controls.Add(this.ACRO_PIT_I); - this.groupBox17.Controls.Add(this.label29); - this.groupBox17.Controls.Add(this.ACRO_PIT_P); - this.groupBox17.Controls.Add(this.label33); - this.groupBox17.Name = "groupBox17"; - this.groupBox17.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox17, resources.GetString("groupBox17.ToolTip")); - // - // ACRO_PIT_IMAX - // - resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX"); - this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX"; - this.toolTip1.SetToolTip(this.ACRO_PIT_IMAX, resources.GetString("ACRO_PIT_IMAX.ToolTip")); - // - // label27 - // - resources.ApplyResources(this.label27, "label27"); - this.label27.Name = "label27"; - this.toolTip1.SetToolTip(this.label27, resources.GetString("label27.ToolTip")); - // - // ACRO_PIT_I - // - resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I"); - this.ACRO_PIT_I.Name = "ACRO_PIT_I"; - this.toolTip1.SetToolTip(this.ACRO_PIT_I, resources.GetString("ACRO_PIT_I.ToolTip")); - // - // label29 - // - resources.ApplyResources(this.label29, "label29"); - this.label29.Name = "label29"; - this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); - // - // ACRO_PIT_P - // - resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P"); - this.ACRO_PIT_P.Name = "ACRO_PIT_P"; - this.toolTip1.SetToolTip(this.ACRO_PIT_P, resources.GetString("ACRO_PIT_P.ToolTip")); - // - // label33 - // - resources.ApplyResources(this.label33, "label33"); - this.label33.Name = "label33"; - this.toolTip1.SetToolTip(this.label33, resources.GetString("label33.ToolTip")); // // groupBox5 // - resources.ApplyResources(this.groupBox5, "groupBox5"); this.groupBox5.Controls.Add(this.label14); this.groupBox5.Controls.Add(this.THR_RATE_IMAX); this.groupBox5.Controls.Add(this.THR_RATE_I); this.groupBox5.Controls.Add(this.label20); this.groupBox5.Controls.Add(this.THR_RATE_P); this.groupBox5.Controls.Add(this.label25); + resources.ApplyResources(this.groupBox5, "groupBox5"); this.groupBox5.Name = "groupBox5"; this.groupBox5.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox5, resources.GetString("groupBox5.ToolTip")); // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; - this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // THR_RATE_IMAX // resources.ApplyResources(this.THR_RATE_IMAX, "THR_RATE_IMAX"); this.THR_RATE_IMAX.Name = "THR_RATE_IMAX"; - this.toolTip1.SetToolTip(this.THR_RATE_IMAX, resources.GetString("THR_RATE_IMAX.ToolTip")); // // THR_RATE_I // resources.ApplyResources(this.THR_RATE_I, "THR_RATE_I"); this.THR_RATE_I.Name = "THR_RATE_I"; - this.toolTip1.SetToolTip(this.THR_RATE_I, resources.GetString("THR_RATE_I.ToolTip")); // // label20 // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; - this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // THR_RATE_P // resources.ApplyResources(this.THR_RATE_P, "THR_RATE_P"); this.THR_RATE_P.Name = "THR_RATE_P"; - this.toolTip1.SetToolTip(this.THR_RATE_P, resources.GetString("THR_RATE_P.ToolTip")); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; - this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); - // - // groupBox18 - // - resources.ApplyResources(this.groupBox18, "groupBox18"); - this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX); - this.groupBox18.Controls.Add(this.label40); - this.groupBox18.Controls.Add(this.ACRO_RLL_I); - this.groupBox18.Controls.Add(this.label44); - this.groupBox18.Controls.Add(this.ACRO_RLL_P); - this.groupBox18.Controls.Add(this.label48); - this.groupBox18.Name = "groupBox18"; - this.groupBox18.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox18, resources.GetString("groupBox18.ToolTip")); - // - // ACRO_RLL_IMAX - // - resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX"); - this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX"; - this.toolTip1.SetToolTip(this.ACRO_RLL_IMAX, resources.GetString("ACRO_RLL_IMAX.ToolTip")); - // - // label40 - // - resources.ApplyResources(this.label40, "label40"); - this.label40.Name = "label40"; - this.toolTip1.SetToolTip(this.label40, resources.GetString("label40.ToolTip")); - // - // ACRO_RLL_I - // - resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I"); - this.ACRO_RLL_I.Name = "ACRO_RLL_I"; - this.toolTip1.SetToolTip(this.ACRO_RLL_I, resources.GetString("ACRO_RLL_I.ToolTip")); - // - // label44 - // - resources.ApplyResources(this.label44, "label44"); - this.label44.Name = "label44"; - this.toolTip1.SetToolTip(this.label44, resources.GetString("label44.ToolTip")); - // - // ACRO_RLL_P - // - resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P"); - this.ACRO_RLL_P.Name = "ACRO_RLL_P"; - this.toolTip1.SetToolTip(this.ACRO_RLL_P, resources.GetString("ACRO_RLL_P.ToolTip")); - // - // label48 - // - resources.ApplyResources(this.label48, "label48"); - this.label48.Name = "label48"; - this.toolTip1.SetToolTip(this.label48, resources.GetString("label48.ToolTip")); // // CHK_lockrollpitch // @@ -1370,13 +1076,11 @@ this.CHK_lockrollpitch.Checked = true; this.CHK_lockrollpitch.CheckState = System.Windows.Forms.CheckState.Checked; this.CHK_lockrollpitch.Name = "CHK_lockrollpitch"; - this.toolTip1.SetToolTip(this.CHK_lockrollpitch, resources.GetString("CHK_lockrollpitch.ToolTip")); this.CHK_lockrollpitch.UseVisualStyleBackColor = true; this.CHK_lockrollpitch.CheckedChanged += new System.EventHandler(this.CHK_lockrollpitch_CheckedChanged); // // groupBox4 // - resources.ApplyResources(this.groupBox4, "groupBox4"); this.groupBox4.Controls.Add(this.WP_SPEED_MAX); this.groupBox4.Controls.Add(this.label9); this.groupBox4.Controls.Add(this.NAV_LAT_IMAX); @@ -1385,61 +1089,52 @@ this.groupBox4.Controls.Add(this.label15); this.groupBox4.Controls.Add(this.NAV_LAT_P); this.groupBox4.Controls.Add(this.label16); + resources.ApplyResources(this.groupBox4, "groupBox4"); this.groupBox4.Name = "groupBox4"; this.groupBox4.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox4, resources.GetString("groupBox4.ToolTip")); // // WP_SPEED_MAX // resources.ApplyResources(this.WP_SPEED_MAX, "WP_SPEED_MAX"); this.WP_SPEED_MAX.Name = "WP_SPEED_MAX"; - this.toolTip1.SetToolTip(this.WP_SPEED_MAX, resources.GetString("WP_SPEED_MAX.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; - this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // NAV_LAT_IMAX // resources.ApplyResources(this.NAV_LAT_IMAX, "NAV_LAT_IMAX"); this.NAV_LAT_IMAX.Name = "NAV_LAT_IMAX"; - this.toolTip1.SetToolTip(this.NAV_LAT_IMAX, resources.GetString("NAV_LAT_IMAX.ToolTip")); // // label13 // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; - this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // NAV_LAT_I // resources.ApplyResources(this.NAV_LAT_I, "NAV_LAT_I"); this.NAV_LAT_I.Name = "NAV_LAT_I"; - this.toolTip1.SetToolTip(this.NAV_LAT_I, resources.GetString("NAV_LAT_I.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; - this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // NAV_LAT_P // resources.ApplyResources(this.NAV_LAT_P, "NAV_LAT_P"); this.NAV_LAT_P.Name = "NAV_LAT_P"; - this.toolTip1.SetToolTip(this.NAV_LAT_P, resources.GetString("NAV_LAT_P.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; - this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // groupBox6 // - resources.ApplyResources(this.groupBox6, "groupBox6"); this.groupBox6.Controls.Add(this.XTRK_ANGLE_CD1); this.groupBox6.Controls.Add(this.label10); this.groupBox6.Controls.Add(this.XTRACK_IMAX); @@ -1448,453 +1143,388 @@ this.groupBox6.Controls.Add(this.label17); this.groupBox6.Controls.Add(this.XTRACK_P); this.groupBox6.Controls.Add(this.label18); + resources.ApplyResources(this.groupBox6, "groupBox6"); this.groupBox6.Name = "groupBox6"; this.groupBox6.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox6, resources.GetString("groupBox6.ToolTip")); // // XTRK_ANGLE_CD1 // resources.ApplyResources(this.XTRK_ANGLE_CD1, "XTRK_ANGLE_CD1"); this.XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD1"; - this.toolTip1.SetToolTip(this.XTRK_ANGLE_CD1, resources.GetString("XTRK_ANGLE_CD1.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; - this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); // // XTRACK_IMAX // resources.ApplyResources(this.XTRACK_IMAX, "XTRACK_IMAX"); this.XTRACK_IMAX.Name = "XTRACK_IMAX"; - this.toolTip1.SetToolTip(this.XTRACK_IMAX, resources.GetString("XTRACK_IMAX.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; - this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // XTRACK_I // resources.ApplyResources(this.XTRACK_I, "XTRACK_I"); this.XTRACK_I.Name = "XTRACK_I"; - this.toolTip1.SetToolTip(this.XTRACK_I, resources.GetString("XTRACK_I.ToolTip")); // // label17 // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; - this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // XTRACK_P // resources.ApplyResources(this.XTRACK_P, "XTRACK_P"); this.XTRACK_P.Name = "XTRACK_P"; - this.toolTip1.SetToolTip(this.XTRACK_P, resources.GetString("XTRACK_P.ToolTip")); // // label18 // resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; - this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip")); // // groupBox7 // - resources.ApplyResources(this.groupBox7, "groupBox7"); this.groupBox7.Controls.Add(this.THR_ALT_IMAX); this.groupBox7.Controls.Add(this.label19); this.groupBox7.Controls.Add(this.THR_ALT_I); this.groupBox7.Controls.Add(this.label21); this.groupBox7.Controls.Add(this.THR_ALT_P); this.groupBox7.Controls.Add(this.label22); + resources.ApplyResources(this.groupBox7, "groupBox7"); this.groupBox7.Name = "groupBox7"; this.groupBox7.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox7, resources.GetString("groupBox7.ToolTip")); // // THR_ALT_IMAX // resources.ApplyResources(this.THR_ALT_IMAX, "THR_ALT_IMAX"); this.THR_ALT_IMAX.Name = "THR_ALT_IMAX"; - this.toolTip1.SetToolTip(this.THR_ALT_IMAX, resources.GetString("THR_ALT_IMAX.ToolTip")); // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; - this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip")); // // THR_ALT_I // resources.ApplyResources(this.THR_ALT_I, "THR_ALT_I"); this.THR_ALT_I.Name = "THR_ALT_I"; - this.toolTip1.SetToolTip(this.THR_ALT_I, resources.GetString("THR_ALT_I.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; - this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // THR_ALT_P // resources.ApplyResources(this.THR_ALT_P, "THR_ALT_P"); this.THR_ALT_P.Name = "THR_ALT_P"; - this.toolTip1.SetToolTip(this.THR_ALT_P, resources.GetString("THR_ALT_P.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; - this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // groupBox19 // - resources.ApplyResources(this.groupBox19, "groupBox19"); this.groupBox19.Controls.Add(this.HLD_LAT_IMAX); this.groupBox19.Controls.Add(this.label28); this.groupBox19.Controls.Add(this.HLD_LAT_I); this.groupBox19.Controls.Add(this.label30); this.groupBox19.Controls.Add(this.HLD_LAT_P); this.groupBox19.Controls.Add(this.label31); + resources.ApplyResources(this.groupBox19, "groupBox19"); this.groupBox19.Name = "groupBox19"; this.groupBox19.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox19, resources.GetString("groupBox19.ToolTip")); // // HLD_LAT_IMAX // resources.ApplyResources(this.HLD_LAT_IMAX, "HLD_LAT_IMAX"); this.HLD_LAT_IMAX.Name = "HLD_LAT_IMAX"; - this.toolTip1.SetToolTip(this.HLD_LAT_IMAX, resources.GetString("HLD_LAT_IMAX.ToolTip")); // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; - this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // HLD_LAT_I // resources.ApplyResources(this.HLD_LAT_I, "HLD_LAT_I"); this.HLD_LAT_I.Name = "HLD_LAT_I"; - this.toolTip1.SetToolTip(this.HLD_LAT_I, resources.GetString("HLD_LAT_I.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; - this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // HLD_LAT_P // resources.ApplyResources(this.HLD_LAT_P, "HLD_LAT_P"); this.HLD_LAT_P.Name = "HLD_LAT_P"; - this.toolTip1.SetToolTip(this.HLD_LAT_P, resources.GetString("HLD_LAT_P.ToolTip")); // // label31 // resources.ApplyResources(this.label31, "label31"); this.label31.Name = "label31"; - this.toolTip1.SetToolTip(this.label31, resources.GetString("label31.ToolTip")); // // groupBox20 // - resources.ApplyResources(this.groupBox20, "groupBox20"); this.groupBox20.Controls.Add(this.STB_YAW_IMAX); this.groupBox20.Controls.Add(this.label32); this.groupBox20.Controls.Add(this.STB_YAW_I); this.groupBox20.Controls.Add(this.label34); this.groupBox20.Controls.Add(this.STB_YAW_P); this.groupBox20.Controls.Add(this.label35); + resources.ApplyResources(this.groupBox20, "groupBox20"); this.groupBox20.Name = "groupBox20"; this.groupBox20.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox20, resources.GetString("groupBox20.ToolTip")); // // STB_YAW_IMAX // resources.ApplyResources(this.STB_YAW_IMAX, "STB_YAW_IMAX"); this.STB_YAW_IMAX.Name = "STB_YAW_IMAX"; - this.toolTip1.SetToolTip(this.STB_YAW_IMAX, resources.GetString("STB_YAW_IMAX.ToolTip")); // // label32 // resources.ApplyResources(this.label32, "label32"); this.label32.Name = "label32"; - this.toolTip1.SetToolTip(this.label32, resources.GetString("label32.ToolTip")); // // STB_YAW_I // resources.ApplyResources(this.STB_YAW_I, "STB_YAW_I"); this.STB_YAW_I.Name = "STB_YAW_I"; - this.toolTip1.SetToolTip(this.STB_YAW_I, resources.GetString("STB_YAW_I.ToolTip")); // // label34 // resources.ApplyResources(this.label34, "label34"); this.label34.Name = "label34"; - this.toolTip1.SetToolTip(this.label34, resources.GetString("label34.ToolTip")); // // STB_YAW_P // resources.ApplyResources(this.STB_YAW_P, "STB_YAW_P"); this.STB_YAW_P.Name = "STB_YAW_P"; - this.toolTip1.SetToolTip(this.STB_YAW_P, resources.GetString("STB_YAW_P.ToolTip")); // // label35 // resources.ApplyResources(this.label35, "label35"); this.label35.Name = "label35"; - this.toolTip1.SetToolTip(this.label35, resources.GetString("label35.ToolTip")); // // groupBox21 // - resources.ApplyResources(this.groupBox21, "groupBox21"); this.groupBox21.Controls.Add(this.STB_PIT_IMAX); this.groupBox21.Controls.Add(this.label36); this.groupBox21.Controls.Add(this.STB_PIT_I); this.groupBox21.Controls.Add(this.label41); this.groupBox21.Controls.Add(this.STB_PIT_P); this.groupBox21.Controls.Add(this.label42); + resources.ApplyResources(this.groupBox21, "groupBox21"); this.groupBox21.Name = "groupBox21"; this.groupBox21.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox21, resources.GetString("groupBox21.ToolTip")); // // STB_PIT_IMAX // resources.ApplyResources(this.STB_PIT_IMAX, "STB_PIT_IMAX"); this.STB_PIT_IMAX.Name = "STB_PIT_IMAX"; - this.toolTip1.SetToolTip(this.STB_PIT_IMAX, resources.GetString("STB_PIT_IMAX.ToolTip")); // // label36 // resources.ApplyResources(this.label36, "label36"); this.label36.Name = "label36"; - this.toolTip1.SetToolTip(this.label36, resources.GetString("label36.ToolTip")); // // STB_PIT_I // resources.ApplyResources(this.STB_PIT_I, "STB_PIT_I"); this.STB_PIT_I.Name = "STB_PIT_I"; - this.toolTip1.SetToolTip(this.STB_PIT_I, resources.GetString("STB_PIT_I.ToolTip")); // // label41 // resources.ApplyResources(this.label41, "label41"); this.label41.Name = "label41"; - this.toolTip1.SetToolTip(this.label41, resources.GetString("label41.ToolTip")); // // STB_PIT_P // resources.ApplyResources(this.STB_PIT_P, "STB_PIT_P"); this.STB_PIT_P.Name = "STB_PIT_P"; - this.toolTip1.SetToolTip(this.STB_PIT_P, resources.GetString("STB_PIT_P.ToolTip")); // // label42 // resources.ApplyResources(this.label42, "label42"); this.label42.Name = "label42"; - this.toolTip1.SetToolTip(this.label42, resources.GetString("label42.ToolTip")); // // groupBox22 // - resources.ApplyResources(this.groupBox22, "groupBox22"); this.groupBox22.Controls.Add(this.STB_RLL_IMAX); this.groupBox22.Controls.Add(this.label43); this.groupBox22.Controls.Add(this.STB_RLL_I); this.groupBox22.Controls.Add(this.label45); this.groupBox22.Controls.Add(this.STB_RLL_P); this.groupBox22.Controls.Add(this.label46); + resources.ApplyResources(this.groupBox22, "groupBox22"); this.groupBox22.Name = "groupBox22"; this.groupBox22.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox22, resources.GetString("groupBox22.ToolTip")); // // STB_RLL_IMAX // resources.ApplyResources(this.STB_RLL_IMAX, "STB_RLL_IMAX"); this.STB_RLL_IMAX.Name = "STB_RLL_IMAX"; - this.toolTip1.SetToolTip(this.STB_RLL_IMAX, resources.GetString("STB_RLL_IMAX.ToolTip")); // // label43 // resources.ApplyResources(this.label43, "label43"); this.label43.Name = "label43"; - this.toolTip1.SetToolTip(this.label43, resources.GetString("label43.ToolTip")); // // STB_RLL_I // resources.ApplyResources(this.STB_RLL_I, "STB_RLL_I"); this.STB_RLL_I.Name = "STB_RLL_I"; - this.toolTip1.SetToolTip(this.STB_RLL_I, resources.GetString("STB_RLL_I.ToolTip")); // // label45 // resources.ApplyResources(this.label45, "label45"); this.label45.Name = "label45"; - this.toolTip1.SetToolTip(this.label45, resources.GetString("label45.ToolTip")); // // STB_RLL_P // resources.ApplyResources(this.STB_RLL_P, "STB_RLL_P"); this.STB_RLL_P.Name = "STB_RLL_P"; - this.toolTip1.SetToolTip(this.STB_RLL_P, resources.GetString("STB_RLL_P.ToolTip")); // // label46 // resources.ApplyResources(this.label46, "label46"); this.label46.Name = "label46"; - this.toolTip1.SetToolTip(this.label46, resources.GetString("label46.ToolTip")); // // groupBox23 // - resources.ApplyResources(this.groupBox23, "groupBox23"); this.groupBox23.Controls.Add(this.RATE_YAW_IMAX); this.groupBox23.Controls.Add(this.label47); this.groupBox23.Controls.Add(this.RATE_YAW_I); this.groupBox23.Controls.Add(this.label77); this.groupBox23.Controls.Add(this.RATE_YAW_P); this.groupBox23.Controls.Add(this.label82); + resources.ApplyResources(this.groupBox23, "groupBox23"); this.groupBox23.Name = "groupBox23"; this.groupBox23.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox23, resources.GetString("groupBox23.ToolTip")); // // RATE_YAW_IMAX // resources.ApplyResources(this.RATE_YAW_IMAX, "RATE_YAW_IMAX"); this.RATE_YAW_IMAX.Name = "RATE_YAW_IMAX"; - this.toolTip1.SetToolTip(this.RATE_YAW_IMAX, resources.GetString("RATE_YAW_IMAX.ToolTip")); // // label47 // resources.ApplyResources(this.label47, "label47"); this.label47.Name = "label47"; - this.toolTip1.SetToolTip(this.label47, resources.GetString("label47.ToolTip")); // // RATE_YAW_I // resources.ApplyResources(this.RATE_YAW_I, "RATE_YAW_I"); this.RATE_YAW_I.Name = "RATE_YAW_I"; - this.toolTip1.SetToolTip(this.RATE_YAW_I, resources.GetString("RATE_YAW_I.ToolTip")); // // label77 // resources.ApplyResources(this.label77, "label77"); this.label77.Name = "label77"; - this.toolTip1.SetToolTip(this.label77, resources.GetString("label77.ToolTip")); // // RATE_YAW_P // resources.ApplyResources(this.RATE_YAW_P, "RATE_YAW_P"); this.RATE_YAW_P.Name = "RATE_YAW_P"; - this.toolTip1.SetToolTip(this.RATE_YAW_P, resources.GetString("RATE_YAW_P.ToolTip")); // // label82 // resources.ApplyResources(this.label82, "label82"); this.label82.Name = "label82"; - this.toolTip1.SetToolTip(this.label82, resources.GetString("label82.ToolTip")); // // groupBox24 // - resources.ApplyResources(this.groupBox24, "groupBox24"); this.groupBox24.Controls.Add(this.RATE_PIT_IMAX); this.groupBox24.Controls.Add(this.label84); this.groupBox24.Controls.Add(this.RATE_PIT_I); this.groupBox24.Controls.Add(this.label86); this.groupBox24.Controls.Add(this.RATE_PIT_P); this.groupBox24.Controls.Add(this.label87); + resources.ApplyResources(this.groupBox24, "groupBox24"); this.groupBox24.Name = "groupBox24"; this.groupBox24.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox24, resources.GetString("groupBox24.ToolTip")); // // RATE_PIT_IMAX // resources.ApplyResources(this.RATE_PIT_IMAX, "RATE_PIT_IMAX"); this.RATE_PIT_IMAX.Name = "RATE_PIT_IMAX"; - this.toolTip1.SetToolTip(this.RATE_PIT_IMAX, resources.GetString("RATE_PIT_IMAX.ToolTip")); // // label84 // resources.ApplyResources(this.label84, "label84"); this.label84.Name = "label84"; - this.toolTip1.SetToolTip(this.label84, resources.GetString("label84.ToolTip")); // // RATE_PIT_I // resources.ApplyResources(this.RATE_PIT_I, "RATE_PIT_I"); this.RATE_PIT_I.Name = "RATE_PIT_I"; - this.toolTip1.SetToolTip(this.RATE_PIT_I, resources.GetString("RATE_PIT_I.ToolTip")); // // label86 // resources.ApplyResources(this.label86, "label86"); this.label86.Name = "label86"; - this.toolTip1.SetToolTip(this.label86, resources.GetString("label86.ToolTip")); // // RATE_PIT_P // resources.ApplyResources(this.RATE_PIT_P, "RATE_PIT_P"); this.RATE_PIT_P.Name = "RATE_PIT_P"; - this.toolTip1.SetToolTip(this.RATE_PIT_P, resources.GetString("RATE_PIT_P.ToolTip")); // // label87 // resources.ApplyResources(this.label87, "label87"); this.label87.Name = "label87"; - this.toolTip1.SetToolTip(this.label87, resources.GetString("label87.ToolTip")); // // groupBox25 // - resources.ApplyResources(this.groupBox25, "groupBox25"); this.groupBox25.Controls.Add(this.RATE_RLL_IMAX); this.groupBox25.Controls.Add(this.label88); this.groupBox25.Controls.Add(this.RATE_RLL_I); this.groupBox25.Controls.Add(this.label90); this.groupBox25.Controls.Add(this.RATE_RLL_P); this.groupBox25.Controls.Add(this.label91); + resources.ApplyResources(this.groupBox25, "groupBox25"); this.groupBox25.Name = "groupBox25"; this.groupBox25.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox25, resources.GetString("groupBox25.ToolTip")); // // RATE_RLL_IMAX // resources.ApplyResources(this.RATE_RLL_IMAX, "RATE_RLL_IMAX"); this.RATE_RLL_IMAX.Name = "RATE_RLL_IMAX"; - this.toolTip1.SetToolTip(this.RATE_RLL_IMAX, resources.GetString("RATE_RLL_IMAX.ToolTip")); // // label88 // resources.ApplyResources(this.label88, "label88"); this.label88.Name = "label88"; - this.toolTip1.SetToolTip(this.label88, resources.GetString("label88.ToolTip")); // // RATE_RLL_I // resources.ApplyResources(this.RATE_RLL_I, "RATE_RLL_I"); this.RATE_RLL_I.Name = "RATE_RLL_I"; - this.toolTip1.SetToolTip(this.RATE_RLL_I, resources.GetString("RATE_RLL_I.ToolTip")); // // label90 // resources.ApplyResources(this.label90, "label90"); this.label90.Name = "label90"; - this.toolTip1.SetToolTip(this.label90, resources.GetString("label90.ToolTip")); // // RATE_RLL_P // resources.ApplyResources(this.RATE_RLL_P, "RATE_RLL_P"); this.RATE_RLL_P.Name = "RATE_RLL_P"; - this.toolTip1.SetToolTip(this.RATE_RLL_P, resources.GetString("RATE_RLL_P.ToolTip")); // // label91 // resources.ApplyResources(this.label91, "label91"); this.label91.Name = "label91"; - this.toolTip1.SetToolTip(this.label91, resources.GetString("label91.ToolTip")); // // TabPlanner // - resources.ApplyResources(this.TabPlanner, "TabPlanner"); this.TabPlanner.Controls.Add(this.label26); this.TabPlanner.Controls.Add(this.CMB_videoresolutions); this.TabPlanner.Controls.Add(this.label12); @@ -1938,28 +1568,25 @@ this.TabPlanner.Controls.Add(this.BUT_Joystick); this.TabPlanner.Controls.Add(this.BUT_videostop); this.TabPlanner.Controls.Add(this.BUT_videostart); + resources.ApplyResources(this.TabPlanner, "TabPlanner"); this.TabPlanner.Name = "TabPlanner"; - this.toolTip1.SetToolTip(this.TabPlanner, resources.GetString("TabPlanner.ToolTip")); // // label26 // resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; - this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // CMB_videoresolutions // - resources.ApplyResources(this.CMB_videoresolutions, "CMB_videoresolutions"); this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videoresolutions.FormattingEnabled = true; + resources.ApplyResources(this.CMB_videoresolutions, "CMB_videoresolutions"); this.CMB_videoresolutions.Name = "CMB_videoresolutions"; - this.toolTip1.SetToolTip(this.CMB_videoresolutions, resources.GetString("CMB_videoresolutions.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; - this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // CHK_GDIPlus // @@ -1973,13 +1600,11 @@ // resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; - this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // CHK_loadwponconnect // resources.ApplyResources(this.CHK_loadwponconnect, "CHK_loadwponconnect"); this.CHK_loadwponconnect.Name = "CHK_loadwponconnect"; - this.toolTip1.SetToolTip(this.CHK_loadwponconnect, resources.GetString("CHK_loadwponconnect.ToolTip")); this.CHK_loadwponconnect.UseVisualStyleBackColor = true; this.CHK_loadwponconnect.CheckedChanged += new System.EventHandler(this.CHK_loadwponconnect_CheckedChanged); // @@ -1987,16 +1612,15 @@ // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; - this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // NUM_tracklength // - resources.ApplyResources(this.NUM_tracklength, "NUM_tracklength"); this.NUM_tracklength.Increment = new decimal(new int[] { 100, 0, 0, 0}); + resources.ApplyResources(this.NUM_tracklength, "NUM_tracklength"); this.NUM_tracklength.Maximum = new decimal(new int[] { 2000, 0, @@ -2020,7 +1644,6 @@ // resources.ApplyResources(this.CHK_speechaltwarning, "CHK_speechaltwarning"); this.CHK_speechaltwarning.Name = "CHK_speechaltwarning"; - this.toolTip1.SetToolTip(this.CHK_speechaltwarning, resources.GetString("CHK_speechaltwarning.ToolTip")); this.CHK_speechaltwarning.UseVisualStyleBackColor = true; this.CHK_speechaltwarning.CheckedChanged += new System.EventHandler(this.CHK_speechaltwarning_CheckedChanged); // @@ -2028,15 +1651,13 @@ // resources.ApplyResources(this.label108, "label108"); this.label108.Name = "label108"; - this.toolTip1.SetToolTip(this.label108, resources.GetString("label108.ToolTip")); // // CHK_resetapmonconnect // - resources.ApplyResources(this.CHK_resetapmonconnect, "CHK_resetapmonconnect"); this.CHK_resetapmonconnect.Checked = true; this.CHK_resetapmonconnect.CheckState = System.Windows.Forms.CheckState.Checked; + resources.ApplyResources(this.CHK_resetapmonconnect, "CHK_resetapmonconnect"); this.CHK_resetapmonconnect.Name = "CHK_resetapmonconnect"; - this.toolTip1.SetToolTip(this.CHK_resetapmonconnect, resources.GetString("CHK_resetapmonconnect.ToolTip")); this.CHK_resetapmonconnect.UseVisualStyleBackColor = true; this.CHK_resetapmonconnect.CheckedChanged += new System.EventHandler(this.CHK_resetapmonconnect_CheckedChanged); // @@ -2044,7 +1665,6 @@ // resources.ApplyResources(this.CHK_mavdebug, "CHK_mavdebug"); this.CHK_mavdebug.Name = "CHK_mavdebug"; - this.toolTip1.SetToolTip(this.CHK_mavdebug, resources.GetString("CHK_mavdebug.ToolTip")); this.CHK_mavdebug.UseVisualStyleBackColor = true; this.CHK_mavdebug.CheckedChanged += new System.EventHandler(this.CHK_mavdebug_CheckedChanged); // @@ -2052,11 +1672,9 @@ // resources.ApplyResources(this.label107, "label107"); this.label107.Name = "label107"; - this.toolTip1.SetToolTip(this.label107, resources.GetString("label107.ToolTip")); // // CMB_raterc // - resources.ApplyResources(this.CMB_raterc, "CMB_raterc"); this.CMB_raterc.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_raterc.FormattingEnabled = true; this.CMB_raterc.Items.AddRange(new object[] { @@ -2064,37 +1682,32 @@ resources.GetString("CMB_raterc.Items1"), resources.GetString("CMB_raterc.Items2"), resources.GetString("CMB_raterc.Items3")}); + resources.ApplyResources(this.CMB_raterc, "CMB_raterc"); this.CMB_raterc.Name = "CMB_raterc"; - this.toolTip1.SetToolTip(this.CMB_raterc, resources.GetString("CMB_raterc.ToolTip")); this.CMB_raterc.SelectedIndexChanged += new System.EventHandler(this.CMB_raterc_SelectedIndexChanged); // // label104 // resources.ApplyResources(this.label104, "label104"); this.label104.Name = "label104"; - this.toolTip1.SetToolTip(this.label104, resources.GetString("label104.ToolTip")); // // label103 // resources.ApplyResources(this.label103, "label103"); this.label103.Name = "label103"; - this.toolTip1.SetToolTip(this.label103, resources.GetString("label103.ToolTip")); // // label102 // resources.ApplyResources(this.label102, "label102"); this.label102.Name = "label102"; - this.toolTip1.SetToolTip(this.label102, resources.GetString("label102.ToolTip")); // // label101 // resources.ApplyResources(this.label101, "label101"); this.label101.Name = "label101"; - this.toolTip1.SetToolTip(this.label101, resources.GetString("label101.ToolTip")); // // CMB_ratestatus // - resources.ApplyResources(this.CMB_ratestatus, "CMB_ratestatus"); this.CMB_ratestatus.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_ratestatus.FormattingEnabled = true; this.CMB_ratestatus.Items.AddRange(new object[] { @@ -2102,13 +1715,12 @@ resources.GetString("CMB_ratestatus.Items1"), resources.GetString("CMB_ratestatus.Items2"), resources.GetString("CMB_ratestatus.Items3")}); + resources.ApplyResources(this.CMB_ratestatus, "CMB_ratestatus"); this.CMB_ratestatus.Name = "CMB_ratestatus"; - this.toolTip1.SetToolTip(this.CMB_ratestatus, resources.GetString("CMB_ratestatus.ToolTip")); this.CMB_ratestatus.SelectedIndexChanged += new System.EventHandler(this.CMB_ratestatus_SelectedIndexChanged); // // CMB_rateposition // - resources.ApplyResources(this.CMB_rateposition, "CMB_rateposition"); this.CMB_rateposition.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_rateposition.FormattingEnabled = true; this.CMB_rateposition.Items.AddRange(new object[] { @@ -2116,13 +1728,12 @@ resources.GetString("CMB_rateposition.Items1"), resources.GetString("CMB_rateposition.Items2"), resources.GetString("CMB_rateposition.Items3")}); + resources.ApplyResources(this.CMB_rateposition, "CMB_rateposition"); this.CMB_rateposition.Name = "CMB_rateposition"; - this.toolTip1.SetToolTip(this.CMB_rateposition, resources.GetString("CMB_rateposition.ToolTip")); this.CMB_rateposition.SelectedIndexChanged += new System.EventHandler(this.CMB_rateposition_SelectedIndexChanged); // // CMB_rateattitude // - resources.ApplyResources(this.CMB_rateattitude, "CMB_rateattitude"); this.CMB_rateattitude.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_rateattitude.FormattingEnabled = true; this.CMB_rateattitude.Items.AddRange(new object[] { @@ -2130,63 +1741,55 @@ resources.GetString("CMB_rateattitude.Items1"), resources.GetString("CMB_rateattitude.Items2"), resources.GetString("CMB_rateattitude.Items3")}); + resources.ApplyResources(this.CMB_rateattitude, "CMB_rateattitude"); this.CMB_rateattitude.Name = "CMB_rateattitude"; - this.toolTip1.SetToolTip(this.CMB_rateattitude, resources.GetString("CMB_rateattitude.ToolTip")); this.CMB_rateattitude.SelectedIndexChanged += new System.EventHandler(this.CMB_rateattitude_SelectedIndexChanged); // // label99 // resources.ApplyResources(this.label99, "label99"); this.label99.Name = "label99"; - this.toolTip1.SetToolTip(this.label99, resources.GetString("label99.ToolTip")); // // label98 // resources.ApplyResources(this.label98, "label98"); this.label98.Name = "label98"; - this.toolTip1.SetToolTip(this.label98, resources.GetString("label98.ToolTip")); // // label97 // resources.ApplyResources(this.label97, "label97"); this.label97.Name = "label97"; - this.toolTip1.SetToolTip(this.label97, resources.GetString("label97.ToolTip")); // // CMB_speedunits // - resources.ApplyResources(this.CMB_speedunits, "CMB_speedunits"); this.CMB_speedunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_speedunits.FormattingEnabled = true; + resources.ApplyResources(this.CMB_speedunits, "CMB_speedunits"); this.CMB_speedunits.Name = "CMB_speedunits"; - this.toolTip1.SetToolTip(this.CMB_speedunits, resources.GetString("CMB_speedunits.ToolTip")); this.CMB_speedunits.SelectedIndexChanged += new System.EventHandler(this.CMB_speedunits_SelectedIndexChanged); // // CMB_distunits // - resources.ApplyResources(this.CMB_distunits, "CMB_distunits"); this.CMB_distunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_distunits.FormattingEnabled = true; + resources.ApplyResources(this.CMB_distunits, "CMB_distunits"); this.CMB_distunits.Name = "CMB_distunits"; - this.toolTip1.SetToolTip(this.CMB_distunits, resources.GetString("CMB_distunits.ToolTip")); this.CMB_distunits.SelectedIndexChanged += new System.EventHandler(this.CMB_distunits_SelectedIndexChanged); // // label96 // resources.ApplyResources(this.label96, "label96"); this.label96.Name = "label96"; - this.toolTip1.SetToolTip(this.label96, resources.GetString("label96.ToolTip")); // // label95 // resources.ApplyResources(this.label95, "label95"); this.label95.Name = "label95"; - this.toolTip1.SetToolTip(this.label95, resources.GetString("label95.ToolTip")); // // CHK_speechbattery // resources.ApplyResources(this.CHK_speechbattery, "CHK_speechbattery"); this.CHK_speechbattery.Name = "CHK_speechbattery"; - this.toolTip1.SetToolTip(this.CHK_speechbattery, resources.GetString("CHK_speechbattery.ToolTip")); this.CHK_speechbattery.UseVisualStyleBackColor = true; this.CHK_speechbattery.CheckedChanged += new System.EventHandler(this.CHK_speechbattery_CheckedChanged); // @@ -2194,7 +1797,6 @@ // resources.ApplyResources(this.CHK_speechcustom, "CHK_speechcustom"); this.CHK_speechcustom.Name = "CHK_speechcustom"; - this.toolTip1.SetToolTip(this.CHK_speechcustom, resources.GetString("CHK_speechcustom.ToolTip")); this.CHK_speechcustom.UseVisualStyleBackColor = true; this.CHK_speechcustom.CheckedChanged += new System.EventHandler(this.CHK_speechcustom_CheckedChanged); // @@ -2202,7 +1804,6 @@ // resources.ApplyResources(this.CHK_speechmode, "CHK_speechmode"); this.CHK_speechmode.Name = "CHK_speechmode"; - this.toolTip1.SetToolTip(this.CHK_speechmode, resources.GetString("CHK_speechmode.ToolTip")); this.CHK_speechmode.UseVisualStyleBackColor = true; this.CHK_speechmode.CheckedChanged += new System.EventHandler(this.CHK_speechmode_CheckedChanged); // @@ -2210,7 +1811,6 @@ // resources.ApplyResources(this.CHK_speechwaypoint, "CHK_speechwaypoint"); this.CHK_speechwaypoint.Name = "CHK_speechwaypoint"; - this.toolTip1.SetToolTip(this.CHK_speechwaypoint, resources.GetString("CHK_speechwaypoint.ToolTip")); this.CHK_speechwaypoint.UseVisualStyleBackColor = true; this.CHK_speechwaypoint.CheckedChanged += new System.EventHandler(this.CHK_speechwaypoint_CheckedChanged); // @@ -2218,48 +1818,42 @@ // resources.ApplyResources(this.label94, "label94"); this.label94.Name = "label94"; - this.toolTip1.SetToolTip(this.label94, resources.GetString("label94.ToolTip")); // // CMB_osdcolor // - resources.ApplyResources(this.CMB_osdcolor, "CMB_osdcolor"); this.CMB_osdcolor.DrawMode = System.Windows.Forms.DrawMode.OwnerDrawFixed; this.CMB_osdcolor.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_osdcolor.FormattingEnabled = true; + resources.ApplyResources(this.CMB_osdcolor, "CMB_osdcolor"); this.CMB_osdcolor.Name = "CMB_osdcolor"; - this.toolTip1.SetToolTip(this.CMB_osdcolor, resources.GetString("CMB_osdcolor.ToolTip")); this.CMB_osdcolor.DrawItem += new System.Windows.Forms.DrawItemEventHandler(this.CMB_osdcolor_DrawItem); this.CMB_osdcolor.SelectedIndexChanged += new System.EventHandler(this.CMB_osdcolor_SelectedIndexChanged); // // CMB_language // - resources.ApplyResources(this.CMB_language, "CMB_language"); this.CMB_language.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_language.FormattingEnabled = true; + resources.ApplyResources(this.CMB_language, "CMB_language"); this.CMB_language.Name = "CMB_language"; - this.toolTip1.SetToolTip(this.CMB_language, resources.GetString("CMB_language.ToolTip")); // // label93 // resources.ApplyResources(this.label93, "label93"); this.label93.Name = "label93"; - this.toolTip1.SetToolTip(this.label93, resources.GetString("label93.ToolTip")); // // CHK_enablespeech // resources.ApplyResources(this.CHK_enablespeech, "CHK_enablespeech"); this.CHK_enablespeech.Name = "CHK_enablespeech"; - this.toolTip1.SetToolTip(this.CHK_enablespeech, resources.GetString("CHK_enablespeech.ToolTip")); this.CHK_enablespeech.UseVisualStyleBackColor = true; this.CHK_enablespeech.CheckedChanged += new System.EventHandler(this.CHK_enablespeech_CheckedChanged); // // CHK_hudshow // - resources.ApplyResources(this.CHK_hudshow, "CHK_hudshow"); this.CHK_hudshow.Checked = true; this.CHK_hudshow.CheckState = System.Windows.Forms.CheckState.Checked; + resources.ApplyResources(this.CHK_hudshow, "CHK_hudshow"); this.CHK_hudshow.Name = "CHK_hudshow"; - this.toolTip1.SetToolTip(this.CHK_hudshow, resources.GetString("CHK_hudshow.ToolTip")); this.CHK_hudshow.UseVisualStyleBackColor = true; this.CHK_hudshow.CheckedChanged += new System.EventHandler(this.CHK_hudshow_CheckedChanged); // @@ -2267,15 +1861,13 @@ // resources.ApplyResources(this.label92, "label92"); this.label92.Name = "label92"; - this.toolTip1.SetToolTip(this.label92, resources.GetString("label92.ToolTip")); // // CMB_videosources // - resources.ApplyResources(this.CMB_videosources, "CMB_videosources"); this.CMB_videosources.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videosources.FormattingEnabled = true; + resources.ApplyResources(this.CMB_videosources, "CMB_videosources"); this.CMB_videosources.Name = "CMB_videosources"; - this.toolTip1.SetToolTip(this.CMB_videosources, resources.GetString("CMB_videosources.ToolTip")); this.CMB_videosources.SelectedIndexChanged += new System.EventHandler(this.CMB_videosources_SelectedIndexChanged); this.CMB_videosources.MouseClick += new System.Windows.Forms.MouseEventHandler(this.CMB_videosources_MouseClick); // @@ -2283,7 +1875,6 @@ // resources.ApplyResources(this.BUT_Joystick, "BUT_Joystick"); this.BUT_Joystick.Name = "BUT_Joystick"; - this.toolTip1.SetToolTip(this.BUT_Joystick, resources.GetString("BUT_Joystick.ToolTip")); this.BUT_Joystick.UseVisualStyleBackColor = true; this.BUT_Joystick.Click += new System.EventHandler(this.BUT_Joystick_Click); // @@ -2291,7 +1882,6 @@ // resources.ApplyResources(this.BUT_videostop, "BUT_videostop"); this.BUT_videostop.Name = "BUT_videostop"; - this.toolTip1.SetToolTip(this.BUT_videostop, resources.GetString("BUT_videostop.ToolTip")); this.BUT_videostop.UseVisualStyleBackColor = true; this.BUT_videostop.Click += new System.EventHandler(this.BUT_videostop_Click); // @@ -2299,7 +1889,6 @@ // resources.ApplyResources(this.BUT_videostart, "BUT_videostart"); this.BUT_videostart.Name = "BUT_videostart"; - this.toolTip1.SetToolTip(this.BUT_videostart, resources.GetString("BUT_videostart.ToolTip")); this.BUT_videostart.UseVisualStyleBackColor = true; this.BUT_videostart.Click += new System.EventHandler(this.BUT_videostart_Click); // @@ -2307,14 +1896,12 @@ // resources.ApplyResources(this.TabSetup, "TabSetup"); this.TabSetup.Name = "TabSetup"; - this.toolTip1.SetToolTip(this.TabSetup, resources.GetString("TabSetup.ToolTip")); this.TabSetup.UseVisualStyleBackColor = true; // // label109 // resources.ApplyResources(this.label109, "label109"); this.label109.Name = "label109"; - this.toolTip1.SetToolTip(this.label109, resources.GetString("label109.ToolTip")); // // BUT_rerequestparams // @@ -2352,10 +1939,93 @@ // resources.ApplyResources(this.BUT_compare, "BUT_compare"); this.BUT_compare.Name = "BUT_compare"; - this.toolTip1.SetToolTip(this.BUT_compare, resources.GetString("BUT_compare.ToolTip")); this.BUT_compare.UseVisualStyleBackColor = true; this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click); // + // groupBox17 + // + this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX); + this.groupBox17.Controls.Add(this.label27); + this.groupBox17.Controls.Add(this.ACRO_PIT_I); + this.groupBox17.Controls.Add(this.label29); + this.groupBox17.Controls.Add(this.ACRO_PIT_P); + this.groupBox17.Controls.Add(this.label33); + resources.ApplyResources(this.groupBox17, "groupBox17"); + this.groupBox17.Name = "groupBox17"; + this.groupBox17.TabStop = false; + // + // ACRO_PIT_IMAX + // + resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX"); + this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX"; + // + // label27 + // + resources.ApplyResources(this.label27, "label27"); + this.label27.Name = "label27"; + // + // ACRO_PIT_I + // + resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I"); + this.ACRO_PIT_I.Name = "ACRO_PIT_I"; + // + // label29 + // + resources.ApplyResources(this.label29, "label29"); + this.label29.Name = "label29"; + // + // ACRO_PIT_P + // + resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P"); + this.ACRO_PIT_P.Name = "ACRO_PIT_P"; + // + // label33 + // + resources.ApplyResources(this.label33, "label33"); + this.label33.Name = "label33"; + // + // groupBox18 + // + this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX); + this.groupBox18.Controls.Add(this.label40); + this.groupBox18.Controls.Add(this.ACRO_RLL_I); + this.groupBox18.Controls.Add(this.label44); + this.groupBox18.Controls.Add(this.ACRO_RLL_P); + this.groupBox18.Controls.Add(this.label48); + resources.ApplyResources(this.groupBox18, "groupBox18"); + this.groupBox18.Name = "groupBox18"; + this.groupBox18.TabStop = false; + // + // ACRO_RLL_IMAX + // + resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX"); + this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX"; + // + // label40 + // + resources.ApplyResources(this.label40, "label40"); + this.label40.Name = "label40"; + // + // ACRO_RLL_I + // + resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I"); + this.ACRO_RLL_I.Name = "ACRO_RLL_I"; + // + // label44 + // + resources.ApplyResources(this.label44, "label44"); + this.label44.Name = "label44"; + // + // ACRO_RLL_P + // + resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P"); + this.ACRO_RLL_P.Name = "ACRO_RLL_P"; + // + // label48 + // + resources.ApplyResources(this.label48, "label48"); + this.label48.Name = "label48"; + // // Configuration // resources.ApplyResources(this, "$this"); @@ -2369,125 +2039,39 @@ this.Controls.Add(this.BUT_load); this.Controls.Add(this.Params); this.Name = "Configuration"; - this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.Load += new System.EventHandler(this.Configuration_Load); ((System.ComponentModel.ISupportInitialize)(this.Params)).EndInit(); this.ConfigTabs.ResumeLayout(false); this.TabAPM2.ResumeLayout(false); this.groupBox3.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).EndInit(); this.groupBox1.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).EndInit(); this.groupBox2.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).EndInit(); this.groupBox15.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).EndInit(); this.groupBox16.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).EndInit(); this.groupBox14.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).EndInit(); this.groupBox13.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).EndInit(); this.groupBox12.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).EndInit(); this.groupBox11.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).EndInit(); this.groupBox10.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).EndInit(); this.groupBox9.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).EndInit(); this.groupBox8.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).EndInit(); this.TabAC2.ResumeLayout(false); this.TabAC2.PerformLayout(); - this.groupBox17.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_P)).EndInit(); this.groupBox5.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).EndInit(); - this.groupBox18.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_P)).EndInit(); this.groupBox4.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).EndInit(); this.groupBox6.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD1)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRACK_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRACK_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.XTRACK_P)).EndInit(); this.groupBox7.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).EndInit(); this.groupBox19.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).EndInit(); this.groupBox20.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).EndInit(); this.groupBox21.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).EndInit(); this.groupBox22.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).EndInit(); this.groupBox23.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).EndInit(); this.groupBox24.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).EndInit(); this.groupBox25.ResumeLayout(false); - ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).EndInit(); this.TabPlanner.ResumeLayout(false); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit(); + this.groupBox17.ResumeLayout(false); + this.groupBox18.ResumeLayout(false); this.ResumeLayout(false); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx index 7b9725cee3..c5e12aff50 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx @@ -117,2843 +117,5340 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - THR_FS_VALUE - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Top, Bottom, Left - - 29 + + True - - groupBox14 + + Command - - - 722, 434 + + 150 - - label50 + + True - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Value - - P + + 80 - - ConfigTabs + + True - - groupBox10 - - - I - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - INT_MAX - - - 78, 20 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 1 - - - 390, 11 - - - - - - RATE_YAW_IMAX - - - label22 - - - label51 - - - groupBox15 - - - 5 - - - 6, 16 - - - Setup - - - 3 - - - 61, 13 - - - INT_MAX - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 170, 91 - - - - - - - - - RATE_RLL_IMAX - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 87 - - - - - - XTRK_ANGLE_CD1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox19 - - - - NoControl - - - label56 - - - 111, 59 - - - groupBox16 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - THR_RATE_P - - - 80, 63 - - - 5 - - - 27, 244 - - - 13 - - - groupBox21 - - - - - - groupBox5 - - - 69, 13 - - - 80, 13 - - - label28 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - WP_SPEED_MAX - - - GDI+ (old type) - - - groupBox24 - - - - - - label57 - - - - - - 111, 36 - - - 7 - - - 65, 13 - - - P - - + Default - - groupBox8 - - - NoControl - - - 3, 416 - - - 22, 13 - - - label29 - - - 3, 3, 3, 3 - - - groupBox24 - - - 80, 21 - - - IMAX - - - P - - - INT_MAX - - - I - - - 136, 244 - - - Dist Units - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - - 6, 221 - - - NoControl - - - 722, 434 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabPlanner - - - NoControl - - - 408, 21 - - - groupBox18 - - - FBW max - - - 65, 13 - - - CHK_hudshow - - - 78, 20 - - - groupBox12 - - - STB_PIT_I - - - 15 - - - 3 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 9 - - - groupBox5 - - - label52 - - - 80, 13 - - - 78, 20 - - - label102 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - YW2SRV_IMAX - - - 4, 109 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 78, 20 - - - 5 - - - 11 - - - 40 - - - 111, 36 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 16 - - - groupBox7 - - - - - - TabPlanner - - - 78, 20 - - - 65, 13 - - - label53 - - - RATE_PIT_IMAX - - - 531, 6 - - - groupBox23 - - - 0 - - - 0 - - - 4 - - - 2 - - - label94 - - - 7 - - - 6 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 43, 13 - - - label58 - - - TabAC2 - - - 11 - - - ACRO_RLL_P - - - UI Language - - - groupBox1 - - - groupBox16 - - - - - - - - - NAV_LAT_I - - - 111, 13 - - - 205, 1 - - - 1 - - - label95 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 730, 460 - - - 7 - - - groupBox17 - - - label59 - - - TabAPM2 - - - label24 - - - NoControl - - - 0 - - - 111, 36 - - - - - - groupBox25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - False - + + mavScale + + + False + + + True + + + RawValue + + + False + + + + 3, 3 + + + 150 + + + 269, 409 + + + 58 + + + Params + + + System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + 6 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Top, Bottom, Left, Right - - groupBox22 + + 111, 82 - + + 78, 20 + + + 11 + + + THR_FS_VALUE + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + 0 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - + + 6, 86 + + + 50, 13 + + + 12 + + + FS Value + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 1 + + + 111, 59 + + 78, 20 - - HDNG2RLL_P + + 9 - + + THR_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 2 + + + NoControl + + + 6, 63 + + + 27, 13 + + + 13 + + + Max + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 111, 36 + + 78, 20 + + 7 + + + THR_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 4 + + + NoControl + + + 6, 40 + + + 24, 13 + + + 14 + + + Min + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + TRIM_THROTTLE + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 6 + + + NoControl + + + 6, 17 + + + 36, 13 + + + 15 + + + Cruise + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 7 + + + 405, 217 + + + 195, 108 + + + 0 + + + Throttle 0-100% + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 0 + + + 111, 82 + + + 78, 20 + + + 0 + + + ARSPD_RATIO + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 0 + + + NoControl + + + 6, 87 + + + 32, 13 + + + 1 + + + Ratio + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 1 + + + 111, 59 + + + 78, 20 + + + 2 + + + ARSPD_FBW_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + NoControl + + + 6, 59 + + + 53, 13 + + + 3 + + + FBW max + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + 111, 36 + + + 78, 20 + + + 4 + + + ARSPD_FBW_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + NoControl + + + 6, 40 + + + 50, 13 + + + 5 + + + FBW min + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + TRIM_ARSPD_CM + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 6 + + + NoControl + + + 6, 17 + + + 64, 13 + + + 6 + + + Cruise + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 7 + + + 406, 325 + + + 195, 108 + + + 1 + + + Airspeed m/s + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + LIM_PITCH_MIN + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + NoControl + + + 6, 63 + + + 51, 13 + + + 10 + + + Pitch Min + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + 111, 36 + + + 78, 20 + + + 7 + + + LIM_PITCH_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + NoControl + + + 6, 40 + + + 54, 13 + + + 11 + + + Pitch Max + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 111, 13 + + + 78, 20 + + + 5 + + + LIM_ROLL_CD + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 4 + + + NoControl + + + 6, 17 + + + 55, 13 + + + 12 + + + Bank Max + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 5 + + + 205, 325 + + + 195, 108 + + + 2 + + + Navigation Angles + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 2 + + + 111, 36 + + + 78, 20 + + + 7 + + + XTRK_ANGLE_CD + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 0 + + + NoControl + + + 6, 40 + + + 61, 13 + + + 8 + + + Entry Angle + + + label79 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 1 + + + 111, 13 + + + 78, 20 + + + 5 + + + XTRK_GAIN_SC + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 2 + + + NoControl + + + 6, 17 + + + 52, 13 + + + 9 + + + Gain (cm) + + + label80 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox15 + + + 3 + + + 4, 325 + + + 195, 108 + + + 3 + + + Xtrack Pids + + + groupBox15 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 3 + + + 111, 13 + + + 78, 20 + + + 13 + + + KFF_PTCH2THR + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 0 + + + NoControl + + + 6, 17 + + + 36, 13 + + + 14 + + + P to T + + + label83 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + KFF_RDDRMIX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 2 + + + NoControl + + + 6, 63 + + + 61, 13 + + + 15 + + + Rudder Mix + + + label78 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + KFF_PTCHCOMP + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 4 + + + NoControl + + + 6, 40 + + + 61, 13 + + + 16 + + + Pitch Comp + + + label81 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox16 + + + 5 + + + 205, 217 + + + 195, 108 + + + 4 + + + Other Mix's + + + groupBox16 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 4 + + + 111, 82 + + + 78, 20 + + + 11 + + + ENRGY2THR_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label73 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + ENRGY2THR_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label74 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + ENRGY2THR_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label75 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + ENRGY2THR_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label76 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox14 + + + 7 + + + 4, 217 + + + 195, 108 + + + 5 + + + Energy/Alt Pid + + + groupBox14 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 5 + + + 111, 82 + + + 78, 20 + + + 0 + + + ALT2PTCH_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 0 + NoControl - - 11 + + 6, 86 - + + 54, 13 + + + 1 + + + INT_MAX + + + label69 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 1 + + + 111, 59 + + + 78, 20 + + + 2 + + + ALT2PTCH_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 2 + + NoControl - - groupBox17 + + 6, 63 - - 139, 340 + + 15, 13 - - 170, 91 + + 3 - - 25 + + D - - + + label70 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 154, 17 + + groupBox13 - - + + 3 - + + 111, 36 + + + 78, 20 + + + 4 + + + ALT2PTCH_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label71 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 5 + + + 111, 13 + + + 78, 20 + + + 6 + + + ALT2PTCH_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 7 + + + P + + + label72 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox13 + + + 7 + + + 406, 109 + + + 195, 108 + + + 6 + + + Nav Pitch Alt Pid + + + groupBox13 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 6 + + + 111, 82 + + + 78, 20 + + + 0 + + + ARSP2PTCH_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 1 + + + INT_MAX + + + label65 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 1 + + + 111, 59 + + + 78, 20 + + + 2 + + + ARSP2PTCH_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 3 + + + D + + + label66 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 3 + + + 111, 36 + + + 78, 20 + + + 4 + + + ARSP2PTCH_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label67 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 5 + + + 111, 13 + + + 78, 20 + + + 6 + + + ARSP2PTCH_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 7 + + + P + + + label68 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox12 + + + 7 + + + 205, 109 + + + 195, 108 + + + 7 + + + Nav Pitch AS Pid + + + groupBox12 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 7 + + + 111, 82 + + + 78, 20 + + + 11 + + + HDNG2RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label61 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + HDNG2RLL_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label62 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + HDNG2RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label63 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + HDNG2RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label64 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox11 + + + 7 + + + 4, 109 + + + 195, 108 + + + 8 + + + Nav Roll Pid + + + groupBox11 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 8 + + + 111, 82 + + + 78, 20 + + + 11 + + + YW2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label57 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + YW2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label58 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + YW2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label59 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + YW2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + + 15 + + + P + + + label60 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox10 + + + 7 + + + 406, 1 + + + 195, 108 + + + 9 + + + Servo Yaw Pid + + + groupBox10 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 9 + + + 111, 82 + + + 78, 20 + + + 11 + + + PTCH2SRV_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label53 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + PTCH2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label54 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox9 - - TabPlanner + + 3 - + + 111, 36 + + 78, 20 - - - - - 103, 19 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - NoControl - - - groupBox20 - - - label3 - - - - - - - - - label90 - - - - - - 111, 13 - - - NoControl - - - TabPlanner - - - label46 - - - 2 - - + 7 - - Write changed params to device + + PTCH2SRV_I - - 78, 20 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + groupBox9 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label55 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 12 - groupBox9 - - groupBox7 - - - NoControl - - - Bottom, Left - - - - - - - - - 12 - - - label91 - - - ENRGY2THR_P - - - 65, 13 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 66 - - - 80, 37 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - CHK_GDIPlus - - - 4 - - - label7 - - - 78, 20 - - - - - - 11 - - - - - - 56, 17 - - - groupBox12 - - - 4 - - - label96 - - - TabPlanner - - - 6, 40 - - - 6 - - - NoControl - - - 0, 0, 0, 0 - - - 14 - - - 16 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - TabPlanner - - - groupBox17 - - - 111, 36 - - - groupBox19 - - - 18 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 177, 17 - - - HLD_LAT_IMAX - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 138, 21 - - + 5 - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - - - - 5 - - - 15 - - - groupBox10 - - - groupBox8 - - - TabPlanner - - - 7 - - - 4 - - - 52, 13 - - - 5 - - - 15, 13 - - - NoControl - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 182, 6 - - - NoControl - - - - - - - - - - - - - - - 1 - - - groupBox8 - - - 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10, 13 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Cruise - - - - - - groupBox25 - - - 3 - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 111, 59 - - - 3 - - - 87, 17 - - - 10 - - - toolTip1 - - - 111, 82 - - - IMAX - - - 6, 63 - - - groupBox9 - - - groupBox9 - - - 111, 36 - - - RLL2SRV_IMAX - - - 12 - - - ARSP2PTCH_P - - - 27 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 80, 86 - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox10 - - - 5 - - - 27, 13 - - - Nav Pitch AS Pid - - - 245, 107 - - - 590, 244 - - - label93 - - - 80, 63 - - - groupBox12 - - - RLL2SRV_I - - - label101 - - - 11 - - - CHK_mavdebug - - - 78, 20 - - - 139, 317 - - - 7 - - - 78, 20 - - - CMB_rateposition - - - 6, 16 - - - 4 - - - 5 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 20 - - - CMB_ratestatus - - - 39 - - - groupBox17 - - - 5 - - - 10, 13 - - - CHK_speechwaypoint - - - - - - 0 - - - CHK_speechaltwarning - - - - - - NoControl - - - 14, 13 - - - NUM_tracklength - - - BUT_Joystick - - - label23 - - - TabAC2 - - - 6, 17 - - - - - - 65, 13 - - - 579, 107 - - - IMAX - - - 139, 158 - - - 78, 20 - - - 2 - - - I - - - - - - 68, 13 - - - 80, 13 - - - groupBox18 - - - groupBox8 - - - 0 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - 0 - - - NoControl - - - label107 - - - 61, 13 - - - groupBox3 - - - - - - - - - NoControl - - - Energy/Alt Pid - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - - - - 78, 20 - - - Load - - - groupBox9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 3 - - - 111, 82 - - - 195, 108 - - - - - - 0 - - - 358, 6 - - - 0 - - - - - - Enable HUD Overlay - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 205, 217 - - - 0 - - - ENRGY2THR_D - - - 15 - - - - - - - - - groupBox10 - - - 6, 86 - - - 80, 37 - - - NAV_LAT_P - - - - - - - - - 139, 131 - - - groupBox23 - - - 722, 434 - - - 50, 13 - - - 78, 20 - - - label64 - - - 30, 162 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - - - - 65, 13 - - - TabAC2 - - - 14, 13 - - - - - - 14, 13 - - - 0 - - - Enable Speech - - - P to T - - - groupBox10 - - - 78, 20 - - - groupBox3 - - - 334, 240 - - - - - - BUT_writePIDS - - - Save params to file - - - 78, 20 - - - label65 - - - - - + 111, 13 - - 10, 13 - - - - - - 3 - - - Reload params from device - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Waypoint - - - 0 - - - 80, 37 - - - 7 - - - 7 - - - 75, 23 - - - 80, 21 - - - 6, 16 - - - 5 - - - 111, 13 - - - 30 - - - - - - 103, 19 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 0 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 195, 108 - - + 78, 20 - - - - - TabPlanner - - - 24 - - - NoControl - - - IMAX - - - 406, 325 - - - P - - - - - - 6 - - - IMAX - - - P - 5 - - TabAPM2 + + PTCH2SRV_P - + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox9 + + + 6 + + NoControl - - P - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - 4, 22 - - - NoControl - - - label60 - - - 170, 95 - - - 14, 13 - - - 139, 187 - - - TabAPM2 - - - 78, 20 - - - 2 - - - TabPlanner - - - 10 - - - 5 - - - - - - 3 - - - label61 - - - 20 - - - IMAX - - - I - - - - - - 150 - - - D - - - RATE_YAW_I - - - 8 - - - 3 - - - groupBox21 - - - Stabilize Roll - 6, 17 - - 4, 22 + + 14, 13 - - True + + 15 - - 78, 20 + + P - - + + label56 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 30, 50 + + groupBox9 - - 5 + + 7 - - HDNG2RLL_D + + 205, 1 - - 111, 59 + + 195, 108 - - NoControl + + 10 - - 14 + + Servo Pitch Pid - - 10, 13 + + groupBox9 - - NoControl + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 2 + + TabAPM2 - - 205, 109 - - - 5 - - - 139, 80 - - - 11 - - - 5 - - - - - - 3, 198 - - - NoControl - - - IMAX - - - NoControl - - - 1 + + 10 111, 82 - - groupBox6 + + 78, 20 - - 44, 13 + + 11 - - APM 2.x + + RLL2SRV_IMAX - + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 0 + + + NoControl + + + 6, 86 + + + 54, 13 + + + 12 + + + INT_MAX + + + label49 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + RLL2SRV_D + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 2 + + + NoControl + + + 6, 63 + + + 15, 13 + + + 13 + + + D + + + label50 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 3 + + + 111, 36 + + + 78, 20 + + + 7 + + + RLL2SRV_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 4 + + + NoControl + + 6, 40 - - label67 + + 10, 13 - - P + + 14 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + I - + + label51 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 5 + + + 111, 13 + + + 78, 20 + + + 5 + + + RLL2SRV_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox8 + + + 6 + + + NoControl + + + 6, 17 + + + 14, 13 + + 15 P - - P + + label52 - - 1 - - - P - - - 195, 108 - - - 12 - - - 78, 20 - - - 5 - - - 15 - - - THR_ALT_I - - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 6, 17 + + groupBox8 - - 2 - - - TRIM_THROTTLE - - - groupBox4 - - - $this - - - I - - - groupBox6 - - - 10, 13 - - - 6, 17 - - - groupBox21 - - - 58 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 4 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 195, 108 - - - - - - 111, 13 - - - 195, 108 - - - TabAC2 - - - NoControl - - - D - - - 1 - - - groupBox4 - - - 6, 17 - - - - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80 - - - - - - 6, 64 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15, 13 - - - 6, 17 - - - 65, 13 - - - - - - - - - groupBox18 - - - 9 - - - 2 - - - 30, 269 - - - groupBox14 - - - 195, 108 - - - 6, 66 - - - 78, 20 - - - label99 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 37 - - - TabPlanner - - - 10, 13 - - - label27 - - - 170, 108 - - - 78, 20 - - - 4 - - - 24 - - - 14 - - + 7 - - 5 + + 4, 1 - - NoControl + + 195, 108 - - Rudder Mix - - - XTRK_GAIN_SC - - - - - - NoControl - - - Video Device - - - 4 - - - 14 - - - TabPlanner - - - 75, 23 - - - TabAPM2 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10 - - - 170, 110 - - - 1 - - - INT_MAX - - - 10, 13 - - - label68 - - - 6, 40 - - - 188, 240 - - - ENRGY2THR_I - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - STB_PIT_P - - - 283, 209 - - - NoControl - - - 6 - - - ARSP2PTCH_D - - - groupBox5 - - - 6, 40 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - HLD_LAT_P - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - 30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - 170, 110 - - - 61, 13 - - - 44, 13 - - - label69 - - - groupBox7 - - - 6, 66 - - - 182, 337 - - - groupBox5 - - - 15, 13 - - - NoControl - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - NoControl - - - - - - - - - THR_MIN - - - 65 - - - 170, 110 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 78, 20 - - - - - - - - - 6, 66 - - - 4 - - - Command - - - 5 - - - 13 - - - groupBox11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 6, 16 - - - 80, 37 - - - 4 - - - 6 - - - TabAPM2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - NoControl - - - 5 - - - 0, 0 - - + 11 - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 34 - - - 0 - - - groupBox5 - - - 111, 36 - - - groupBox23 - - - groupBox6 - - - 4 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15, 13 - - - ConfigTabs - - - 2 - - - - - - TabAC2 - - - 4 - - - Top, Bottom, Left, Right - - - Ratio - - - 11 - - - groupBox16 - - - 65, 13 + + Servo Roll Pid groupBox8 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAPM2 + + + 11 + + + 4, 22 + + + 0, 0, 0, 0 + + + 722, 434 + + + 0 + + + APM 2.x + + + TabAPM2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 0 + + + 80, 63 + + + 78, 20 + + + 0 + + + ACRO_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 1 + + + IMAX + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + ACRO_PIT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + ACRO_PIT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label33 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox17 + + + 5 + + + 182, 337 + + + 170, 91 + + + 13 + + + Acro Pitch + + + groupBox17 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 16 + + + IMAX + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + 80, 63 + + + 78, 20 + + + 11 + + + THR_RATE_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + THR_RATE_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + THR_RATE_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 5 + + + 6, 221 + + + 170, 110 + + + 16 + + + Throttle Rate + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + 1 - + + 80, 63 + + + 78, 20 + + + 0 + + + ACRO_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 0 + + + NoControl + + + 6, 66 + + + 68, 13 + + + 1 + + + IMAX + + + label40 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + ACRO_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label44 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + ACRO_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label48 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox18 + + + 5 + + + 6, 337 + + + 170, 91 + + + 14 + + + Acro Roll + + + groupBox18 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 2 + + + True + + + 3, 198 + + + 154, 17 + + + 13 + + + Lock Pitch and Roll Values + + + CHK_lockrollpitch + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 3 + + + 80, 86 + + + 78, 20 + + + 16 + + + WP_SPEED_MAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 0 + + + NoControl + + + 6, 89 + + + 54, 13 + + + 17 + + + m/s + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 1 + + + 80, 63 + + + 78, 20 + + + 11 + + + NAV_LAT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 2 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 3 + + + 80, 37 + + + 78, 20 + + + 7 + + + NAV_LAT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 5 + + + 80, 13 + + + 78, 20 + + + 5 + + + NAV_LAT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 6 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 7 + + + 534, 107 + + + 170, 108 + + + 0 + + + Nav WP + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 4 + + + 80, 86 + + + 78, 20 + + + 18 + + + XTRK_ANGLE_CD1 + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 0 + + + NoControl + + + 6, 89 + + + 82, 13 + + + 19 + + + Error Max + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 1 + + + 80, 63 + + + 78, 20 + + + 11 + + + XTRACK_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 2 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 3 + + + 80, 37 + + + 78, 20 + + + 7 + + + XTRACK_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 4 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 5 + + + 80, 13 + + + 78, 20 + + + 5 + + + XTRACK_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 6 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 7 + + + 358, 221 + + + 170, 110 + + + 2 + + + Crosstrack Correction + + + groupBox6 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 5 + + + 80, 63 + + + 78, 20 + + + 11 + + + THR_ALT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label19 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox7 - - ConfigTabs + + 1 - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 80, 37 - - ALT2PTCH_I - - - - - - - - - 4 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 28 - - - NoControl - - - - - - 14, 13 - - - - - - - - - 102, 17 - - - ARSP2PTCH_I - - - groupBox1 - - - 15 - - - 11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 278, 0 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox22 - - - 6, 40 - - - 6, 40 - - - NoControl - - - 111, 36 - - - - - - THR_ALT_IMAX - - - 12 - - - 6, 40 - - - 7 - - - 3 - - - - - - NoControl - - - 14 - - - 33 - - - 15 - - - 6, 16 - - - - - - TabAPM2 - - - Track Length - - - 80, 13 - - - 3 - - - CMB_distunits - - - groupBox14 - - - label4 - - - groupBox15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 31 + + 78, 20 7 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + THR_ALT_I - - 14, 13 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + groupBox7 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox23 - - - groupBox13 - - - label2 - - - 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - YW2SRV_I - - - 6, 66 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 12 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 402, 13 - - + 2 - - Max + + NoControl - - Min + + 6, 40 - - label6 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 63 - - - 61, 13 - - - 111, 82 - - - P - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 32 - - - label8 - - - groupBox19 - - - 30, 318 - - - 125, 17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 78, 20 - - - 14, 13 - - - 80, 63 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - 30, 189 - - - - - - 111, 59 - - - groupBox1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 22 - - - 2 - - + 10, 13 - - + + 14 - - Nav Pitch Alt Pid - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 0 - - - groupBox21 - - - 2 - - + I - - 6, 66 + + label21 - - Servo Roll Pid + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 12 + + groupBox7 - - RLL2SRV_P + + 3 - - 12 + + 80, 13 - - ACRO_PIT_I + + 78, 20 - - 30, 16 + + 5 - - YW2SRV_D + + THR_ALT_P - - 7 + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox7 + + + 5 + + + 182, 221 + + + 170, 110 + + + 3 + + + Altitude Hold groupBox7 - - 0 - - - 80, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 11 - - - mavScale - - - NoControl - - - - - - NoControl - - - Servo Pitch Pid - - - TabPlanner - - - Start - - - label44 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 13 - - - 9 - - - Bottom, Left - - - 1 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - PTCH2SRV_D - - - - - - m/s - - - 195, 108 - - - P - - - Telemetry Rates - - - label45 - - - 6, 63 - - - groupBox15 - - - 111, 82 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - I - - - - - - 78, 20 - - - TabPlanner - - - 1 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - NoControl - - - groupBox4 - - - 18 - - - 78, 20 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 30, 217 - - - 15 - - - HDNG2RLL_IMAX - - - 6, 66 - - - NoControl - - - 78, 20 - - - 10, 13 - - - - - - Nav Roll Pid - - - 3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - IMAX - - + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + + TabAC2 - - STB_PIT_IMAX - - - 5 - - - 30, 135 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label97 - - - - - + 6 - - 80, 37 + + 80, 61 - - - - - 10, 13 - - - 25 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Stabilize Pitch - - - 6, 86 - - + 78, 20 - - ENRGY2THR_IMAX + + 11 - + + HLD_LAT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 0 + + + NoControl + + + 6, 64 + + + 65, 13 + + + 12 + + + IMAX + + + label28 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 31 + + groupBox19 - - TabPlanner + + 1 - - groupBox4 + + 80, 37 + + + 78, 20 + + + 7 + + + HLD_LAT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + HLD_LAT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox19 + + + 5 + + + 531, 6 + + + 170, 95 + + + 6 + + + Loiter + + + groupBox19 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 7 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_YAW_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_YAW_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 groupBox20 - - label40 + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_YAW_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox20 + + + 5 + + + 358, 6 + + + 170, 95 + + + 7 + + + Stabilize Yaw + + + groupBox20 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 8 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_PIT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label41 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_PIT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 5 + + + 182, 6 + + + 170, 95 + + + 8 + + + Stabilize Pitch + + + groupBox21 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 9 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 12 + + + IMAX + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 1 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 14 + + + I + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 3 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 15 + + + P + + + label46 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox22 + + + 5 + + + 6, 6 + + + 170, 95 + + + 9 + + + Stabilize Roll + + + groupBox22 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 10 + + + 80, 63 + + + 78, 20 + + + 0 + + + RATE_YAW_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 1 + + + IMAX + + + label47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_YAW_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label77 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_YAW_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label82 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 5 + + + 358, 107 + + + 170, 91 + + + 10 + + + Rate Yaw + + + groupBox23 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 11 + + + 80, 63 + + + 78, 20 + + + 0 + + + RATE_PIT_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 0 + + + NoControl + + + 6, 66 + + + 65, 13 + + + 1 + + + IMAX + + + label84 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_PIT_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label86 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_PIT_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label87 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 5 + + + 182, 107 + + + 170, 91 + + + 11 + + + Rate Pitch + + + groupBox24 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 12 + + + 80, 63 + + + 78, 20 + + + 0 + + + RATE_RLL_IMAX + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 0 + + + NoControl + + + 6, 66 + + + 68, 13 + + + 1 + + + IMAX + + + label88 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 1 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_RLL_I + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 2 + + + NoControl + + + 6, 40 + + + 10, 13 + + + 5 + + + I + + + label90 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 3 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_RLL_P + + + System.Windows.Forms.DomainUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 4 + + + NoControl + + + 6, 16 + + + 14, 13 + + + 7 + + + P + + + label91 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 5 + + + 6, 107 + + + 170, 91 + + + 12 + + + Rate Roll + + + groupBox25 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabAC2 + + + 13 + + + 4, 22 + + + 3, 3, 3, 3 + + + 722, 434 + + + 1 + + + AC2 + + + TabAC2 + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 1 + + + NoControl + + + 30, 50 + + + 100, 23 + + + 41 + + + Video Format + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 0 + + + 139, 47 + + + 408, 21 + + + 0 + + + CMB_videoresolutions + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 1 + + + NoControl + + + 30, 340 + + + 61, 13 + + + 39 + + + HUD + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 2 + + + NoControl + + + 139, 340 + + + 177, 17 + + + 40 + + + GDI+ (old type) + + + 17, 17 + + + OpenGL = Disabled +GDI+ = Enabled + + + CHK_GDIPlus + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 3 + + + NoControl + + + 30, 318 + + + 61, 13 + + + 37 + + + Waypoints + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 4 + + + NoControl + + + 139, 317 + + + 177, 17 + + + 38 + + + Load Waypoints on connect? + + + CHK_loadwponconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 5 + + + NoControl + + + 30, 292 + + + 103, 18 + + + 36 + + + Track Length + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 6 + + + 139, 291 + + + 67, 20 + + + 35 + + + On the Flight Data Tab + + + NUM_tracklength + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 7 + + + NoControl + + + 579, 107 + + + 102, 17 + + + 34 + + + Alt Warning + + + CHK_speechaltwarning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 8 + + + NoControl + + + 30, 269 + + + 61, 13 + + + 0 + + + APM Reset + + + label108 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 9 + + + NoControl + + + 139, 267 + + + 163, 17 + + + 1 + + + Reset APM on USB Connect + + + CHK_resetapmonconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 10 + + + Bottom, Left + + + NoControl + + + 33, 411 + + + 144, 17 + + + 2 + + + Mavlink Message Debug + + + CHK_mavdebug + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 11 + + + NoControl + + + 590, 244 + + + 22, 13 + + + 3 + + + RC + + + label107 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 12 + + + 0 + + + 1 + + + 3 + + + 10 + + + 621, 240 + + + 80, 21 + + + 4 + + + CMB_raterc + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 13 + + + NoControl + + + 425, 244 + + + 69, 13 + + + 5 + + + Mode/Status + + + label104 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 14 + + + NoControl + + + 280, 244 + + + 44, 13 + + + 6 + + + Position + + + label103 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 15 + + + NoControl + + + 136, 244 + + + 43, 13 + + + 7 + + + Attitude + + + label102 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 16 + + + NoControl + + + 27, 244 + + + 84, 13 + + + 8 + + + Telemetry Rates + + + label101 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 17 + + + 0 + + + 1 3 @@ -2961,4207 +5458,972 @@ 10 - - 4 - - - 6 - - - 13 - - - 23 - - - groupBox2 - - - groupBox1 - - - NoControl - - - 3, 3 - - - groupBox6 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 4 - - - TabAC2 - - - groupBox6 - - - - - - 280, 244 - - - - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 16 - - - HUD - - - 0 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - TabAC2 - - - 10, 13 - - - 7 - - - 0 - - - 0 - - - CHK_enablespeech - - - 10, 13 - - - NoControl - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NAV_LAT_IMAX - - - 54, 13 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 52, 13 - - - I - - - 111, 59 - - - 50, 13 - - - 4, 217 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - INT_MAX - - - - - - 2 - - - Bottom, Left - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox8 - - - Joystick Setup - - - label47 - - - NoControl - - - 6 - - - Save - - - - - - ALT2PTCH_D - - - 6, 63 - - - TabPlanner - - - 6 - - - 9 - - - Bottom, Left - - - 14, 13 - - - Airspeed m/s - - - 102, 17 - - - label98 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 0, 0, 0, 0 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 6, 86 - - - 6 - - - 3 - - - 78, 20 - - - 10 - - - 6 - - - 139, 47 - - - 6, 16 - - - 2 - - - NoControl - - - - - - Navigation Angles - - - groupBox24 - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - RawValue - - - False - - - CHK_speechcustom - - - groupBox20 - - - 16 - - - 4 - - - 78, 20 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - XTRK_ANGLE_CD - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 6 - - - 17 - - - P - - - label42 - - - groupBox19 - - - D - - - 3 - - - CHK_loadwponconnect - - - 6, 66 - - - Loiter - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - Throttle 0-100% - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 15 - - - groupBox1 - - - 378, 107 - - - 205, 325 - - - 6, 40 - - - NoControl - - - Nav WP - - - 65, 13 - - - label43 - - - 0 - - - 78, 20 - - - 65, 13 - - - - - - Alt Warning - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 111, 82 - - - - - - NoControl - - - label48 - - - Throttle Rate - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36, 13 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 78, 20 - - - 7 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label108 - - - ConfigTabs - - - 12 - - - - - - 14 - - - 111, 36 - - - 78, 20 - - - I - - - 33 - - - groupBox14 - - - label49 - - - groupBox10 - - - Crosstrack Correction - - - 35 - - - - - - - - - - - - P - - - 30, 83 - - - groupBox19 - - - NoControl - - - 16 - - - - - - TabAC2 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 15 - - - 8 - - - 26 - - - Altitude Hold - - - 57, 13 - - - groupBox1 - - - 12 - - - 4, 22 - - - 6, 63 - - - INT_MAX - - - 17 - - - groupBox19 - - - TabPlanner - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - Lock Pitch and Roll Values - - - - - - 103, 18 - - - 13 - - - NoControl - - - NoControl - - - groupBox24 - - - 40 - - - 80, 63 - - - 71, 17 - - - 5 - - - 2 - - - 111, 82 - - - groupBox21 - - - label109 - - - 80, 63 - - - 0 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - CMB_videoresolutions - - - NoControl - - - groupBox13 - - - - - - 3 - - - groupBox6 - - - 1 - - - NoControl - - - groupBox2 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 13 - - - groupBox11 - - - INT_MAX - - - 54, 13 - - - 30, 111 - - - - - - 4, 22 - - - 4 - - - label33 - - - 6, 40 - - - 0 - - - NoControl - - - Value - - - NoControl - - - ARSPD_FBW_MIN - - - 14 - - - 7 - - - - - - 0 - - - 14 - - - 78, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Reset APM on USB Connect - - - ALT2PTCH_IMAX - - - 5 - - - 170, 91 - - - 7 - - - TabPlanner - - - 78, 20 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - - - - 11 - - - 80, 61 - - - 1 - - - 78, 20 - - - YW2SRV_P - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 59 - - - 17 - - - 13 - - - groupBox8 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 31, 438 - - - 78, 20 - - - 80, 37 - - - ARSPD_FBW_MAX - - - Compare Params - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 3 - - - 78, 20 - - - label41 - - - 2 - - - groupBox20 - - - CMB_speedunits - - - 195, 108 - - - - - - 722, 434 - - - - - - 22 - - - groupBox23 - - - THR_RATE_I - - - groupBox3 - - - - - - - - - - - - 5 - - - 1 - - - 111, 59 - - - 15, 13 - - - 13 - - - groupBox17 - - - 4, 325 - - - 11 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - PTCH2SRV_P - - - 78, 20 - - - 78, 20 - - - - - - NoControl - - - 28 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - 144, 17 - - - 78, 20 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox10 - - - 358, 221 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 4 - - - groupBox2 - - - 78, 20 - - - - - - STB_YAW_P - 499, 240 - - 1 - - - - - - TabPlanner - - - 111, 13 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 10 - - - D - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 621, 240 - - - 322, 107 - - - groupBox2 - - - groupBox11 - - - 2 - - - NoControl - - - groupBox2 - - - - - - IMAX - - - 4 - - - 6, 86 - - - 0 - - - 7 - - - 6, 17 - - - XTRACK_I - - - 7 - - - - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - - - - 2 - - - 11 - - - 4 - - - NoControl - - - groupBox18 - - - Joystick - - - 169, 441 - - - 14 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - NoControl - - - 15 - - - 54, 13 - - - 9 - - - 80, 37 - - - groupBox12 - - - 7 - - - CMB_raterc - - - groupBox24 - - - KFF_PTCH2THR - - - PTCH2SRV_IMAX - - - Bottom, Left - - - Top, Bottom, Left - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - $this - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 27 - - - KFF_PTCHCOMP - - - 9 - - - 19 - - - 4 - - - 78, 20 - - - NoControl - - - 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14 - - - On the Flight Data Tab - - - - - - 6, 107 - - - 45, 13 - - - groupBox24 - - - 5 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 20 - - - 138, 21 - - - groupBox3 - - - 9 - - - groupBox20 - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 4 - - - 4 - - - 41 - - - 0 - - - NoControl - - - Gain (cm) - - - 6 - - - NoControl - - - RATE_PIT_P - - - groupBox4 - - - - - - 5 - - - 7 - - - 65, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 6, 40 - - - - - - - - - Rate Pitch - - - 80, 13 - - - LIM_PITCH_MIN - - - TabPlanner - - - - - - 61, 13 - 80, 21 - - APM Reset + + 9 - - 1 + + CMB_ratestatus - - 6, 16 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 7 - - - 63 - - - 10 - - - 13 - - - Battery Warning - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - IMAX - - - 7 - - - 21 - - - groupBox22 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 5 - - - 5 - - - groupBox2 - - + TabPlanner - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 18 - - 67, 20 - - - - - - 14, 13 - - - - - - TabPlanner - - - 14 - - + 0 - - 75, 19 - - + 1 - - 30, 292 + + 3 - - 3, 3, 3, 3 + + 10 - - TabAC2 + + 334, 240 - - 111, 13 + + 80, 21 - + + 10 + + + CMB_rateposition + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabPlanner - - 38 + + 19 - - NoControl + + 0 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15 - - - 80, 63 - - + 1 - - 4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 3 10 - - 42 + + 188, 240 - - 0, 0 - - - NoControl - - - groupBox17 - - - 2 - - - - - - label18 - - - 15, 13 - - - 111, 13 - - - 3 - - - NoControl - - - NoControl - - - 5 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - label14 - - - NoControl - - - 14, 13 - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 11 - - - 5 - - - Cruise - - - - - - 0 - - - 1 - - - 100, 23 - - - 78, 20 - - - 78, 20 - - - - - - TabPlanner - - - 5 - - - I - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - Mode/Status - - - 2 - - - 11 - - - 80, 37 - - - 6 - - - NoControl - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAC2 - - - 80, 13 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label84 - - - groupBox6 - - - 7 - - - - - - 78, 20 - - - groupBox18 - - - label73 - - - 53, 13 - - - Servo Yaw Pid - - - 78, 20 - - - 4 - - - P - - - - - - Pitch Max - - - TabAPM2 - - - D - - - groupBox23 - - - label103 - - - 6 - - - groupBox14 - - - - - - 1 - - - - - - 11 - - - 38 - - - - - - 78, 20 - - - 9 - - - 3 - - - Stabilize Yaw - - - 3 - - - groupBox20 - - - label34 - - - NoControl - - - 14, 13 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox15 - - - BUT_videostart - - - 5 - - - IMAX - - - 78, 20 - - - 35 - - - 3 - - - NoControl - - - 10, 13 - - - groupBox4 - - - 6 - - - 32, 13 - - - 5 - - - 4 - - - STB_RLL_P - - - label35 - - - TabPlanner - - - $this - - - 406, 109 - - - I - - - label62 - - - 4 - - - 1 - - - STB_YAW_IMAX - - - 177, 17 - - - NoControl - - - - - - 5 - - - TabPlanner - - - CMB_osdcolor - - - 3 - - - 0 - - - - - - - - - 78, 20 - - - 7 - - - 182, 107 - - - 14, 13 - - - label80 - - - - - - TabPlanner - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 63 - - - groupBox4 - - - 7 - - - 78, 20 - - - groupBox18 - - - - - - NoControl - - - 5 - - - groupBox14 - - - 5 - - - 11 - - - - - - Speed Units - - - NoControl - - - label81 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - - - - - - - BUT_save - - - 3 - - - - - - groupBox20 - - - 14 - - - P - - - CHK_speechbattery - - - I - - - 26 - - - label30 - - - RawValue - - - label17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - False - - - $this - - - Configuration - - - 82, 13 - - - groupBox11 - - - 78, 20 - - - groupBox1 - - - 23 - - - groupBox13 - - - label31 - - - THR_MAX - - - 61, 13 - - - 14, 13 - - - TabPlanner - - - 54, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36, 13 - - - STB_RLL_IMAX - - - 80, 13 - - - 78, 20 - - - label87 - - - 6, 40 - - - 75, 19 - - - Load param's from file - - - 6, 89 - - - 1 - - - ACRO_PIT_P - - - 80, 63 - - - 4 - - - TabPlanner - - - label36 - - - TabPlanner - - - ARSP2PTCH_IMAX - - - groupBox9 - - - 78, 20 - - - - - - groupBox25 - - - 4 - - - Time Interval - - - Other Mix's - - - 0 - - - - - - Acro Roll - - - Mode - - - groupBox23 - - - - - - 405, 217 - - - TabAC2 - - - 11 - - - 7 - - - 80, 13 - - - label12 - - - 0 - - - label37 - - - 5 - - - 1 - - - TabPlanner - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - I - - - Attitude - - - P - - - 1 - - - RC - - - 6, 86 - - - 3 - - - 80, 63 - - - NoControl - - - label82 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox17 - - - 54, 13 - - - 1 - - - groupBox21 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Speech - - - - - - 0 - - - 9 - - - - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - THR_RATE_IMAX - - - 1 - - - 1008, 461 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - Error Max - - - label83 - - - 3 - - - 0 - - - 0 - - - NoControl - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 195, 108 - - - 7 - - - - - - 6 - - - 6 - - - 6, 40 - - - 7 - - - 6 - - - 111, 59 - - - label32 - - - label19 - - - groupBox13 - - - 1 - - - label88 - - - 78, 20 - - - groupBox22 - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - NoControl - - - 2 - - - 170, 95 - - - 163, 17 - - - groupBox3 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 170, 91 - - - groupBox14 - - - label15 - - - groupBox4 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 86 - - - RATE_RLL_P - - - 195, 108 - - - 5 - - - 21 - - - groupBox9 - - - 534, 107 - - - TabPlanner - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 64 - - - 4 - - - 13 - - - label38 - - - groupBox1 - - - $this - - - 111, 59 - - - groupBox16 - - - 4 - - - 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - TabPlanner - - - 195, 108 - - - groupBox6 - - - 0 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 100, 23 - - - XTRACK_IMAX - - - label39 - - - - - - 6, 16 - - - 78, 20 - - - NoControl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14 - - - 6 - - - groupBox15 - - - 14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - RATE_YAW_P - - - - - - groupBox4 - - - - - - 1 - - - 6, 40 - - - - - - Default - - - 12 - - - TabAPM2 - - - LIM_PITCH_MAX - - - - - - label10 - - - 0 - - - groupBox8 - - - 3 - - - - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 99, 23 - - - 80, 63 - - - NoControl - - - - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14 - - - THR_ALT_P - - - TabPlanner - - - 6 - - - label11 - - - 6, 17 - - - groupBox7 - - - 14 - - - - - - - - - 6, 16 - - - label1 - - - - - - 80, 63 - - - 111, 82 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - P - - - label16 - - - - - - 3 - - + 80, 21 - - 6, 16 - - - ConfigTabs - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 182, 221 - - - 0 - - - - - - 7 - - - 4 - - - 13 - - - 4, 1 - - - 30, 340 - - - D - - - 9 - - - 12 - - - 8 - - - NoControl - - - label5 - - - groupBox14 - - - 111, 59 - - - 6, 17 - - - NoControl - - - 170, 95 - - - 10, 13 - - - - - - TabAPM2 - - - - - - 4 - - - 6, 40 - - - 2 - - - 6, 40 - - - 14, 13 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Refresh Params - - - CHK_lockrollpitch - - - HDNG2RLL_I - - - 12 - - - - - - - - - 6, 16 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 10, 13 - - - 19 - - - CMB_language - - - label9 - - - RATE_PIT_I - - - NoControl - - - 7 - - - 12 - - - 471, 11 - - - groupBox12 - - - groupBox3 - - - groupBox16 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0, 0, 0, 0 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Write Params - - - 78, 20 - - - 80, 13 - - - IMAX - - - 68, 13 - - - 6, 17 - - - - - - NoControl - - - 80, 37 - - - - - - 2 - - - XTRACK_P - - - 14 - - - NoControl - - - 4 - - - TabPlanner - - - - - - 4 - - - I - - - 425, 244 - - - Value - - - 139, 291 - - - KFF_RDDRMIX - - - 36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Video Format - - - 0 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabAPM2 - - - label13 - - - 41 - - - mavScale - - - groupBox16 - - - TabAC2 - - - 80, 86 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - TabSetup - - - NoControl - - - 78, 20 - - - I - - - P - - - 2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - I - - - 111, 13 - - - 2 - - - 0 - - - 14, 13 - - - groupBox3 - - - 3 - - - - - - 78, 20 - - - 5 - - - 6, 66 - - - 5 - - - Waypoints - - - - - - 15 - - - 10, 13 - - - 138, 21 - - - $this - - - 80, 37 - - - - - - groupBox22 - - - TabPlanner - - - 78, 20 - - - - - - 78, 20 - - - 6, 17 - - - 1 - - - TabAC2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Command - - - 78, 20 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 10 - - - 29 - - - 2 - - - groupBox11 - - - - - - NoControl - - - 6, 16 - - - 2 - - - Pitch Comp - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 19 - - - 5 - - - FBW min - - - NoControl - - - D - - - 51, 13 - - - - - - 6, 66 - - - + + 11 CMB_rateattitude - - - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - HLD_LAT_I - - - 6, 40 - - - 6, 40 - - - 7 - - - I - - - - - - groupBox12 - - - 80, 13 - - - 11 - - - 2 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 40 - - - 111, 13 - - - - - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox10 - - - 6, 63 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 82, 416 - - - - - - 5 - - - 78, 20 - - - Bank Max - - - AC2 - - - groupBox9 - - - 78, 20 - - - - - - 78, 20 - - - 0 - - - 103, 19 - - - groupBox14 - - - groupBox13 - - - - - - 2 - - - 1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - P - - - 54, 13 - - - 6 - - - 0 - - - - - - 69, 13 - - - 6, 63 - - - Rate Yaw - - - 13 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - TabAC2 - - - FS Value - - - 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + TabPlanner - - 10, 13 + + 20 - + + NoControl + + + 283, 209 + + + 402, 13 + + 12 - - - - - 5 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - groupBox16 - - - 111, 36 - - - - - - 7 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 7 - - - - - - 10, 13 - - - BUT_videostop - - - CHK_resetapmonconnect - - - - - - 14, 13 - - - 245, 21 - - - 15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 11 - - - 78, 20 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 3 - - - 2 - - - 6, 40 - - - System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 55, 13 - - - ARSPD_RATIO - - - Params - - - groupBox19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 37 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - groupBox5 - - - 0 - - - 7 - - - - - - TabPlanner - - - ACRO_PIT_IMAX - - - TabPlanner - - - NoControl - - - 6, 89 - - - groupBox25 - - - - - - NoControl - - - - - - - - - IMAX - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Pitch Min - - - 269, 409 - - - 358, 107 - - - I - - - NoControl - - - TabAPM2 - - - ACRO_RLL_I - - - 7 - - - 0, 0, 0, 0 - - - - - - 78, 20 - - - NoControl - - - Stop - - - 18 - - - 169, 416 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox11 - - - 111, 13 - - - 78, 20 - - - 1 - - - 2 - - - 4 - - - label74 - - - 78, 20 - - - RATE_RLL_I - - - NoControl - - - 78, 20 - - - 7 - - - 6, 66 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14, 13 - - - 54, 13 - - - CMB_videosources - - - Acro Pitch - - - groupBox12 - - - TabPlanner - - - groupBox13 - - - label75 - - - ACRO_RLL_IMAX - - - 3 - - - NoControl - - - 5 - - - 6, 40 - - - - - - - - - 139, 214 - - - 6, 63 - - - 5 - - - 2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 16 - - - 6, 66 - - - TabPlanner - - - 33, 411 - - - 6, 17 - - - 7 - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 12 - - - 16 - - - 111, 59 - - - - - - CHK_speechmode - - - 111, 59 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - Entry Angle - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - NOTE: The Configuration Tab will NOT display these units, as those are raw values. - - + + label99 - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - 84, 13 - - - 2 - - - 4 - - - 4 - - - $this - - - - - - 8 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - Position - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 63 - - - - - - 8 - - - 0 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6 - - - LIM_ROLL_CD - - - groupBox10 - - - label66 - - - label70 - - - groupBox13 - - - - - - 6, 40 - - - System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - OpenGL = Disabled -GDI+ = Enabled - - - 6 - - - 54, 13 - - - BUT_rerequestparams - - - 8 - - - 111, 82 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - NoControl - - - Xtrack Pids - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + TabPlanner - - 24, 13 + + 21 - - label71 - - - 39 - - - 552, 15 - - - groupBox11 - - - BUT_compare - - - 139, 107 - - + NoControl - - Planner + + 30, 217 - - 6, 63 + + 65, 13 - + + 13 + + + Speed Units + + + label98 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabPlanner - - I + + 22 - - 5 + + NoControl - - 0 + + 30, 189 - - 13 + + 52, 13 - - groupBox21 + + 14 - - OSD Color + + Dist Units - - + + label97 - - Rate Roll - - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label25 - - - 80, 37 - - - label76 - - - 6, 86 - - - 406, 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - NoControl - - - 100, 23 - - - 37 - - - NoControl - - - 6, 6 - - - 111, 36 - - - - - - 64, 13 - - - 111, 36 - - - 11 - - - Mavlink Message Debug - - - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox12 - - - 111, 13 - - - 6, 337 - - - BUT_load - - - label77 - - - 9 - - - 3 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox18 - - - 2 - - - 9 - - - 78, 20 - - - NoControl - - - NoControl - - - 5 - - - 195, 108 - - - - - - groupBox7 - - - Bottom, Left - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 66 - - - RLL2SRV_D - - - 32 - - - - - - 9 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 170, 95 - - - label20 - - - 15, 13 - - - 6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label92 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label63 - - - TRIM_ARSPD_CM - - - - - - 111, 36 - - - 7 - - - 170, 91 - - - 10, 13 - - - NoControl - - - label21 - - - 13 - - - groupBox9 - - - label72 - - - label54 - - - 471, 107 - - - 10 - TabPlanner - - + + 23 - - groupBox11 + + 139, 214 - - groupBox11 + + 138, 21 - - 99, 17 + + 15 - - groupBox6 + + CMB_speedunits - + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + TabPlanner - - 1 + + 24 - - PTCH2SRV_I + + 139, 187 - - groupBox24 + + 138, 21 - - 139, 267 + + 16 - - Load Waypoints on connect? + + CMB_distunits - - STB_RLL_I + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label26 + + TabPlanner - - label55 + + 25 - - groupBox25 - - - 14 - - + NoControl - - 78, 20 + + 30, 162 - - 34 + + 45, 13 - - 3 + + 17 - - 14, 13 + + Joystick - - groupBox8 + + label96 - - + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 62 + + TabPlanner - - + + 26 - - 5 + + NoControl - - + + 30, 111 - - 150 + + 44, 13 - - groupBox25 + + 18 - + + Speech + + + label95 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 27 + + + NoControl + + + 471, 107 + + + 102, 17 + + + 19 + + + Battery Warning + + + CHK_speechbattery + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label78 + + TabPlanner - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 28 + + + NoControl + + + 378, 107 + + + 87, 17 + + + 20 + + + Time Interval + + + CHK_speechcustom + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 29 + + + NoControl + + + 322, 107 + + + 56, 17 + + + 21 + + + Mode + + + CHK_speechmode + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 30 + + + NoControl + + + 245, 107 + + + 71, 17 + + + 22 + + + Waypoint + + + CHK_speechwaypoint + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 31 + + + NoControl + + + 30, 83 + + + 57, 13 + + + 23 + + + OSD Color + + + label94 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 32 + + + 139, 80 138, 21 - + + 24 + + + CMB_osdcolor + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 33 + + + 139, 131 + + + 138, 21 + + + 25 + + + CMB_language + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 34 + + + NoControl + + + 30, 135 + + + 69, 13 + + + 26 + + + UI Language + + + label93 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 54, 13 + + TabPlanner - - STB_YAW_I + + 35 - - groupBox22 + + NoControl - - label104 + + 139, 107 - - 5 + + 99, 17 - + + 27 + + + Enable Speech + + + CHK_enablespeech + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 36 + + + NoControl + + + 552, 15 + + + 125, 17 + + + 28 + + + Enable HUD Overlay + + + CHK_hudshow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + TabPlanner + + + 37 + + + NoControl + + + 30, 16 + + + 100, 23 + + + 29 + + + Video Device + + + label92 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox25 + + TabPlanner - - + + 38 139, 13 - - 80, 13 + + 245, 21 - - 80, 63 + + 30 - - 9 + + CMB_videosources - - label79 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox3 + + TabPlanner - - TabAC2 + + 39 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - label86 + + 139, 158 - - groupBox3 + + 99, 23 - - + + 31 - - ALT2PTCH_P + + Joystick Setup - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + BUT_Joystick - - 15 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - 65, 13 + + TabPlanner - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 40 - - 10, 13 + + NoControl - - 10 + + 471, 11 - - groupBox13 + + 75, 23 - - I + + 32 - - groupBox22 + + Stop + + + BUT_videostop + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + TabPlanner + + + 41 + + + NoControl + + + 390, 11 + + + 75, 23 + + + 33 + + + Start + + + BUT_videostart + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + TabPlanner + + + 42 + + + 4, 22 + + + 3, 3, 3, 3 + + + 722, 434 + + + 2 + + + Planner + + + TabPlanner + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 2 + + + 4, 22 + + + 722, 434 + + + 3 + + + Setup + + + TabSetup + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTabs + + + 3 52, 18 - - True + + 278, 0 + + + 0, 0, 0, 0 + + + 0, 0 + + + 730, 460 + + + 62 + + + ConfigTabs + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 0, 0 + + + 100, 23 + + + 0 + + + label109 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Bottom, Left + + + NoControl + + + 169, 441 + + + 103, 19 + + + 0 + + + Refresh Params + + + Reload params from device + + + BUT_rerequestparams + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 1 + + + Bottom, Left + + + NoControl + + + 169, 416 + + + 103, 19 + + + 63 + + + Write Params + + + Write changed params to device + + + BUT_writePIDS + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 3 + + + Bottom, Left + + + NoControl + + + 82, 416 + + + 0, 0, 0, 0 + + + 75, 19 + + + 64 + + + Save + + + Save params to file + + + BUT_save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 4 + + + Bottom, Left + + + NoControl + + + 3, 416 + + + 0, 0, 0, 0 + + + 75, 19 + + + 65 + + + Load + + + Load param's from file + + + BUT_load + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 5 + + + Bottom, Left + + + NoControl + + + 31, 438 + + + 103, 19 + + + 66 + + + Compare Params + + + BUT_compare + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 0 True - - 17, 17 + + 6, 13 - - True + + 1008, 461 - - True + + Command - - True + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Value + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Default + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + mavScale + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + RawValue + + + System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Configuration + + + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 698fe0c59e..9eaeb83689 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -510,7 +510,7 @@ namespace ArdupilotMega.GCSViews Console.WriteLine("Detected a " + board); string baseurl = ""; - if (board == "2560" || board == "2560-2") + if (board == "2560") { baseurl = temp.url2560.ToString(); } @@ -605,7 +605,7 @@ namespace ArdupilotMega.GCSViews //port = new ArduinoSTK(); port.BaudRate = 57600; } - else if (board == "2560" || board == "2560-2") + else if (board == "2560") { port = new ArduinoSTKv2(); port.BaudRate = 115200; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 7dc0455310..bddd7f9853 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -10,6 +10,9 @@ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightData)); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle(); + this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components); + this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.MainH = new System.Windows.Forms.SplitContainer(); this.SubMainLeft = new System.Windows.Forms.SplitContainer(); this.hud1 = new hud.HUD(); @@ -52,9 +55,6 @@ this.lbl_winddir = new ArdupilotMega.MyLabel(); this.lbl_windvel = new ArdupilotMega.MyLabel(); this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl(); - this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components); - this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); - this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.panel1 = new System.Windows.Forms.Panel(); this.TXT_lat = new ArdupilotMega.MyLabel(); this.Zoomlevel = new System.Windows.Forms.NumericUpDown(); @@ -68,6 +68,7 @@ this.ZedGraphTimer = new System.Windows.Forms.Timer(this.components); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.label6 = new ArdupilotMega.MyLabel(); + this.contextMenuStrip1.SuspendLayout(); this.MainH.Panel1.SuspendLayout(); this.MainH.Panel2.SuspendLayout(); this.MainH.SuspendLayout(); @@ -86,11 +87,30 @@ this.splitContainer1.Panel1.SuspendLayout(); this.splitContainer1.Panel2.SuspendLayout(); this.splitContainer1.SuspendLayout(); - this.contextMenuStrip1.SuspendLayout(); this.panel1.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).BeginInit(); this.SuspendLayout(); // + // contextMenuStrip1 + // + this.contextMenuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { + this.goHereToolStripMenuItem, + this.pointCameraHereToolStripMenuItem}); + this.contextMenuStrip1.Name = "contextMenuStrip1"; + resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1"); + // + // goHereToolStripMenuItem + // + this.goHereToolStripMenuItem.Name = "goHereToolStripMenuItem"; + resources.ApplyResources(this.goHereToolStripMenuItem, "goHereToolStripMenuItem"); + this.goHereToolStripMenuItem.Click += new System.EventHandler(this.goHereToolStripMenuItem_Click); + // + // pointCameraHereToolStripMenuItem + // + this.pointCameraHereToolStripMenuItem.Name = "pointCameraHereToolStripMenuItem"; + resources.ApplyResources(this.pointCameraHereToolStripMenuItem, "pointCameraHereToolStripMenuItem"); + this.pointCameraHereToolStripMenuItem.Click += new System.EventHandler(this.pointCameraHereToolStripMenuItem_Click); + // // MainH // this.MainH.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; @@ -1098,26 +1118,6 @@ this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown); this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove); // - // contextMenuStrip1 - // - this.contextMenuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { - this.goHereToolStripMenuItem, - this.pointCameraHereToolStripMenuItem}); - this.contextMenuStrip1.Name = "contextMenuStrip1"; - resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1"); - // - // goHereToolStripMenuItem - // - this.goHereToolStripMenuItem.Name = "goHereToolStripMenuItem"; - resources.ApplyResources(this.goHereToolStripMenuItem, "goHereToolStripMenuItem"); - this.goHereToolStripMenuItem.Click += new System.EventHandler(this.goHereToolStripMenuItem_Click); - // - // pointCameraHereToolStripMenuItem - // - this.pointCameraHereToolStripMenuItem.Name = "pointCameraHereToolStripMenuItem"; - resources.ApplyResources(this.pointCameraHereToolStripMenuItem, "pointCameraHereToolStripMenuItem"); - this.pointCameraHereToolStripMenuItem.Click += new System.EventHandler(this.pointCameraHereToolStripMenuItem_Click); - // // panel1 // this.panel1.Controls.Add(this.TXT_lat); @@ -1246,6 +1246,7 @@ this.Load += new System.EventHandler(this.FlightData_Load); this.Resize += new System.EventHandler(this.FlightData_Resize); this.ParentChanged += new System.EventHandler(this.FlightData_ParentChanged); + this.contextMenuStrip1.ResumeLayout(false); this.MainH.Panel1.ResumeLayout(false); this.MainH.Panel2.ResumeLayout(false); this.MainH.ResumeLayout(false); @@ -1265,7 +1266,6 @@ this.splitContainer1.Panel1.ResumeLayout(false); this.splitContainer1.Panel2.ResumeLayout(false); this.splitContainer1.ResumeLayout(false); - this.contextMenuStrip1.ResumeLayout(false); this.panel1.ResumeLayout(false); this.panel1.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).EndInit(); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index 9cba58f074..23e320a9e3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -695,7 +695,7 @@ namespace ArdupilotMega.GCSViews { ((Button)sender).Enabled = false; #if MAVLINK10 - comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text)); + comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text),0,0,0,0,0,0,0); #else comPort.doAction((MAVLink.MAV_ACTION)Enum.Parse(typeof(MAVLink.MAV_ACTION), "MAV_ACTION_" + CMB_action.Text)); #endif diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index c7658555de..845fa8bfd8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -117,11 +117,35 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 290, 17 + + + + 174, 22 + + + Fly To Here + + + 174, 22 + + + Point Camera Here + + + 175, 48 + + + contextMenuStrip1 + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + Fill - 0, 0 @@ -184,7 +208,7 @@ hud1 - hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c SubMainLeft.Panel1 @@ -229,7 +253,7 @@ BUT_joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -259,7 +283,7 @@ BUT_quickmanual - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -289,7 +313,7 @@ BUT_quickrtl - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -319,7 +343,7 @@ BUT_quickauto - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -373,7 +397,7 @@ BUT_setwp - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -424,7 +448,7 @@ BUT_setmode - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -454,7 +478,7 @@ BUT_clear_track - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -505,7 +529,7 @@ BUT_Homealt - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -535,7 +559,7 @@ BUT_RAWSensor - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -565,7 +589,7 @@ BUTrestartmission - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -595,7 +619,7 @@ BUTactiondo - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabActions @@ -649,7 +673,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabGauges @@ -679,7 +703,7 @@ Gheading - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabGauges @@ -709,7 +733,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabGauges @@ -742,7 +766,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabGauges @@ -823,7 +847,7 @@ lbl_logpercent - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabTLogs @@ -874,7 +898,7 @@ BUT_log2kml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabTLogs @@ -925,7 +949,7 @@ BUT_playlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabTLogs @@ -952,7 +976,7 @@ BUT_loadtelem - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabTLogs @@ -1138,7 +1162,7 @@ lbl_winddir - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c splitContainer1.Panel2 @@ -1168,7 +1192,7 @@ lbl_windvel - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c splitContainer1.Panel2 @@ -1176,30 +1200,6 @@ 1 - - 290, 17 - - - 174, 22 - - - Fly To Here - - - 174, 22 - - - Point Camera Here - - - 175, 48 - - - contextMenuStrip1 - - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - Fill @@ -1427,7 +1427,7 @@ TXT_lat - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c panel1 @@ -1484,7 +1484,7 @@ label1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c panel1 @@ -1514,7 +1514,7 @@ TXT_long - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c panel1 @@ -1544,7 +1544,7 @@ TXT_alt - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c panel1 @@ -1745,7 +1745,7 @@ label6 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1765,6 +1765,18 @@ 1008, 461 + + goHereToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + pointCameraHereToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + recordHudToAVIToolStripMenuItem @@ -1783,18 +1795,6 @@ System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - goHereToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - pointCameraHereToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - dataGridViewImageColumn1 @@ -1823,6 +1823,6 @@ FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs index d94e9fecea..851f72bc0c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs @@ -120,6 +120,7 @@ this.label11 = new System.Windows.Forms.Label(); this.panelBASE = new System.Windows.Forms.Panel(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); + this.BUT_zoomto = new ArdupilotMega.MyButton(); ((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit(); this.panel5.SuspendLayout(); this.panel1.SuspendLayout(); @@ -508,6 +509,7 @@ this.panelWaypoints.CaptionFont = new System.Drawing.Font("Segoe UI", 11.75F, System.Drawing.FontStyle.Bold); this.panelWaypoints.CaptionHeight = 21; this.panelWaypoints.ColorScheme = BSE.Windows.Forms.ColorScheme.Custom; + this.panelWaypoints.Controls.Add(this.BUT_zoomto); this.panelWaypoints.Controls.Add(this.BUT_Camera); this.panelWaypoints.Controls.Add(this.BUT_grid); this.panelWaypoints.Controls.Add(this.BUT_Prefetch); @@ -832,6 +834,14 @@ resources.ApplyResources(this.panelBASE, "panelBASE"); this.panelBASE.Name = "panelBASE"; // + // BUT_zoomto + // + resources.ApplyResources(this.BUT_zoomto, "BUT_zoomto"); + this.BUT_zoomto.Name = "BUT_zoomto"; + this.toolTip1.SetToolTip(this.BUT_zoomto, resources.GetString("BUT_zoomto.ToolTip")); + this.BUT_zoomto.UseVisualStyleBackColor = true; + this.BUT_zoomto.Click += new System.EventHandler(this.BUT_zoomto_Click); + // // FlightPlanner // resources.ApplyResources(this, "$this"); @@ -943,5 +953,6 @@ private System.Windows.Forms.DataGridViewButtonColumn Delete; private System.Windows.Forms.DataGridViewImageColumn Up; private System.Windows.Forms.DataGridViewImageColumn Down; + private MyButton BUT_zoomto; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index 3deeb7ac6b..5f00291486 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -691,6 +691,15 @@ namespace ArdupilotMega.GCSViews private void Commands_RowsAdded(object sender, DataGridViewRowsAddedEventArgs e) { + for (int i = 0; i < Commands.ColumnCount; i++) + { + DataGridViewCell tcell = Commands.Rows[e.RowIndex].Cells[i]; + if (tcell.GetType() == typeof(DataGridViewTextBoxCell)) + { + tcell.Value = "0"; + } + } + DataGridViewComboBoxCell cell = Commands.Rows[e.RowIndex].Cells[Command.Index] as DataGridViewComboBoxCell; if (cell.Value == null) { @@ -2079,6 +2088,18 @@ namespace ArdupilotMega.GCSViews // update row headers ((ComboBox)sender).ForeColor = Color.White; ChangeColumnHeader(((ComboBox)sender).Text); + try + { + for (int i = 0; i < Commands.ColumnCount; i++) + { + DataGridViewCell tcell = Commands.Rows[selectedrow].Cells[i]; + if (tcell.GetType() == typeof(DataGridViewTextBoxCell)) + { + tcell.Value = "0"; + } + } + } + catch { } } /// /// Get the Google earth ALT for a given coord @@ -2723,5 +2744,21 @@ namespace ArdupilotMega.GCSViews trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y); label11.Location = new Point(panelMap.Size.Width - 50, label11.Location.Y); } + + private void BUT_zoomto_Click(object sender, EventArgs e) + { + string place = "Perth, Australia"; + Common.InputBox("Location", "Enter your location", ref place); + + GeoCoderStatusCode status = MainMap.SetCurrentPositionByKeywords(place); + if (status != GeoCoderStatusCode.G_GEO_SUCCESS) + { + MessageBox.Show("Google Maps Geocoder can't find: '" + place + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation); + } + else + { + MainMap.Zoom = 15; + } + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx index 4c3ddace09..4495da6c9f 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx @@ -127,7 +127,7 @@ - 326, 31 + 213, 31 82, 17 @@ -148,7 +148,7 @@ panelWaypoints - 3 + 4 True @@ -157,7 +157,7 @@ NoControl - 411, 24 + 298, 24 98, 17 @@ -178,7 +178,7 @@ panelWaypoints - 8 + 9 Top, Bottom, Left, Right @@ -186,9 +186,9 @@ 30 - + True - + Command @@ -198,9 +198,9 @@ 150 - + True - + P1 @@ -210,9 +210,9 @@ 40 - + True - + P2 @@ -222,9 +222,9 @@ 40 - + True - + P3 @@ -234,9 +234,9 @@ 40 - + True - + P4 @@ -246,9 +246,9 @@ 40 - + True - + Lat @@ -258,9 +258,9 @@ 40 - + True - + Lon @@ -270,9 +270,9 @@ 40 - + True - + Alt @@ -282,9 +282,9 @@ 40 - + True - + Delete @@ -294,9 +294,9 @@ 50 - + True - + Up @@ -306,9 +306,9 @@ 30 - + True - + Down @@ -340,7 +340,7 @@ panelWaypoints - 10 + 11 True @@ -349,7 +349,7 @@ NoControl - 411, 40 + 298, 40 86, 17 @@ -370,10 +370,10 @@ panelWaypoints - 12 + 13 - 73, 32 + 23, 36 36, 20 @@ -394,10 +394,10 @@ panelWaypoints - 13 + 14 - 280, 32 + 154, 36 40, 20 @@ -418,7 +418,7 @@ panelWaypoints - 11 + 12 True @@ -427,7 +427,7 @@ NoControl - 9, 32 + 9, 24 61, 13 @@ -448,7 +448,7 @@ panelWaypoints - 4 + 5 True @@ -457,7 +457,7 @@ NoControl - 221, 32 + 151, 24 56, 13 @@ -478,10 +478,10 @@ panelWaypoints - 9 + 10 - 184, 32 + 89, 36 36, 20 @@ -502,7 +502,7 @@ panelWaypoints - 7 + 8 True @@ -511,7 +511,7 @@ NoControl - 112, 32 + 76, 24 69, 13 @@ -532,7 +532,7 @@ panelWaypoints - 6 + 7 Bottom, Right @@ -556,7 +556,7 @@ BUT_write - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -583,7 +583,7 @@ BUT_read - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -610,7 +610,7 @@ SaveFile - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -637,7 +637,7 @@ BUT_loadwpfile - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -1128,9 +1128,9 @@ 42 - + 172, 17 - + Change the current map type @@ -1239,11 +1239,41 @@ 0 + + NoControl + + + 746, 26 + + + 62, 23 + + + 53 + + + Zoom To + + + Get Camera settings for overlap + + + BUT_zoomto + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + panelWaypoints + + + 0 + NoControl - 809, 26 + 692, 26 48, 23 @@ -1261,19 +1291,19 @@ BUT_Camera - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 0 + 1 NoControl - 755, 26 + 638, 26 48, 23 @@ -1291,19 +1321,19 @@ BUT_grid - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 1 + 2 NoControl - 693, 26 + 576, 26 56, 23 @@ -1321,19 +1351,19 @@ BUT_Prefetch - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 2 + 3 NoControl - 596, 26 + 479, 26 91, 23 @@ -1351,19 +1381,19 @@ button1 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 5 + 6 NoControl - 515, 26 + 398, 26 75, 23 @@ -1381,13 +1411,13 @@ BUT_Add - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 14 + 15 Bottom @@ -1536,9 +1566,9 @@ Top, Bottom, Left, Right - + 17, 17 - + 167, 22 @@ -1823,7 +1853,7 @@ trackBar1 - ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelMap @@ -1915,9 +1945,9 @@ 1 - + True - + 6, 13 @@ -2105,9 +2135,6 @@ FlightPlanner - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - ..\Resources\MAVCmd.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs index 0b7a3993ba..db612a34dd 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs @@ -125,7 +125,6 @@ // resources.ApplyResources(this.CHKREV_roll, "CHKREV_roll"); this.CHKREV_roll.Name = "CHKREV_roll"; - this.toolTip1.SetToolTip(this.CHKREV_roll, resources.GetString("CHKREV_roll.ToolTip")); this.CHKREV_roll.UseVisualStyleBackColor = true; this.CHKREV_roll.CheckedChanged += new System.EventHandler(this.CHKREV_roll_CheckedChanged); // @@ -133,7 +132,6 @@ // resources.ApplyResources(this.CHKREV_pitch, "CHKREV_pitch"); this.CHKREV_pitch.Name = "CHKREV_pitch"; - this.toolTip1.SetToolTip(this.CHKREV_pitch, resources.GetString("CHKREV_pitch.ToolTip")); this.CHKREV_pitch.UseVisualStyleBackColor = true; this.CHKREV_pitch.CheckedChanged += new System.EventHandler(this.CHKREV_pitch_CheckedChanged); // @@ -141,13 +139,11 @@ // resources.ApplyResources(this.CHKREV_rudder, "CHKREV_rudder"); this.CHKREV_rudder.Name = "CHKREV_rudder"; - this.toolTip1.SetToolTip(this.CHKREV_rudder, resources.GetString("CHKREV_rudder.ToolTip")); this.CHKREV_rudder.UseVisualStyleBackColor = true; this.CHKREV_rudder.CheckedChanged += new System.EventHandler(this.CHKREV_rudder_CheckedChanged); // // GPSrate // - resources.ApplyResources(this.GPSrate, "GPSrate"); this.GPSrate.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.GPSrate.FormattingEnabled = true; this.GPSrate.Items.AddRange(new object[] { @@ -159,8 +155,8 @@ resources.GetString("GPSrate.Items5"), resources.GetString("GPSrate.Items6"), resources.GetString("GPSrate.Items7")}); + resources.ApplyResources(this.GPSrate, "GPSrate"); this.GPSrate.Name = "GPSrate"; - this.toolTip1.SetToolTip(this.GPSrate, resources.GetString("GPSrate.ToolTip")); this.GPSrate.SelectedIndexChanged += new System.EventHandler(this.GPSrate_SelectedIndexChanged); this.GPSrate.KeyDown += new System.Windows.Forms.KeyEventHandler(this.GPSrate_KeyDown); this.GPSrate.Leave += new System.EventHandler(this.GPSrate_Leave); @@ -169,7 +165,6 @@ // resources.ApplyResources(this.ConnectComPort, "ConnectComPort"); this.ConnectComPort.Name = "ConnectComPort"; - this.toolTip1.SetToolTip(this.ConnectComPort, resources.GetString("ConnectComPort.ToolTip")); this.ConnectComPort.UseVisualStyleBackColor = true; this.ConnectComPort.Click += new System.EventHandler(this.ConnectComPort_Click); // @@ -177,7 +172,6 @@ // resources.ApplyResources(this.OutputLog, "OutputLog"); this.OutputLog.Name = "OutputLog"; - this.toolTip1.SetToolTip(this.OutputLog, resources.GetString("OutputLog.ToolTip")); this.OutputLog.TextChanged += new System.EventHandler(this.OutputLog_TextChanged); // // TXT_roll @@ -185,28 +179,24 @@ resources.ApplyResources(this.TXT_roll, "TXT_roll"); this.TXT_roll.Name = "TXT_roll"; this.TXT_roll.resize = false; - this.toolTip1.SetToolTip(this.TXT_roll, resources.GetString("TXT_roll.ToolTip")); // // TXT_pitch // resources.ApplyResources(this.TXT_pitch, "TXT_pitch"); this.TXT_pitch.Name = "TXT_pitch"; this.TXT_pitch.resize = false; - this.toolTip1.SetToolTip(this.TXT_pitch, resources.GetString("TXT_pitch.ToolTip")); // // TXT_heading // resources.ApplyResources(this.TXT_heading, "TXT_heading"); this.TXT_heading.Name = "TXT_heading"; this.TXT_heading.resize = false; - this.toolTip1.SetToolTip(this.TXT_heading, resources.GetString("TXT_heading.ToolTip")); // // TXT_wpdist // resources.ApplyResources(this.TXT_wpdist, "TXT_wpdist"); this.TXT_wpdist.Name = "TXT_wpdist"; this.TXT_wpdist.resize = false; - this.toolTip1.SetToolTip(this.TXT_wpdist, resources.GetString("TXT_wpdist.ToolTip")); // // currentStateBindingSource // @@ -217,41 +207,35 @@ resources.ApplyResources(this.TXT_bererror, "TXT_bererror"); this.TXT_bererror.Name = "TXT_bererror"; this.TXT_bererror.resize = false; - this.toolTip1.SetToolTip(this.TXT_bererror, resources.GetString("TXT_bererror.ToolTip")); // // TXT_alterror // resources.ApplyResources(this.TXT_alterror, "TXT_alterror"); this.TXT_alterror.Name = "TXT_alterror"; this.TXT_alterror.resize = false; - this.toolTip1.SetToolTip(this.TXT_alterror, resources.GetString("TXT_alterror.ToolTip")); // // TXT_lat // resources.ApplyResources(this.TXT_lat, "TXT_lat"); this.TXT_lat.Name = "TXT_lat"; this.TXT_lat.resize = false; - this.toolTip1.SetToolTip(this.TXT_lat, resources.GetString("TXT_lat.ToolTip")); // // TXT_long // resources.ApplyResources(this.TXT_long, "TXT_long"); this.TXT_long.Name = "TXT_long"; this.TXT_long.resize = false; - this.toolTip1.SetToolTip(this.TXT_long, resources.GetString("TXT_long.ToolTip")); // // TXT_alt // resources.ApplyResources(this.TXT_alt, "TXT_alt"); this.TXT_alt.Name = "TXT_alt"; this.TXT_alt.resize = false; - this.toolTip1.SetToolTip(this.TXT_alt, resources.GetString("TXT_alt.ToolTip")); // // SaveSettings // resources.ApplyResources(this.SaveSettings, "SaveSettings"); this.SaveSettings.Name = "SaveSettings"; - this.toolTip1.SetToolTip(this.SaveSettings, resources.GetString("SaveSettings.ToolTip")); this.SaveSettings.UseVisualStyleBackColor = true; this.SaveSettings.Click += new System.EventHandler(this.SaveSettings_Click); // @@ -278,32 +262,27 @@ resources.ApplyResources(this.TXT_servoroll, "TXT_servoroll"); this.TXT_servoroll.Name = "TXT_servoroll"; this.TXT_servoroll.resize = false; - this.toolTip1.SetToolTip(this.TXT_servoroll, resources.GetString("TXT_servoroll.ToolTip")); // // TXT_servopitch // resources.ApplyResources(this.TXT_servopitch, "TXT_servopitch"); this.TXT_servopitch.Name = "TXT_servopitch"; this.TXT_servopitch.resize = false; - this.toolTip1.SetToolTip(this.TXT_servopitch, resources.GetString("TXT_servopitch.ToolTip")); // // TXT_servorudder // resources.ApplyResources(this.TXT_servorudder, "TXT_servorudder"); this.TXT_servorudder.Name = "TXT_servorudder"; this.TXT_servorudder.resize = false; - this.toolTip1.SetToolTip(this.TXT_servorudder, resources.GetString("TXT_servorudder.ToolTip")); // // TXT_servothrottle // resources.ApplyResources(this.TXT_servothrottle, "TXT_servothrottle"); this.TXT_servothrottle.Name = "TXT_servothrottle"; this.TXT_servothrottle.resize = false; - this.toolTip1.SetToolTip(this.TXT_servothrottle, resources.GetString("TXT_servothrottle.ToolTip")); // // panel1 // - resources.ApplyResources(this.panel1, "panel1"); this.panel1.Controls.Add(this.label4); this.panel1.Controls.Add(this.label3); this.panel1.Controls.Add(this.label2); @@ -311,40 +290,35 @@ this.panel1.Controls.Add(this.TXT_lat); this.panel1.Controls.Add(this.TXT_long); this.panel1.Controls.Add(this.TXT_alt); + resources.ApplyResources(this.panel1, "panel1"); this.panel1.Name = "panel1"; - this.toolTip1.SetToolTip(this.panel1, resources.GetString("panel1.ToolTip")); // // label4 // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; this.label4.resize = false; - this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; this.label3.resize = false; - this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; this.label2.resize = false; - this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // label1 // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; this.label1.resize = false; - this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // panel2 // - resources.ApplyResources(this.panel2, "panel2"); this.panel2.Controls.Add(this.label30); this.panel2.Controls.Add(this.TXT_yaw); this.panel2.Controls.Add(this.label11); @@ -354,75 +328,65 @@ this.panel2.Controls.Add(this.TXT_roll); this.panel2.Controls.Add(this.TXT_pitch); this.panel2.Controls.Add(this.TXT_heading); + resources.ApplyResources(this.panel2, "panel2"); this.panel2.Name = "panel2"; - this.toolTip1.SetToolTip(this.panel2, resources.GetString("panel2.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; this.label30.resize = false; - this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // TXT_yaw // resources.ApplyResources(this.TXT_yaw, "TXT_yaw"); this.TXT_yaw.Name = "TXT_yaw"; this.TXT_yaw.resize = false; - this.toolTip1.SetToolTip(this.TXT_yaw, resources.GetString("TXT_yaw.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; this.label11.resize = false; - this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // label7 // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; this.label7.resize = false; - this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // label6 // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; this.label6.resize = false; - this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // label5 // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; this.label5.resize = false; - this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // label8 // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; this.label8.resize = false; - this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; this.label9.resize = false; - this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; this.label10.resize = false; - this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); // // panel3 // - resources.ApplyResources(this.panel3, "panel3"); this.panel3.Controls.Add(this.label16); this.panel3.Controls.Add(this.label15); this.panel3.Controls.Add(this.label14); @@ -432,47 +396,41 @@ this.panel3.Controls.Add(this.TXT_servopitch); this.panel3.Controls.Add(this.TXT_servorudder); this.panel3.Controls.Add(this.TXT_servothrottle); + resources.ApplyResources(this.panel3, "panel3"); this.panel3.Name = "panel3"; - this.toolTip1.SetToolTip(this.panel3, resources.GetString("panel3.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; this.label16.resize = false; - this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; this.label15.resize = false; - this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; this.label14.resize = false; - this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // label13 // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; this.label13.resize = false; - this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; this.label12.resize = false; - this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // panel4 // - resources.ApplyResources(this.panel4, "panel4"); this.panel4.Controls.Add(this.label20); this.panel4.Controls.Add(this.label19); this.panel4.Controls.Add(this.TXT_control_mode); @@ -484,57 +442,50 @@ this.panel4.Controls.Add(this.TXT_wpdist); this.panel4.Controls.Add(this.TXT_bererror); this.panel4.Controls.Add(this.TXT_alterror); + resources.ApplyResources(this.panel4, "panel4"); this.panel4.Name = "panel4"; - this.toolTip1.SetToolTip(this.panel4, resources.GetString("panel4.ToolTip")); // // label20 // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; this.label20.resize = false; - this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; this.label19.resize = false; - this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip")); // // TXT_control_mode // resources.ApplyResources(this.TXT_control_mode, "TXT_control_mode"); this.TXT_control_mode.Name = "TXT_control_mode"; this.TXT_control_mode.resize = false; - this.toolTip1.SetToolTip(this.TXT_control_mode, resources.GetString("TXT_control_mode.ToolTip")); // // TXT_WP // resources.ApplyResources(this.TXT_WP, "TXT_WP"); this.TXT_WP.Name = "TXT_WP"; this.TXT_WP.resize = false; - this.toolTip1.SetToolTip(this.TXT_WP, resources.GetString("TXT_WP.ToolTip")); // // label18 // resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; this.label18.resize = false; - this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip")); // // label17 // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; this.label17.resize = false; - this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // panel5 // - resources.ApplyResources(this.panel5, "panel5"); this.panel5.Controls.Add(this.ConnectComPort); + resources.ApplyResources(this.panel5, "panel5"); this.panel5.Name = "panel5"; - this.toolTip1.SetToolTip(this.panel5, resources.GetString("panel5.ToolTip")); // // zg1 // @@ -547,7 +498,6 @@ this.zg1.ScrollMinX = 0D; this.zg1.ScrollMinY = 0D; this.zg1.ScrollMinY2 = 0D; - this.toolTip1.SetToolTip(this.zg1, resources.GetString("zg1.ToolTip")); // // timer1 // @@ -555,7 +505,6 @@ // // panel6 // - resources.ApplyResources(this.panel6, "panel6"); this.panel6.Controls.Add(this.label28); this.panel6.Controls.Add(this.label29); this.panel6.Controls.Add(this.label27); @@ -568,42 +517,37 @@ this.panel6.Controls.Add(this.TXT_ruddergain); this.panel6.Controls.Add(this.TXT_pitchgain); this.panel6.Controls.Add(this.TXT_rollgain); + resources.ApplyResources(this.panel6, "panel6"); this.panel6.Name = "panel6"; - this.toolTip1.SetToolTip(this.panel6, resources.GetString("panel6.ToolTip")); // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; this.label28.resize = false; - this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // label29 // resources.ApplyResources(this.label29, "label29"); this.label29.Name = "label29"; this.label29.resize = false; - this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); // // label27 // resources.ApplyResources(this.label27, "label27"); this.label27.Name = "label27"; this.label27.resize = false; - this.toolTip1.SetToolTip(this.label27, resources.GetString("label27.ToolTip")); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; this.label25.resize = false; - this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); // // TXT_throttlegain // resources.ApplyResources(this.TXT_throttlegain, "TXT_throttlegain"); this.TXT_throttlegain.Name = "TXT_throttlegain"; - this.toolTip1.SetToolTip(this.TXT_throttlegain, resources.GetString("TXT_throttlegain.ToolTip")); this.TXT_throttlegain.TextChanged += new System.EventHandler(this.TXT_throttlegain_TextChanged); // // label24 @@ -611,48 +555,41 @@ resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; this.label24.resize = false; - this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // label23 // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; this.label23.resize = false; - this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; this.label22.resize = false; - this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; this.label21.resize = false; - this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // TXT_ruddergain // resources.ApplyResources(this.TXT_ruddergain, "TXT_ruddergain"); this.TXT_ruddergain.Name = "TXT_ruddergain"; - this.toolTip1.SetToolTip(this.TXT_ruddergain, resources.GetString("TXT_ruddergain.ToolTip")); this.TXT_ruddergain.TextChanged += new System.EventHandler(this.TXT_ruddergain_TextChanged); // // TXT_pitchgain // resources.ApplyResources(this.TXT_pitchgain, "TXT_pitchgain"); this.TXT_pitchgain.Name = "TXT_pitchgain"; - this.toolTip1.SetToolTip(this.TXT_pitchgain, resources.GetString("TXT_pitchgain.ToolTip")); this.TXT_pitchgain.TextChanged += new System.EventHandler(this.TXT_pitchgain_TextChanged); // // TXT_rollgain // resources.ApplyResources(this.TXT_rollgain, "TXT_rollgain"); this.TXT_rollgain.Name = "TXT_rollgain"; - this.toolTip1.SetToolTip(this.TXT_rollgain, resources.GetString("TXT_rollgain.ToolTip")); this.TXT_rollgain.TextChanged += new System.EventHandler(this.TXT_rollgain_TextChanged); // // label26 @@ -660,13 +597,11 @@ resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; this.label26.resize = false; - this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // CHKdisplayall // resources.ApplyResources(this.CHKdisplayall, "CHKdisplayall"); this.CHKdisplayall.Name = "CHKdisplayall"; - this.toolTip1.SetToolTip(this.CHKdisplayall, resources.GetString("CHKdisplayall.ToolTip")); this.CHKdisplayall.UseVisualStyleBackColor = true; this.CHKdisplayall.CheckedChanged += new System.EventHandler(this.CHKdisplayall_CheckedChanged); // @@ -676,7 +611,6 @@ this.CHKgraphroll.Checked = true; this.CHKgraphroll.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphroll.Name = "CHKgraphroll"; - this.toolTip1.SetToolTip(this.CHKgraphroll, resources.GetString("CHKgraphroll.ToolTip")); this.CHKgraphroll.UseVisualStyleBackColor = true; // // CHKgraphpitch @@ -685,7 +619,6 @@ this.CHKgraphpitch.Checked = true; this.CHKgraphpitch.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphpitch.Name = "CHKgraphpitch"; - this.toolTip1.SetToolTip(this.CHKgraphpitch, resources.GetString("CHKgraphpitch.ToolTip")); this.CHKgraphpitch.UseVisualStyleBackColor = true; // // CHKgraphrudder @@ -694,7 +627,6 @@ this.CHKgraphrudder.Checked = true; this.CHKgraphrudder.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphrudder.Name = "CHKgraphrudder"; - this.toolTip1.SetToolTip(this.CHKgraphrudder, resources.GetString("CHKgraphrudder.ToolTip")); this.CHKgraphrudder.UseVisualStyleBackColor = true; // // CHKgraphthrottle @@ -703,14 +635,12 @@ this.CHKgraphthrottle.Checked = true; this.CHKgraphthrottle.CheckState = System.Windows.Forms.CheckState.Checked; this.CHKgraphthrottle.Name = "CHKgraphthrottle"; - this.toolTip1.SetToolTip(this.CHKgraphthrottle, resources.GetString("CHKgraphthrottle.ToolTip")); this.CHKgraphthrottle.UseVisualStyleBackColor = true; // // but_advsettings // resources.ApplyResources(this.but_advsettings, "but_advsettings"); this.but_advsettings.Name = "but_advsettings"; - this.toolTip1.SetToolTip(this.but_advsettings, resources.GetString("but_advsettings.ToolTip")); this.but_advsettings.UseVisualStyleBackColor = true; this.but_advsettings.Click += new System.EventHandler(this.but_advsettings_Click); // @@ -718,14 +648,12 @@ // resources.ApplyResources(this.chkSensor, "chkSensor"); this.chkSensor.Name = "chkSensor"; - this.toolTip1.SetToolTip(this.chkSensor, resources.GetString("chkSensor.ToolTip")); this.chkSensor.UseVisualStyleBackColor = true; // // CHK_quad // resources.ApplyResources(this.CHK_quad, "CHK_quad"); this.CHK_quad.Name = "CHK_quad"; - this.toolTip1.SetToolTip(this.CHK_quad, resources.GetString("CHK_quad.ToolTip")); this.CHK_quad.UseVisualStyleBackColor = true; this.CHK_quad.CheckedChanged += new System.EventHandler(this.CHK_quad_CheckedChanged); // @@ -733,7 +661,6 @@ // resources.ApplyResources(this.BUT_startfgquad, "BUT_startfgquad"); this.BUT_startfgquad.Name = "BUT_startfgquad"; - this.toolTip1.SetToolTip(this.BUT_startfgquad, resources.GetString("BUT_startfgquad.ToolTip")); this.BUT_startfgquad.UseVisualStyleBackColor = true; this.BUT_startfgquad.Click += new System.EventHandler(this.BUT_startfgquad_Click); // @@ -741,7 +668,6 @@ // resources.ApplyResources(this.BUT_startfgplane, "BUT_startfgplane"); this.BUT_startfgplane.Name = "BUT_startfgplane"; - this.toolTip1.SetToolTip(this.BUT_startfgplane, resources.GetString("BUT_startfgplane.ToolTip")); this.BUT_startfgplane.UseVisualStyleBackColor = true; this.BUT_startfgplane.Click += new System.EventHandler(this.BUT_startfgplane_Click); // @@ -749,7 +675,6 @@ // resources.ApplyResources(this.BUT_startxplane, "BUT_startxplane"); this.BUT_startxplane.Name = "BUT_startxplane"; - this.toolTip1.SetToolTip(this.BUT_startxplane, resources.GetString("BUT_startxplane.ToolTip")); this.BUT_startxplane.UseVisualStyleBackColor = true; this.BUT_startxplane.Click += new System.EventHandler(this.BUT_startxplane_Click); // @@ -757,7 +682,6 @@ // resources.ApplyResources(this.CHK_heli, "CHK_heli"); this.CHK_heli.Name = "CHK_heli"; - this.toolTip1.SetToolTip(this.CHK_heli, resources.GetString("CHK_heli.ToolTip")); this.CHK_heli.UseVisualStyleBackColor = true; // // RAD_aerosimrc @@ -803,7 +727,6 @@ this.Controls.Add(this.CHKREV_pitch); this.Controls.Add(this.CHKREV_roll); this.Name = "Simulation"; - this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.Load += new System.EventHandler(this.Simulation_Load); ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); this.panel1.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx index 8d79ea9ad7..5d542ad283 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx @@ -118,1210 +118,312 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 3 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - 45, 13 - - - - - - - - - 1000 - - - 126, 37 - - - FlightGear - - - 47, 13 - - - label26 - - - $this - - - 128, 23 - - - Plane IMU - - - CHKgraphthrottle - - - 24 - - - 5 - - - label27 - - - Pitch - - - 25, 13 - - - ConnectComPort - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 7, 104 - - - 5 - - - 508, 330 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 43 - - - 10 - - - 67, 24 - - - Roll - - - 8 - - - 41 - - - 9 - - - panel1 - - - Reverse Pitch - - - Show Rudder - - - panel2 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 19 - - - panel5 - - - 67, 76 - - - 11 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 7 - - - 538, 36 - - - 75, 74 - - - 500 - - - 39 - - - Start FG Quad - - - 2 - - - 17 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - label22 - - - 6 - - - panel2 - - - 2 - - - 6 - - - 100, 20 - - - $this - - - $this - - - 100, 20 - - - $this - - - X-plane - - - TXT_heading - - - CHKdisplayall - - - label23 - - - toolTip1 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 0 - - - Longitude - - - 4 - - - panel6 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - label28 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 7, 52 - - - - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 68, 13 - - - 64, 34 - - - but_advsettings - - - 7, 78 - - - 17 - - - - Bottom, Left - - - 1 - - - 6 - - - 14 - - - 7, 27 - - - 0 - - - label29 - - - 6 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 2 - - - - - - 73, 17 - - - Can do Plane and Quad with model - - - 99999 - - - - - - Quad - - - panel2 - - - - - - 23 - - - Latitude - - - CHKREV_roll - - - $this - - - 16 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - True - - - Sensor - - - Simulation - - - 1 - - - - - - Reverse Rudder - - - label14 - - - - - - Save Settings - - - Plane GPS - - - 7 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - True - - - label15 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - TXT_servothrottle - - - 110, 709 - - - 566, 66 - - - Show Roll - - - - - - 91, 17 - - - 72, 104 - - - 0 - - - Pitch - - - 67, 102 - - - TXT_bererror - - - 207, 709 - - - 27 - - - BUT_startxplane - - - - - - 16 - - - $this - - - RAD_softFlightGear - - - 2 - - - CHKgraphroll - - - TXT_servorudder - - - 30000 - - - 5 - - - panel2 - - - 40 - - - - - - panel6 - - - panel1 - - - 23 - - - - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - These - - - 74, 17 - - - 2 - - - True - - - Start Xplane - - - 63, 20 - - - - - - $this - - - 0 - - - 100, 20 - - - 7, 78 - - - 18 - - - 4 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - panel3 - - - label11 - - - - - - 19 - - - 0 - - - 13, 709 - - - - - - panel3 - - - Show Pitch - - - 16 - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel3 - - - panel3 - - - 13, 294 - - - $this - - - 22 - - - 27 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 17 - - - label16 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - TXT_rollgain - - - 126, 63 - - - 6, 13 - - - panel3 - - - 213, 10 - - - 23 - - - 100, 20 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - - - - $this - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - label17 - - - $this - - - - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 8 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 566, 368 - - - - - - True - - - 12, 172 - - - $this - - - panel6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - 566, 186 - - - True - - - TXT_yaw - - - - - - panel2 - - - - - - 10, 27 - - - panel6 - - - 4 - - - panel6 - - - panel4 - - - Throttle - - - 69, 13 - - - label12 - - - TXT_throttlegain - - - 45, 20 - - - 6 - - - Show Throttle - - - 3 - - - 4, 78 - - - label2 - - - - - - panel5 - - - panel1 - - - label6 - - - - - - 44 - - - - - - panel4 - - - 2, 7 - - - Start FG Plane - - - 28, 13 - - - 178, 52 - - - 104, 17 - - - 48, 13 - - - ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 - - - 7 - - - 10 - - - 37, 13 - - - - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - panel3 - - - System.Windows.Forms.RichTextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - Yaw - - - SIM only - - - True - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - panel2 - - - 4 - - - 299, 10 - True - - $this + + + 213, 10 - - 1 - - - Altitude - - - 30 - - - label19 - - - 8 - - - Yaw - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 67, 45 - - - 5 - - - - - - NoControl - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - panel6 - - - 47 - - - Sim Link Start/Stop - - - $this - - - 25, 13 - - - True - - - - - - True - - - currentStateBindingSource - - - 10, 78 - - - Bottom, Left - - - 36 + + 87, 17 1 - + + Reverse Roll + + + CHKREV_roll + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - panel1 - - - 92, 21 - - - 7 - - - 304, 709 - - - 22, 13 - - - WPDist - - - 14 - - - 25 - 29 - - WP + + True - - panel3 + + 299, 10 - - 566, 146 + + 93, 17 - - panel1 + + 2 - - 6 + + Reverse Pitch - - are + + CHKREV_pitch - - 4, 52 - - - $this - - - GPS Refresh Rate - - - 7, 52 - - - 43, 13 - - - 178, 100 - - - 0 - - - - - - BUT_startfgquad - - - - - - panel4 - - - 7, 100 - - - 13 - - - 126, 76 - - - 197, 294 - - - 27 - - - 178, 122 - - + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - TXT_long + + $this - - 21 + + 28 - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - - panel4 + + 398, 10 - - 13 + + 104, 17 - - 59, 17 + + 3 - - 10000 - - - 100, 20 - - - 100, 20 - - - 45 - - - label25 - - - Heli - - - 50, 13 - - - 52, 17 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 24 - - - 50, 8 - - - panel6 - - - 9 - - - - - - 22 - - - NoControl - - - NoControl - - - 266, 40 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + Reverse Rudder CHKREV_rudder - + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - + + 27 - - 28 + + 100 - + + 200 + + + 250 + + + 333 + + + 500 + + + 1000 + + + 30000 + + + 99999 + + + 538, 36 + + + 92, 21 + + + 4 + + + GPSrate + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + 26 - - panel6 + + 26, 13 - - panel6 + + 128, 23 - - 29 + + 5 - - 31, 13 + + Sim Link Start/Stop - - 197, 40 + + ConnectComPort - - Bottom, Left + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - 702, 283 + + panel5 - + + 0 + + + Lucida Console, 8.25pt + + + 197, 66 + + + 363, 208 + + + 6 + + - - 3 + + OutputLog - - 4, 104 + + System.Windows.Forms.RichTextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 59, 13 + + $this - - True + + 25 - - 19 + + 67, 22 - - AeroSimRC + + 100, 20 - - + + 7 - - 722, 742 + + TXT_roll + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel2 + + + 6 + + + 67, 45 + + + 100, 20 8 - - 100, 20 + + TXT_pitch - - panel6 - - - 81, 13 - - - Bottom, Left - - - 10000 - - - 83, 13 - - - 2 - - - 75, 24 - - - 169, 13 - - - 11 - - - panel1 - - - System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - panel6 + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c panel2 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + 7 - - Display All + + 67, 70 - - 25, 13 + + 100, 20 - - 56, 13 + + 9 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + TXT_heading - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - Throttle Gain + + panel2 - - + + 8 + + + 75, 24 + + + 100, 20 + + + 10 + + + TXT_wpdist + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 8 + + + 104, 17 + + + 75, 50 + + + 100, 20 + + + 11 + + + TXT_bererror + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 9 + + + 75, 76 + + + 100, 20 + + + 12 + + + TXT_alterror + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 10 67, 23 @@ -1329,1003 +431,1670 @@ 100, 20 - - Can do Plane/Heli/Quads + + 13 - - label30 + + TXT_lat - - TXT_pitch + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - 3 - - - 1 - - - TXT_servoroll - - - Reverse Roll - - - Pitch Gain - - - $this - - - 10 - - - 2 - - - 26, 13 - - - 566, 330 - - - Can Do Plane/Quad with plugin - - - 0 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 67, 22 - - - True - - - 7, 29 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 67, 50 - - - 15 - - - 178, 122 - - - System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 95, 13 - - - 3 - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - panel2 - - - panel4 - - - - - - 3 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 8 - - - 100 - - - NoControl - - - 333 - - - 363, 208 - - + panel1 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 382, 294 - - - 67, 70 - - - 7 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 75, 100 - - - - - - - - - 12 - - - 21 - - - 112, 99 - - - 31, 13 - - - chkSensor - - - 7, 77 - - - 42 - - - 24 - - - RAD_softXplanes - - - TXT_alterror - - - 19 - - - - - - - - - 45, 20 - - - - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - Altitude ERR - - - - - - 178, 116 - - - TXT_servopitch - - - label4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label8 - - - 566, 203 - - - 46 - 4 - - TXT_pitchgain + + 67, 49 - - 12 + + 100, 20 - - + + 14 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + TXT_long - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - 67, 93 + + panel1 - - 10, 52 + + 5 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 67, 75 - - 44, 17 + + 100, 20 - - panel2 + + 15 - - + + TXT_alt - - GPSrate + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - + + panel1 + + + 6 + + + 566, 330 + + + 64, 34 + + + 16 + + + Save Settings + + + SaveSettings + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + $this - - 535, 9 + + 24 - - 57, 13 + + True - - panel2 + + 197, 40 - - 31 + + 61, 17 - - + + 17 - - 9 + + X-plane - - + + 301, 17 + + + Can Do Plane/Quad with plugin - - 54, 13 + + RAD_softXplanes + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + True + + + 266, 40 + + + 73, 17 + + + 18 + + + FlightGear + + + Can do Plane and Quad with model + + + RAD_softFlightGear + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + 67, 24 100, 20 - - $this + + 19 - - 74, 17 + + TXT_servoroll - - BUT_startfgplane + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - 13, 5 + + panel3 - - 1 + + 5 - - 87, 17 + + 67, 50 - - $this + + 100, 20 - - $this + + 20 - + + TXT_servopitch + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + 6 - - 25 + + 67, 76 - - 67, 13 + + 100, 20 - - Roll Gain + + 21 - - + + TXT_servorudder - + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 7 + + + 67, 102 + + + 100, 20 + + + 22 + + + TXT_servothrottle + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 8 + + + 60, 3 + + + 59, 13 + + + 19 + + + Plane GPS + + + label4 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 0 + + + 7, 78 + + + 42, 13 + + + 18 + + + Altitude + + + label3 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 1 + + + 7, 52 + + + 54, 13 + + + 17 + + + Longitude + + + label2 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 2 + + + 7, 26 + + + 45, 13 + + + 16 + + + Latitude + + + label1 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 3 + + + 13, 66 + + + 178, 100 + + + 23 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - 345, 40 + + 21 - + + 7, 100 + + + 28, 13 + + + 21 + + + Yaw + + + label30 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel2 + + + 0 + + + 67, 93 + + 100, 20 20 - - + + TXT_yaw - - 10000 + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - Rudder Gain - - - Advanced IP Settings - - - 64, 34 - - - 75, 48 - - - Lucida Console, 8.25pt - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 79, 17 - - - 3 - - - panel3 - - - 7, 52 - - - 45, 20 - - - Heading - - - 5 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 60, 4 - - - 398, 10 - - - 9 - - - - - - - - - 20 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - Top, Bottom, Left, Right - - - TXT_WP - - - 5 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 64, 34 - - - NOTE: - - - 7 - - - 20 - - - 26 - - - - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label10 - - - 11 - - - 10 - - - - - - 18 - - - 200 - - - 67, 49 - - - TXT_roll - - - 64, 34 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - CHKgraphpitch - - - 19 - - - 68, 13 - - - 26 - - - label1 - - - - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 15 - - - label5 - - - $this - - - True - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - 75, 23 - - - 566, 219 - - - 21 - - - $this - - - 64, 47 - - - RAD_aerosimrc - - - - - - 75, 76 - - - True - - - 23 - - - 28 - - - 7, 26 - - - 16 - - - - - - 566, 106 - - - TXT_control_mode - - - zg1 - - - 4 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 60, 3 - - - - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - TXT_wpdist - - - 50, 8 - - - 18 - - - True - - - Simulator Authority - For diff planes - - - - - - 75, 50 - - - timer1 - - - 2 - - - label3 - - - panel4 - - - 28, 13 - - - label7 - - - $this - - - - - - 100, 20 - - - 67, 75 - - - Ardupilot Output - - - - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 456, 41 - - - - - - 15 - - - 178, 122 - - - 43, 13 - - - 21 - - - $this - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 197, 66 - - - - - - 10000 - - - 80, 17 - - - panel4 + + panel2 1 - - 10, 104 + + 60, 4 - - 4, 27 + + 57, 13 - - 38, 98 + + 19 + + + Plane IMU + + + label11 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel2 + + + 2 + + + 7, 77 + + + 47, 13 + + + 15 + + + Heading + + + label7 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel2 + + + 3 + + + 7, 52 + + + 31, 13 + + + 14 + + + Pitch + + + label6 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel2 + + + 4 + + + 7, 29 + + + 25, 13 + + + 13 + + + Roll + + + label5 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel2 + + + 5 + + + 12, 172 + + + 178, 116 + + + 24 + + + panel2 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 7, 27 + + + 43, 13 + + + 16 + + + WPDist + + + label8 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 7 + + + 7, 52 + + + 69, 13 + + + 17 + + + Bearing ERR label9 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - + + panel4 + + + 6 + + + 7, 78 + + + 68, 13 + + + 18 + + + Altitude ERR + + + label10 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 5 + + + 50, 8 + + + 83, 13 + + + 27 + + + Ardupilot Output + + + label16 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 0 + + + 10, 104 + + + 43, 13 + + + 26 + + + Throttle + + + label15 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 1 + + + 10, 78 + + + 28, 13 + + + 25 + + + Yaw + + + label14 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 2 + + + 10, 52 + + + 31, 13 + + + 24 + + + Pitch + + + label13 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 3 + + + 10, 27 + + + 25, 13 + + + 23 + + + Roll + + + label12 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel3 + + + 4 + + + 13, 294 + + + 178, 122 + + + 25 + + + panel3 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + 72, 104 + + + 34, 13 + + + 23 + + + Mode + + + label20 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 0 + + + 7, 104 + + + 25, 13 + + + 22 + + + WP + + + label19 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 1 + + + 112, 99 + + + 63, 20 + + + 21 + + + TXT_control_mode + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 2 + + + 38, 98 + + + 28, 20 + + + 20 + + + TXT_WP + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 3 + + + 50, 8 + + + 81, 13 + + + 19 + + + Autopilot Status + + + label18 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel4 + + + 4 + + + 197, 294 + + + 178, 122 + + + 26 + + + panel4 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this 18 - - 93, 17 + + 535, 9 - - + + 95, 13 - - + + 27 - - 4 + + GPS Refresh Rate - - panel4 + + label17 - - TXT_alt + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - CHK_heli + + $this - - panel3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 28, 20 - - - 22 - - - label24 - - - 42, 13 - - - CHK_quad - - - 25 - - - 1 - - - - - - label13 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - - - - panel6 - - - 45, 20 - - - 38 - - - CHKgraphrudder - - - 92, 17 - - - label18 - - - 100, 20 - - - 43, 13 - - - TXT_lat - - - 100, 20 - - - 5 - - - panel4 - - - 33 - - - TXT_ruddergain - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - panel4 - - + 17 - - 250 + + 13, 5 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + 178, 52 - - 20 + + 28 - - 34, 13 + + panel5 - - + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + + $this - - + + 16 - - CHKREV_pitch - - - 48 - - - 6 - - - 100, 20 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel6 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 0 - - - - - - 4 - - - Mode - - - 8 - - - 8 - - - SaveSettings + + + Top, Bottom, Left, Right 12, 420 - - 32 + + 702, 283 - - panel4 + + 29 - - Roll + + zg1 - - 13, 66 + + ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + $this - - - - - label20 - - - 3 - - - - - - Bearing ERR - - - - - - 7 - - - 14 - - - Autopilot Status - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - OutputLog - - - 61, 17 - - - NoControl - - - label21 - - - 37 - - - 13 - - - panel4 - - - 5 + + 15 17, 17 + + 126, 76 + + + 48, 13 + + + 32 + + + SIM only + + + label28 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 0 + + + 126, 37 + + + 43, 13 + + + 33 + + + NOTE: + + + label29 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 1 + + + 126, 63 + + + 22, 13 + + + 31 + + + are + + + label27 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 2 + + + 4, 104 + + + 68, 13 + + + 8 + + + Throttle Gain + + + label25 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 3 + + + 75, 100 + + + 45, 20 + + + 7 + + + 10000 + + + TXT_throttlegain + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel6 + + + 4 + + + 4, 78 + + + 67, 13 + + + 6 + + + Rudder Gain + + + label24 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 5 + + + 4, 52 + + + 56, 13 + + + 5 + + + Pitch Gain + + + label23 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 6 + + + 4, 27 + + + 50, 13 + + + 4 + + + Roll Gain + + + label22 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 7 + + + 2, 7 + + + 169, 13 + + + 3 + + + Simulator Authority - For diff planes + + + label21 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel6 + + + 8 + + + 75, 74 + + + 45, 20 + + + 2 + + + 10000 + + + TXT_ruddergain + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel6 + + + 9 + + + 75, 48 + + + 45, 20 + + + 1 + + + 10000 + + + TXT_pitchgain + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel6 + + + 10 + + + 75, 23 + + + 45, 20 + + + 0 + + + 10000 + + + TXT_rollgain + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel6 + + + 11 + + + 382, 294 + + + 178, 122 + + + 30 + + + panel6 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 508, 330 + + + 37, 13 + + + 9 + + + These + + + label26 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 13 + + + True + + + 456, 41 + + + 74, 17 + + + 36 + + + Display All + + + CHKdisplayall + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + Bottom, Left + + + True + + + 13, 709 + + + 74, 17 + + + 37 + + + Show Roll + + + CHKgraphroll + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + Bottom, Left + + + True + + + 110, 709 + + + 80, 17 + + + 38 + + + Show Pitch + + + CHKgraphpitch + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + Bottom, Left + + + True + + + 207, 709 + + + 91, 17 + + + 39 + + + Show Rudder + + + CHKgraphrudder + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + Bottom, Left + + + True + + + 304, 709 + + + 92, 17 + + + 40 + + + Show Throttle + + + CHKgraphthrottle + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 566, 368 + + + 64, 47 + + + 41 + + + Advanced IP Settings + + + but_advsettings + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 7 + + + True + + + 566, 186 + + + 59, 17 + + + 42 + + + Sensor + + + chkSensor + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + True + + + NoControl + + + 566, 203 + + + 52, 17 + + + 43 + + + Quad + + + CHK_quad + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + NoControl + + + 566, 66 + + + 64, 34 + + + 44 + + + Start FG Quad + + + BUT_startfgquad + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 4 + + + NoControl + + + 566, 106 + + + 64, 34 + + + 45 + + + Start FG Plane + + + BUT_startfgplane + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 3 + + + NoControl + + + 566, 146 + + + 64, 34 + + + 46 + + + Start Xplane + + + BUT_startxplane + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 2 + + + True + + + NoControl + + + 566, 219 + + + 44, 17 + + + 47 + + + Heli + + + CHK_heli + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + NoControl + + + 345, 40 + + + 79, 17 + + + 48 + + + AeroSimRC + + + Can do Plane/Heli/Quads + + + RAD_aerosimrc + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + True - - 301, 17 - - - 104, 17 - + + 6, 13 + + + 722, 742 + + + currentStateBindingSource + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + timer1 + + + System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Simulation + + + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs b/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs index 5149771eda..9e33ec5b7a 100644 --- a/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs +++ b/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs @@ -146,6 +146,11 @@ namespace ArdupilotMega.HIL accel3D += new Vector3d(0, 0, -gravity); accel3D += air_resistance; + Random rand = new Random(); + int fixme; + + //velocity.X += .05 + rand.NextDouble() * .03; + //velocity.Y += .05 + rand.NextDouble() * .03; //# new velocity vector velocity += accel3D * delta_time.TotalSeconds; diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index 172006310c..396d75f1db 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -473,6 +473,8 @@ namespace ArdupilotMega packetcount++; + + //System.Threading.Thread.Sleep(1); } @@ -818,7 +820,7 @@ namespace ArdupilotMega } } - public bool doCommand(MAV_CMD actionid) + public bool doCommand(MAV_CMD actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7) { MainV2.givecomport = true; @@ -831,6 +833,14 @@ namespace ArdupilotMega req.command = (ushort)actionid; + req.param1 = p1; + req.param2 = p2; + req.param3 = p3; + req.param4 = p4; + req.param5 = p5; + req.param6 = p6; + req.param7 = p7; + generatePacket(MAVLINK_MSG_ID_COMMAND_LONG, req); DateTime start = DateTime.Now; diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 6d0024a7a6..fafa87f8d9 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -19,6 +19,7 @@ using System.Speech.Synthesis; using System.Globalization; using System.Threading; using System.Net.Sockets; +using IronPython.Hosting; namespace ArdupilotMega { @@ -37,7 +38,7 @@ namespace ArdupilotMega public static Hashtable config = new Hashtable(); public static bool givecomport = false; public static Firmwares APMFirmware = Firmwares.ArduPlane; - public static bool MAC = false; + public static bool MONO = false; public static bool speechenable = false; public static SpeechSynthesizer talk = new SpeechSynthesizer(); @@ -78,6 +79,11 @@ namespace ArdupilotMega GCSViews.Firmware Firmware; GCSViews.Terminal Terminal; + public void testpython() + { + Console.WriteLine("hello world from c# via python"); + } + public MainV2() { //System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US"); @@ -91,8 +97,17 @@ namespace ArdupilotMega //return; + var engine = Python.CreateEngine(); + var scope = engine.CreateScope(); + + scope.SetVariable("MainV2",this); + Console.WriteLine(DateTime.Now.Millisecond); + engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope); + Console.WriteLine(DateTime.Now.Millisecond); + engine.CreateScriptSourceFromString("MainV2.testpython()").Execute(scope); + Console.WriteLine(DateTime.Now.Millisecond); var t = Type.GetType("Mono.Runtime"); - MAC = (t != null); + MONO = (t != null); Form splash = new Splash(); splash.Show(); @@ -146,7 +161,7 @@ namespace ArdupilotMega if (config.ContainsKey("language") && !string.IsNullOrEmpty((string)config["language"])) changelanguage(getcultureinfo((string)config["language"])); - if (!MAC) // windows only + if (!MONO) // windows only { if (MainV2.config["showconsole"] != null && MainV2.config["showconsole"].ToString() == "True") { @@ -208,7 +223,7 @@ namespace ArdupilotMega //System.Threading.Thread.Sleep(2000); // make sure new enough .net framework is installed - if (!MAC) + if (!MONO) { Microsoft.Win32.RegistryKey installed_versions = Microsoft.Win32.Registry.LocalMachine.OpenSubKey(@"SOFTWARE\Microsoft\NET Framework Setup\NDP"); string[] version_names = installed_versions.GetSubKeyNames(); @@ -216,9 +231,9 @@ namespace ArdupilotMega double Framework = Convert.ToDouble(version_names[version_names.Length - 1].Remove(0, 1), CultureInfo.InvariantCulture); int SP = Convert.ToInt32(installed_versions.OpenSubKey(version_names[version_names.Length - 1]).GetValue("SP", 0)); - if (Framework < 3.5) + if (Framework < 4.0) { - MessageBox.Show("This program requires .NET Framework 3.5 +. You currently have " + Framework); + MessageBox.Show("This program requires .NET Framework 4.0 +. You currently have " + Framework); } } @@ -809,7 +824,7 @@ namespace ArdupilotMega { try { - System.Configuration.Configuration appconfig = System.Configuration.ConfigurationManager.OpenExeConfiguration(System.Configuration.ConfigurationUserLevel.None); + //System.Configuration.Configuration appconfig = System.Configuration.ConfigurationManager.OpenExeConfiguration(System.Configuration.ConfigurationUserLevel.None); XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml", Encoding.ASCII); xmlwriter.Formatting = Formatting.Indented; @@ -824,9 +839,9 @@ namespace ArdupilotMega xmlwriter.WriteElementString("APMFirmware", APMFirmware.ToString()); - appconfig.AppSettings.Settings.Add("comport", comportname); - appconfig.AppSettings.Settings.Add("baudrate", CMB_baudrate.Text); - appconfig.AppSettings.Settings.Add("APMFirmware", APMFirmware.ToString()); + //appconfig.AppSettings.Settings.Add("comport", comportname); + //appconfig.AppSettings.Settings.Add("baudrate", CMB_baudrate.Text); + //appconfig.AppSettings.Settings.Add("APMFirmware", APMFirmware.ToString()); foreach (string key in config.Keys) { @@ -836,7 +851,7 @@ namespace ArdupilotMega continue; xmlwriter.WriteElementString(key, config[key].ToString()); - appconfig.AppSettings.Settings.Add(key, config[key].ToString()); + //appconfig.AppSettings.Settings.Add(key, config[key].ToString()); } catch { } } @@ -846,7 +861,7 @@ namespace ArdupilotMega xmlwriter.WriteEndDocument(); xmlwriter.Close(); - appconfig.Save(); + //appconfig.Save(); } catch (Exception ex) { MessageBox.Show(ex.ToString()); } } @@ -926,7 +941,7 @@ namespace ArdupilotMega { try { - if (!MAC) + if (!MONO) { //joystick stuff @@ -980,7 +995,7 @@ namespace ArdupilotMega int minbytes = 10; - if (MAC) + if (MONO) minbytes = 0; DateTime menuupdate = DateTime.Now; @@ -1401,7 +1416,7 @@ namespace ArdupilotMega string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/"; bool update = updatecheck(loadinglabel, baseurl, ""); System.Diagnostics.Process P = new System.Diagnostics.Process(); - if (MAC) + if (MONO) { P.StartInfo.FileName = "mono"; P.StartInfo.Arguments = " \"" + Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "Updater.exe\""; diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index fe3c75f856..3f309a5e99 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -231,7 +231,7 @@ namespace ArdupilotMega // create kmz - aka zip file - FileStream fs = File.Open(filename.Replace(".tlog.kml", ".kmz"), FileMode.Create); + FileStream fs = File.Open(filename.Replace(Path.GetExtension(filename), ".kmz"), FileMode.Create); ZipOutputStream zipStream = new ZipOutputStream(fs); zipStream.SetLevel(9); //0-9, 9 being the highest level of compression zipStream.UseZip64 = UseZip64.Off; // older zipfile @@ -246,14 +246,12 @@ namespace ArdupilotMega // Zip the file in buffered chunks // the "using" will close the stream even if an exception occurs byte[] buffer = new byte[4096]; - using (FileStream streamReader = File.OpenRead(filename)) + using (FileStream streamReader = File.Open(filename,FileMode.Open,FileAccess.Read,FileShare.ReadWrite)) { StreamUtils.Copy(streamReader, zipStream, buffer); } zipStream.CloseEntry(); - File.Delete(filename); - filename = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "block_plane_0.dae"; // entry 2 @@ -275,6 +273,9 @@ namespace ArdupilotMega zipStream.IsStreamOwner = true; // Makes the Close also Close the underlying stream zipStream.Close(); + + File.Delete(filename); + flightdata.Clear(); } diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 15678c9825..d226b1803b 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.0.95")] +[assembly: AssemblyFileVersion("1.0.96")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs b/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs index 47c8282690..30c8f96d77 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs @@ -1,7 +1,7 @@ //------------------------------------------------------------------------------ // // This code was generated by a tool. -// Runtime Version:4.0.30319.235 +// Runtime Version:4.0.30319.239 // // Changes to this file may cause incorrect behavior and will be lost if // the code is regenerated. diff --git a/Tools/ArdupilotMegaPlanner/Script.cs b/Tools/ArdupilotMegaPlanner/Script.cs new file mode 100644 index 0000000000..a8c11ddc1b --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Script.cs @@ -0,0 +1,36 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega +{ + public class Script + { + DateTime timeout = DateTime.Now; + + public enum Conditional + { + LT = 0, + LTEQ, + EQ, + GT, + GTEQ + } + + public bool WaitFor(string item, Conditional cond,double value ,int timeoutms) + { + timeout = DateTime.Now; + while (DateTime.Now < timeout.AddMilliseconds(timeoutms)) + { + //if (item) + { + + } + } + + return false; + } + + } +} diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs index 955fa8f8ae..1f30541e5a 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs @@ -190,7 +190,6 @@ // // tabControl1 // - resources.ApplyResources(this.tabControl1, "tabControl1"); this.tabControl1.Controls.Add(this.tabReset); this.tabControl1.Controls.Add(this.tabRadioIn); this.tabControl1.Controls.Add(this.tabModes); @@ -198,17 +197,16 @@ this.tabControl1.Controls.Add(this.tabBattery); this.tabControl1.Controls.Add(this.tabArducopter); this.tabControl1.Controls.Add(this.tabHeli); + resources.ApplyResources(this.tabControl1, "tabControl1"); this.tabControl1.Name = "tabControl1"; this.tabControl1.SelectedIndex = 0; - this.toolTip1.SetToolTip(this.tabControl1, resources.GetString("tabControl1.ToolTip")); this.tabControl1.SelectedIndexChanged += new System.EventHandler(this.tabControl1_SelectedIndexChanged); // // tabReset // - resources.ApplyResources(this.tabReset, "tabReset"); this.tabReset.Controls.Add(this.BUT_reset); + resources.ApplyResources(this.tabReset, "tabReset"); this.tabReset.Name = "tabReset"; - this.toolTip1.SetToolTip(this.tabReset, resources.GetString("tabReset.ToolTip")); this.tabReset.UseVisualStyleBackColor = true; // // BUT_reset @@ -216,13 +214,11 @@ resources.ApplyResources(this.BUT_reset, "BUT_reset"); this.BUT_reset.Name = "BUT_reset"; this.BUT_reset.Tag = ""; - this.toolTip1.SetToolTip(this.BUT_reset, resources.GetString("BUT_reset.ToolTip")); this.BUT_reset.UseVisualStyleBackColor = true; this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click); // // tabRadioIn // - resources.ApplyResources(this.tabRadioIn, "tabRadioIn"); this.tabRadioIn.Controls.Add(this.CHK_revch3); this.tabRadioIn.Controls.Add(this.CHK_revch4); this.tabRadioIn.Controls.Add(this.CHK_revch2); @@ -236,15 +232,14 @@ this.tabRadioIn.Controls.Add(this.BARthrottle); this.tabRadioIn.Controls.Add(this.BARyaw); this.tabRadioIn.Controls.Add(this.BARroll); + resources.ApplyResources(this.tabRadioIn, "tabRadioIn"); this.tabRadioIn.Name = "tabRadioIn"; - this.toolTip1.SetToolTip(this.tabRadioIn, resources.GetString("tabRadioIn.ToolTip")); this.tabRadioIn.UseVisualStyleBackColor = true; // // CHK_revch3 // resources.ApplyResources(this.CHK_revch3, "CHK_revch3"); this.CHK_revch3.Name = "CHK_revch3"; - this.toolTip1.SetToolTip(this.CHK_revch3, resources.GetString("CHK_revch3.ToolTip")); this.CHK_revch3.UseVisualStyleBackColor = true; this.CHK_revch3.CheckedChanged += new System.EventHandler(this.CHK_revch3_CheckedChanged); // @@ -252,7 +247,6 @@ // resources.ApplyResources(this.CHK_revch4, "CHK_revch4"); this.CHK_revch4.Name = "CHK_revch4"; - this.toolTip1.SetToolTip(this.CHK_revch4, resources.GetString("CHK_revch4.ToolTip")); this.CHK_revch4.UseVisualStyleBackColor = true; this.CHK_revch4.CheckedChanged += new System.EventHandler(this.CHK_revch4_CheckedChanged); // @@ -260,7 +254,6 @@ // resources.ApplyResources(this.CHK_revch2, "CHK_revch2"); this.CHK_revch2.Name = "CHK_revch2"; - this.toolTip1.SetToolTip(this.CHK_revch2, resources.GetString("CHK_revch2.ToolTip")); this.CHK_revch2.UseVisualStyleBackColor = true; this.CHK_revch2.CheckedChanged += new System.EventHandler(this.CHK_revch2_CheckedChanged); // @@ -268,7 +261,6 @@ // resources.ApplyResources(this.CHK_revch1, "CHK_revch1"); this.CHK_revch1.Name = "CHK_revch1"; - this.toolTip1.SetToolTip(this.CHK_revch1, resources.GetString("CHK_revch1.ToolTip")); this.CHK_revch1.UseVisualStyleBackColor = true; this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged); // @@ -276,23 +268,21 @@ // resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio"); this.BUT_Calibrateradio.Name = "BUT_Calibrateradio"; - this.toolTip1.SetToolTip(this.BUT_Calibrateradio, resources.GetString("BUT_Calibrateradio.ToolTip")); this.BUT_Calibrateradio.UseVisualStyleBackColor = true; this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click); // // BAR8 // - resources.ApplyResources(this.BAR8, "BAR8"); this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true)); this.BAR8.Label = "Radio 8"; + resources.ApplyResources(this.BAR8, "BAR8"); this.BAR8.Maximum = 2200; this.BAR8.maxline = 0; this.BAR8.Minimum = 800; this.BAR8.minline = 0; this.BAR8.Name = "BAR8"; - this.toolTip1.SetToolTip(this.BAR8, resources.GetString("BAR8.ToolTip")); this.BAR8.Value = 1500; this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // @@ -302,119 +292,111 @@ // // BAR7 // - resources.ApplyResources(this.BAR7, "BAR7"); this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true)); this.BAR7.Label = "Radio 7"; + resources.ApplyResources(this.BAR7, "BAR7"); this.BAR7.Maximum = 2200; this.BAR7.maxline = 0; this.BAR7.Minimum = 800; this.BAR7.minline = 0; this.BAR7.Name = "BAR7"; - this.toolTip1.SetToolTip(this.BAR7, resources.GetString("BAR7.ToolTip")); this.BAR7.Value = 1500; this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BAR6 // - resources.ApplyResources(this.BAR6, "BAR6"); this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true)); this.BAR6.Label = "Radio 6"; + resources.ApplyResources(this.BAR6, "BAR6"); this.BAR6.Maximum = 2200; this.BAR6.maxline = 0; this.BAR6.Minimum = 800; this.BAR6.minline = 0; this.BAR6.Name = "BAR6"; - this.toolTip1.SetToolTip(this.BAR6, resources.GetString("BAR6.ToolTip")); this.BAR6.Value = 1500; this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BAR5 // - resources.ApplyResources(this.BAR5, "BAR5"); this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true)); this.BAR5.Label = "Radio 5"; + resources.ApplyResources(this.BAR5, "BAR5"); this.BAR5.Maximum = 2200; this.BAR5.maxline = 0; this.BAR5.Minimum = 800; this.BAR5.minline = 0; this.BAR5.Name = "BAR5"; - this.toolTip1.SetToolTip(this.BAR5, resources.GetString("BAR5.ToolTip")); this.BAR5.Value = 1500; this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BARpitch // - resources.ApplyResources(this.BARpitch, "BARpitch"); this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true)); this.BARpitch.Label = "Pitch"; + resources.ApplyResources(this.BARpitch, "BARpitch"); this.BARpitch.Maximum = 2200; this.BARpitch.maxline = 0; this.BARpitch.Minimum = 800; this.BARpitch.minline = 0; this.BARpitch.Name = "BARpitch"; - this.toolTip1.SetToolTip(this.BARpitch, resources.GetString("BARpitch.ToolTip")); this.BARpitch.Value = 1500; this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BARthrottle // - resources.ApplyResources(this.BARthrottle, "BARthrottle"); this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true)); this.BARthrottle.Label = "Throttle"; + resources.ApplyResources(this.BARthrottle, "BARthrottle"); this.BARthrottle.Maximum = 2200; this.BARthrottle.maxline = 0; this.BARthrottle.Minimum = 800; this.BARthrottle.minline = 0; this.BARthrottle.Name = "BARthrottle"; - this.toolTip1.SetToolTip(this.BARthrottle, resources.GetString("BARthrottle.ToolTip")); this.BARthrottle.Value = 1000; this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); // // BARyaw // - resources.ApplyResources(this.BARyaw, "BARyaw"); this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true)); this.BARyaw.Label = "Yaw"; + resources.ApplyResources(this.BARyaw, "BARyaw"); this.BARyaw.Maximum = 2200; this.BARyaw.maxline = 0; this.BARyaw.Minimum = 800; this.BARyaw.minline = 0; this.BARyaw.Name = "BARyaw"; - this.toolTip1.SetToolTip(this.BARyaw, resources.GetString("BARyaw.ToolTip")); this.BARyaw.Value = 1500; this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // BARroll // - resources.ApplyResources(this.BARroll, "BARroll"); this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255))))); this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true)); this.BARroll.Label = "Roll"; + resources.ApplyResources(this.BARroll, "BARroll"); this.BARroll.Maximum = 2200; this.BARroll.maxline = 0; this.BARroll.Minimum = 800; this.BARroll.minline = 0; this.BARroll.Name = "BARroll"; - this.toolTip1.SetToolTip(this.BARroll, resources.GetString("BARroll.ToolTip")); this.BARroll.Value = 1500; this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255))))); // // tabModes // - resources.ApplyResources(this.tabModes, "tabModes"); this.tabModes.Controls.Add(this.CB_simple6); this.tabModes.Controls.Add(this.CB_simple5); this.tabModes.Controls.Add(this.CB_simple4); @@ -444,220 +426,190 @@ this.tabModes.Controls.Add(this.label1); this.tabModes.Controls.Add(this.CMB_fmode1); this.tabModes.Controls.Add(this.BUT_SaveModes); + resources.ApplyResources(this.tabModes, "tabModes"); this.tabModes.Name = "tabModes"; - this.toolTip1.SetToolTip(this.tabModes, resources.GetString("tabModes.ToolTip")); this.tabModes.UseVisualStyleBackColor = true; // // CB_simple6 // resources.ApplyResources(this.CB_simple6, "CB_simple6"); this.CB_simple6.Name = "CB_simple6"; - this.toolTip1.SetToolTip(this.CB_simple6, resources.GetString("CB_simple6.ToolTip")); this.CB_simple6.UseVisualStyleBackColor = true; // // CB_simple5 // resources.ApplyResources(this.CB_simple5, "CB_simple5"); this.CB_simple5.Name = "CB_simple5"; - this.toolTip1.SetToolTip(this.CB_simple5, resources.GetString("CB_simple5.ToolTip")); this.CB_simple5.UseVisualStyleBackColor = true; // // CB_simple4 // resources.ApplyResources(this.CB_simple4, "CB_simple4"); this.CB_simple4.Name = "CB_simple4"; - this.toolTip1.SetToolTip(this.CB_simple4, resources.GetString("CB_simple4.ToolTip")); this.CB_simple4.UseVisualStyleBackColor = true; // // CB_simple3 // resources.ApplyResources(this.CB_simple3, "CB_simple3"); this.CB_simple3.Name = "CB_simple3"; - this.toolTip1.SetToolTip(this.CB_simple3, resources.GetString("CB_simple3.ToolTip")); this.CB_simple3.UseVisualStyleBackColor = true; // // CB_simple2 // resources.ApplyResources(this.CB_simple2, "CB_simple2"); this.CB_simple2.Name = "CB_simple2"; - this.toolTip1.SetToolTip(this.CB_simple2, resources.GetString("CB_simple2.ToolTip")); this.CB_simple2.UseVisualStyleBackColor = true; // // CB_simple1 // resources.ApplyResources(this.CB_simple1, "CB_simple1"); this.CB_simple1.Name = "CB_simple1"; - this.toolTip1.SetToolTip(this.CB_simple1, resources.GetString("CB_simple1.ToolTip")); this.CB_simple1.UseVisualStyleBackColor = true; // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; - this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // LBL_flightmodepwm // resources.ApplyResources(this.LBL_flightmodepwm, "LBL_flightmodepwm"); this.LBL_flightmodepwm.Name = "LBL_flightmodepwm"; - this.toolTip1.SetToolTip(this.LBL_flightmodepwm, resources.GetString("LBL_flightmodepwm.ToolTip")); // // label13 // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; - this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // lbl_currentmode // resources.ApplyResources(this.lbl_currentmode, "lbl_currentmode"); this.lbl_currentmode.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "mode", true)); this.lbl_currentmode.Name = "lbl_currentmode"; - this.toolTip1.SetToolTip(this.lbl_currentmode, resources.GetString("lbl_currentmode.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; - this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; - this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; - this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; - this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // label8 // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; - this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // label7 // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; - this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // label6 // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; - this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // CMB_fmode6 // - resources.ApplyResources(this.CMB_fmode6, "CMB_fmode6"); this.CMB_fmode6.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode6.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode6.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode6.FormattingEnabled = true; + resources.ApplyResources(this.CMB_fmode6, "CMB_fmode6"); this.CMB_fmode6.Name = "CMB_fmode6"; - this.toolTip1.SetToolTip(this.CMB_fmode6, resources.GetString("CMB_fmode6.ToolTip")); // // label5 // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; - this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // CMB_fmode5 // - resources.ApplyResources(this.CMB_fmode5, "CMB_fmode5"); this.CMB_fmode5.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode5.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode5.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode5.FormattingEnabled = true; + resources.ApplyResources(this.CMB_fmode5, "CMB_fmode5"); this.CMB_fmode5.Name = "CMB_fmode5"; - this.toolTip1.SetToolTip(this.CMB_fmode5, resources.GetString("CMB_fmode5.ToolTip")); // // label4 // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; - this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // CMB_fmode4 // - resources.ApplyResources(this.CMB_fmode4, "CMB_fmode4"); this.CMB_fmode4.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode4.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode4.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode4.FormattingEnabled = true; + resources.ApplyResources(this.CMB_fmode4, "CMB_fmode4"); this.CMB_fmode4.Name = "CMB_fmode4"; - this.toolTip1.SetToolTip(this.CMB_fmode4, resources.GetString("CMB_fmode4.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; - this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // CMB_fmode3 // - resources.ApplyResources(this.CMB_fmode3, "CMB_fmode3"); this.CMB_fmode3.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode3.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode3.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode3.FormattingEnabled = true; + resources.ApplyResources(this.CMB_fmode3, "CMB_fmode3"); this.CMB_fmode3.Name = "CMB_fmode3"; - this.toolTip1.SetToolTip(this.CMB_fmode3, resources.GetString("CMB_fmode3.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; - this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // CMB_fmode2 // - resources.ApplyResources(this.CMB_fmode2, "CMB_fmode2"); this.CMB_fmode2.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode2.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode2.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode2.FormattingEnabled = true; + resources.ApplyResources(this.CMB_fmode2, "CMB_fmode2"); this.CMB_fmode2.Name = "CMB_fmode2"; - this.toolTip1.SetToolTip(this.CMB_fmode2, resources.GetString("CMB_fmode2.ToolTip")); // // label1 // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; - this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // CMB_fmode1 // - resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1"); this.CMB_fmode1.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend; this.CMB_fmode1.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems; this.CMB_fmode1.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_fmode1.FormattingEnabled = true; + resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1"); this.CMB_fmode1.Name = "CMB_fmode1"; - this.toolTip1.SetToolTip(this.CMB_fmode1, resources.GetString("CMB_fmode1.ToolTip")); // // BUT_SaveModes // resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes"); this.BUT_SaveModes.Name = "BUT_SaveModes"; - this.toolTip1.SetToolTip(this.BUT_SaveModes, resources.GetString("BUT_SaveModes.ToolTip")); this.BUT_SaveModes.UseVisualStyleBackColor = true; this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click); // // tabHardware // - resources.ApplyResources(this.tabHardware, "tabHardware"); this.tabHardware.BackColor = System.Drawing.Color.DarkRed; this.tabHardware.Controls.Add(this.linkLabelmagdec); this.tabHardware.Controls.Add(this.label100); @@ -668,22 +620,20 @@ this.tabHardware.Controls.Add(this.pictureBox4); this.tabHardware.Controls.Add(this.pictureBox3); this.tabHardware.Controls.Add(this.pictureBox1); + resources.ApplyResources(this.tabHardware, "tabHardware"); this.tabHardware.Name = "tabHardware"; - this.toolTip1.SetToolTip(this.tabHardware, resources.GetString("tabHardware.ToolTip")); // // linkLabelmagdec // resources.ApplyResources(this.linkLabelmagdec, "linkLabelmagdec"); this.linkLabelmagdec.Name = "linkLabelmagdec"; this.linkLabelmagdec.TabStop = true; - this.toolTip1.SetToolTip(this.linkLabelmagdec, resources.GetString("linkLabelmagdec.ToolTip")); this.linkLabelmagdec.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked); // // label100 // resources.ApplyResources(this.label100, "label100"); this.label100.Name = "label100"; - this.toolTip1.SetToolTip(this.label100, resources.GetString("label100.ToolTip")); // // TXT_declination // @@ -696,7 +646,6 @@ // resources.ApplyResources(this.CHK_enableairspeed, "CHK_enableairspeed"); this.CHK_enableairspeed.Name = "CHK_enableairspeed"; - this.toolTip1.SetToolTip(this.CHK_enableairspeed, resources.GetString("CHK_enableairspeed.ToolTip")); this.CHK_enableairspeed.UseVisualStyleBackColor = true; this.CHK_enableairspeed.CheckedChanged += new System.EventHandler(this.CHK_enableairspeed_CheckedChanged); // @@ -704,7 +653,6 @@ // resources.ApplyResources(this.CHK_enablesonar, "CHK_enablesonar"); this.CHK_enablesonar.Name = "CHK_enablesonar"; - this.toolTip1.SetToolTip(this.CHK_enablesonar, resources.GetString("CHK_enablesonar.ToolTip")); this.CHK_enablesonar.UseVisualStyleBackColor = true; this.CHK_enablesonar.CheckedChanged += new System.EventHandler(this.CHK_enablesonar_CheckedChanged); // @@ -712,42 +660,37 @@ // resources.ApplyResources(this.CHK_enablecompass, "CHK_enablecompass"); this.CHK_enablecompass.Name = "CHK_enablecompass"; - this.toolTip1.SetToolTip(this.CHK_enablecompass, resources.GetString("CHK_enablecompass.ToolTip")); this.CHK_enablecompass.UseVisualStyleBackColor = true; this.CHK_enablecompass.CheckedChanged += new System.EventHandler(this.CHK_enablecompass_CheckedChanged); // // pictureBox4 // - resources.ApplyResources(this.pictureBox4, "pictureBox4"); this.pictureBox4.BackColor = System.Drawing.Color.White; this.pictureBox4.BackgroundImage = global::ArdupilotMega.Properties.Resources.airspeed; + resources.ApplyResources(this.pictureBox4, "pictureBox4"); this.pictureBox4.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox4.Name = "pictureBox4"; this.pictureBox4.TabStop = false; - this.toolTip1.SetToolTip(this.pictureBox4, resources.GetString("pictureBox4.ToolTip")); // // pictureBox3 // - resources.ApplyResources(this.pictureBox3, "pictureBox3"); this.pictureBox3.BackColor = System.Drawing.Color.White; this.pictureBox3.BackgroundImage = global::ArdupilotMega.Properties.Resources.sonar; + resources.ApplyResources(this.pictureBox3, "pictureBox3"); this.pictureBox3.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox3.Name = "pictureBox3"; this.pictureBox3.TabStop = false; - this.toolTip1.SetToolTip(this.pictureBox3, resources.GetString("pictureBox3.ToolTip")); // // pictureBox1 // - resources.ApplyResources(this.pictureBox1, "pictureBox1"); this.pictureBox1.BackgroundImage = global::ArdupilotMega.Properties.Resources.compass; + resources.ApplyResources(this.pictureBox1, "pictureBox1"); this.pictureBox1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox1.Name = "pictureBox1"; this.pictureBox1.TabStop = false; - this.toolTip1.SetToolTip(this.pictureBox1, resources.GetString("pictureBox1.ToolTip")); // // tabBattery // - resources.ApplyResources(this.tabBattery, "tabBattery"); this.tabBattery.Controls.Add(this.TXT_ampspervolt); this.tabBattery.Controls.Add(this.TXT_divider); this.tabBattery.Controls.Add(this.TXT_voltage); @@ -764,15 +707,14 @@ this.tabBattery.Controls.Add(this.TXT_battcapacity); this.tabBattery.Controls.Add(this.CMB_batmontype); this.tabBattery.Controls.Add(this.pictureBox5); + resources.ApplyResources(this.tabBattery, "tabBattery"); this.tabBattery.Name = "tabBattery"; - this.toolTip1.SetToolTip(this.tabBattery, resources.GetString("tabBattery.ToolTip")); this.tabBattery.UseVisualStyleBackColor = true; // // TXT_ampspervolt // resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt"); this.TXT_ampspervolt.Name = "TXT_ampspervolt"; - this.toolTip1.SetToolTip(this.TXT_ampspervolt, resources.GetString("TXT_ampspervolt.ToolTip")); this.TXT_ampspervolt.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_ampspervolt_Validating); this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated); // @@ -780,23 +722,20 @@ // resources.ApplyResources(this.TXT_divider, "TXT_divider"); this.TXT_divider.Name = "TXT_divider"; - this.toolTip1.SetToolTip(this.TXT_divider, resources.GetString("TXT_divider.ToolTip")); this.TXT_divider.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_divider_Validating); this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated); // // TXT_voltage // - resources.ApplyResources(this.TXT_voltage, "TXT_voltage"); this.TXT_voltage.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "battery_voltage", true)); + resources.ApplyResources(this.TXT_voltage, "TXT_voltage"); this.TXT_voltage.Name = "TXT_voltage"; this.TXT_voltage.ReadOnly = true; - this.toolTip1.SetToolTip(this.TXT_voltage, resources.GetString("TXT_voltage.ToolTip")); // // TXT_measuredvoltage // resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage"); this.TXT_measuredvoltage.Name = "TXT_measuredvoltage"; - this.toolTip1.SetToolTip(this.TXT_measuredvoltage, resources.GetString("TXT_measuredvoltage.ToolTip")); this.TXT_measuredvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_measuredvoltage_Validating); this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated); // @@ -804,7 +743,6 @@ // resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage"); this.TXT_inputvoltage.Name = "TXT_inputvoltage"; - this.toolTip1.SetToolTip(this.TXT_inputvoltage, resources.GetString("TXT_inputvoltage.ToolTip")); this.TXT_inputvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_inputvoltage_Validating); this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated); // @@ -812,62 +750,52 @@ // resources.ApplyResources(this.label35, "label35"); this.label35.Name = "label35"; - this.toolTip1.SetToolTip(this.label35, resources.GetString("label35.ToolTip")); // // label34 // resources.ApplyResources(this.label34, "label34"); this.label34.Name = "label34"; - this.toolTip1.SetToolTip(this.label34, resources.GetString("label34.ToolTip")); // // label33 // resources.ApplyResources(this.label33, "label33"); this.label33.Name = "label33"; - this.toolTip1.SetToolTip(this.label33, resources.GetString("label33.ToolTip")); // // label32 // resources.ApplyResources(this.label32, "label32"); this.label32.Name = "label32"; - this.toolTip1.SetToolTip(this.label32, resources.GetString("label32.ToolTip")); // // label31 // resources.ApplyResources(this.label31, "label31"); this.label31.Name = "label31"; - this.toolTip1.SetToolTip(this.label31, resources.GetString("label31.ToolTip")); // // textBox3 // resources.ApplyResources(this.textBox3, "textBox3"); this.textBox3.Name = "textBox3"; this.textBox3.ReadOnly = true; - this.toolTip1.SetToolTip(this.textBox3, resources.GetString("textBox3.ToolTip")); // // label29 // resources.ApplyResources(this.label29, "label29"); this.label29.Name = "label29"; - this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; - this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // TXT_battcapacity // resources.ApplyResources(this.TXT_battcapacity, "TXT_battcapacity"); this.TXT_battcapacity.Name = "TXT_battcapacity"; - this.toolTip1.SetToolTip(this.TXT_battcapacity, resources.GetString("TXT_battcapacity.ToolTip")); this.TXT_battcapacity.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_battcapacity_Validating); this.TXT_battcapacity.Validated += new System.EventHandler(this.TXT_battcapacity_Validated); // // CMB_batmontype // - resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype"); this.CMB_batmontype.FormattingEnabled = true; this.CMB_batmontype.Items.AddRange(new object[] { resources.GetString("CMB_batmontype.Items"), @@ -875,82 +803,73 @@ resources.GetString("CMB_batmontype.Items2"), resources.GetString("CMB_batmontype.Items3"), resources.GetString("CMB_batmontype.Items4")}); + resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype"); this.CMB_batmontype.Name = "CMB_batmontype"; - this.toolTip1.SetToolTip(this.CMB_batmontype, resources.GetString("CMB_batmontype.ToolTip")); this.CMB_batmontype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmontype_SelectedIndexChanged); // // pictureBox5 // - resources.ApplyResources(this.pictureBox5, "pictureBox5"); this.pictureBox5.BackColor = System.Drawing.Color.White; this.pictureBox5.BackgroundImage = global::ArdupilotMega.Properties.Resources.attocurrent; + resources.ApplyResources(this.pictureBox5, "pictureBox5"); this.pictureBox5.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox5.Name = "pictureBox5"; this.pictureBox5.TabStop = false; - this.toolTip1.SetToolTip(this.pictureBox5, resources.GetString("pictureBox5.ToolTip")); // // tabArducopter // - resources.ApplyResources(this.tabArducopter, "tabArducopter"); this.tabArducopter.Controls.Add(this.label28); this.tabArducopter.Controls.Add(this.label16); this.tabArducopter.Controls.Add(this.label15); this.tabArducopter.Controls.Add(this.pictureBoxQuadX); this.tabArducopter.Controls.Add(this.pictureBoxQuad); this.tabArducopter.Controls.Add(this.BUT_levelac2); + resources.ApplyResources(this.tabArducopter, "tabArducopter"); this.tabArducopter.Name = "tabArducopter"; - this.toolTip1.SetToolTip(this.tabArducopter, resources.GetString("tabArducopter.ToolTip")); this.tabArducopter.UseVisualStyleBackColor = true; // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; - this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; - this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; - this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // pictureBoxQuadX // - resources.ApplyResources(this.pictureBoxQuadX, "pictureBoxQuadX"); this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand; this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.frames_04; + resources.ApplyResources(this.pictureBoxQuadX, "pictureBoxQuadX"); this.pictureBoxQuadX.Name = "pictureBoxQuadX"; this.pictureBoxQuadX.TabStop = false; - this.toolTip1.SetToolTip(this.pictureBoxQuadX, resources.GetString("pictureBoxQuadX.ToolTip")); this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click); // // pictureBoxQuad // - resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad"); this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand; this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.frames_03; + resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad"); this.pictureBoxQuad.Name = "pictureBoxQuad"; this.pictureBoxQuad.TabStop = false; - this.toolTip1.SetToolTip(this.pictureBoxQuad, resources.GetString("pictureBoxQuad.ToolTip")); this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click); // // BUT_levelac2 // resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2"); this.BUT_levelac2.Name = "BUT_levelac2"; - this.toolTip1.SetToolTip(this.BUT_levelac2, resources.GetString("BUT_levelac2.ToolTip")); this.BUT_levelac2.UseVisualStyleBackColor = true; this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click); // // tabHeli // - resources.ApplyResources(this.tabHeli, "tabHeli"); this.tabHeli.Controls.Add(this.groupBox3); this.tabHeli.Controls.Add(this.label44); this.tabHeli.Controls.Add(this.label43); @@ -987,39 +906,35 @@ this.tabHeli.Controls.Add(this.HS4); this.tabHeli.Controls.Add(this.HS3); this.tabHeli.Controls.Add(this.Gservoloc); + resources.ApplyResources(this.tabHeli, "tabHeli"); this.tabHeli.Name = "tabHeli"; - this.toolTip1.SetToolTip(this.tabHeli, resources.GetString("tabHeli.ToolTip")); this.tabHeli.UseVisualStyleBackColor = true; this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click); // // groupBox3 // - resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Controls.Add(this.label46); this.groupBox3.Controls.Add(this.label45); this.groupBox3.Controls.Add(this.GYR_ENABLE_); this.groupBox3.Controls.Add(this.GYR_GAIN_); + resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Name = "groupBox3"; this.groupBox3.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox3, resources.GetString("groupBox3.ToolTip")); // // label46 // resources.ApplyResources(this.label46, "label46"); this.label46.Name = "label46"; - this.toolTip1.SetToolTip(this.label46, resources.GetString("label46.ToolTip")); // // label45 // resources.ApplyResources(this.label45, "label45"); this.label45.Name = "label45"; - this.toolTip1.SetToolTip(this.label45, resources.GetString("label45.ToolTip")); // // GYR_ENABLE_ // resources.ApplyResources(this.GYR_ENABLE_, "GYR_ENABLE_"); this.GYR_ENABLE_.Name = "GYR_ENABLE_"; - this.toolTip1.SetToolTip(this.GYR_ENABLE_, resources.GetString("GYR_ENABLE_.ToolTip")); this.GYR_ENABLE_.UseVisualStyleBackColor = true; this.GYR_ENABLE_.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged); // @@ -1027,57 +942,49 @@ // resources.ApplyResources(this.GYR_GAIN_, "GYR_GAIN_"); this.GYR_GAIN_.Name = "GYR_GAIN_"; - this.toolTip1.SetToolTip(this.GYR_GAIN_, resources.GetString("GYR_GAIN_.ToolTip")); this.GYR_GAIN_.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating); // // label44 // resources.ApplyResources(this.label44, "label44"); this.label44.Name = "label44"; - this.toolTip1.SetToolTip(this.label44, resources.GetString("label44.ToolTip")); // // label43 // resources.ApplyResources(this.label43, "label43"); this.label43.Name = "label43"; - this.toolTip1.SetToolTip(this.label43, resources.GetString("label43.ToolTip")); // // label42 // resources.ApplyResources(this.label42, "label42"); this.label42.Name = "label42"; - this.toolTip1.SetToolTip(this.label42, resources.GetString("label42.ToolTip")); // // BUT_HS4save // resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save"); this.BUT_HS4save.Name = "BUT_HS4save"; - this.toolTip1.SetToolTip(this.BUT_HS4save, resources.GetString("BUT_HS4save.ToolTip")); this.BUT_HS4save.UseVisualStyleBackColor = true; this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click); // // groupBox2 // - resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Controls.Add(this.label24); this.groupBox2.Controls.Add(this.HS4_MIN); this.groupBox2.Controls.Add(this.HS4_MAX); this.groupBox2.Controls.Add(this.label40); + resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Name = "groupBox2"; this.groupBox2.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox2, resources.GetString("groupBox2.ToolTip")); // // label24 // resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; - this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // HS4_MIN // resources.ApplyResources(this.HS4_MIN, "HS4_MIN"); this.HS4_MIN.Name = "HS4_MIN"; - this.toolTip1.SetToolTip(this.HS4_MIN, resources.GetString("HS4_MIN.ToolTip")); this.HS4_MIN.Enter += new System.EventHandler(this.HS4_MIN_Enter); this.HS4_MIN.Leave += new System.EventHandler(this.HS4_MIN_Leave); this.HS4_MIN.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1086,7 +993,6 @@ // resources.ApplyResources(this.HS4_MAX, "HS4_MAX"); this.HS4_MAX.Name = "HS4_MAX"; - this.toolTip1.SetToolTip(this.HS4_MAX, resources.GetString("HS4_MAX.ToolTip")); this.HS4_MAX.Enter += new System.EventHandler(this.HS4_MAX_Enter); this.HS4_MAX.Leave += new System.EventHandler(this.HS4_MAX_Leave); this.HS4_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1095,46 +1001,40 @@ // resources.ApplyResources(this.label40, "label40"); this.label40.Name = "label40"; - this.toolTip1.SetToolTip(this.label40, resources.GetString("label40.ToolTip")); // // BUT_swash_manual // resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual"); this.BUT_swash_manual.Name = "BUT_swash_manual"; - this.toolTip1.SetToolTip(this.BUT_swash_manual, resources.GetString("BUT_swash_manual.ToolTip")); this.BUT_swash_manual.UseVisualStyleBackColor = true; this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click); // // groupBox1 // - resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Controls.Add(this.label41); this.groupBox1.Controls.Add(this.label21); this.groupBox1.Controls.Add(this.COL_MIN_); this.groupBox1.Controls.Add(this.COL_MID_); this.groupBox1.Controls.Add(this.COL_MAX_); this.groupBox1.Controls.Add(this.BUT_0collective); + resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Name = "groupBox1"; this.groupBox1.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox1, resources.GetString("groupBox1.ToolTip")); // // label41 // resources.ApplyResources(this.label41, "label41"); this.label41.Name = "label41"; - this.toolTip1.SetToolTip(this.label41, resources.GetString("label41.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; - this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // COL_MIN_ // resources.ApplyResources(this.COL_MIN_, "COL_MIN_"); this.COL_MIN_.Name = "COL_MIN_"; - this.toolTip1.SetToolTip(this.COL_MIN_, resources.GetString("COL_MIN_.ToolTip")); this.COL_MIN_.Enter += new System.EventHandler(this.COL_MIN__Enter); this.COL_MIN_.Leave += new System.EventHandler(this.COL_MIN__Leave); this.COL_MIN_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1143,14 +1043,12 @@ // resources.ApplyResources(this.COL_MID_, "COL_MID_"); this.COL_MID_.Name = "COL_MID_"; - this.toolTip1.SetToolTip(this.COL_MID_, resources.GetString("COL_MID_.ToolTip")); this.COL_MID_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); // // COL_MAX_ // resources.ApplyResources(this.COL_MAX_, "COL_MAX_"); this.COL_MAX_.Name = "COL_MAX_"; - this.toolTip1.SetToolTip(this.COL_MAX_, resources.GetString("COL_MAX_.ToolTip")); this.COL_MAX_.Enter += new System.EventHandler(this.COL_MAX__Enter); this.COL_MAX_.Leave += new System.EventHandler(this.COL_MAX__Leave); this.COL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating); @@ -1159,7 +1057,6 @@ // resources.ApplyResources(this.BUT_0collective, "BUT_0collective"); this.BUT_0collective.Name = "BUT_0collective"; - this.toolTip1.SetToolTip(this.BUT_0collective, resources.GetString("BUT_0collective.ToolTip")); this.BUT_0collective.UseVisualStyleBackColor = true; this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click); // @@ -1177,7 +1074,6 @@ 0, 0}); this.HS4_TRIM.Name = "HS4_TRIM"; - this.toolTip1.SetToolTip(this.HS4_TRIM, resources.GetString("HS4_TRIM.ToolTip")); this.HS4_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1199,7 +1095,6 @@ 0, 0}); this.HS3_TRIM.Name = "HS3_TRIM"; - this.toolTip1.SetToolTip(this.HS3_TRIM, resources.GetString("HS3_TRIM.ToolTip")); this.HS3_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1221,7 +1116,6 @@ 0, 0}); this.HS2_TRIM.Name = "HS2_TRIM"; - this.toolTip1.SetToolTip(this.HS2_TRIM, resources.GetString("HS2_TRIM.ToolTip")); this.HS2_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1243,7 +1137,6 @@ 0, 0}); this.HS1_TRIM.Name = "HS1_TRIM"; - this.toolTip1.SetToolTip(this.HS1_TRIM, resources.GetString("HS1_TRIM.ToolTip")); this.HS1_TRIM.Value = new decimal(new int[] { 1500, 0, @@ -1255,69 +1148,58 @@ // resources.ApplyResources(this.label39, "label39"); this.label39.Name = "label39"; - this.toolTip1.SetToolTip(this.label39, resources.GetString("label39.ToolTip")); // // label38 // resources.ApplyResources(this.label38, "label38"); this.label38.Name = "label38"; - this.toolTip1.SetToolTip(this.label38, resources.GetString("label38.ToolTip")); // // label37 // resources.ApplyResources(this.label37, "label37"); this.label37.Name = "label37"; - this.toolTip1.SetToolTip(this.label37, resources.GetString("label37.ToolTip")); // // label36 // resources.ApplyResources(this.label36, "label36"); this.label36.Name = "label36"; - this.toolTip1.SetToolTip(this.label36, resources.GetString("label36.ToolTip")); // // label26 // resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; - this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // PIT_MAX_ // resources.ApplyResources(this.PIT_MAX_, "PIT_MAX_"); this.PIT_MAX_.Name = "PIT_MAX_"; - this.toolTip1.SetToolTip(this.PIT_MAX_, resources.GetString("PIT_MAX_.ToolTip")); this.PIT_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; - this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); // // ROL_MAX_ // resources.ApplyResources(this.ROL_MAX_, "ROL_MAX_"); this.ROL_MAX_.Name = "ROL_MAX_"; - this.toolTip1.SetToolTip(this.ROL_MAX_, resources.GetString("ROL_MAX_.ToolTip")); this.ROL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating); // // label23 // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; - this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; - this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // HS4_REV // resources.ApplyResources(this.HS4_REV, "HS4_REV"); this.HS4_REV.Name = "HS4_REV"; - this.toolTip1.SetToolTip(this.HS4_REV, resources.GetString("HS4_REV.ToolTip")); this.HS4_REV.UseVisualStyleBackColor = true; this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged); // @@ -1325,46 +1207,39 @@ // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; - this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // label19 // resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; - this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip")); // // label18 // resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; - this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip")); // // SV3_POS_ // resources.ApplyResources(this.SV3_POS_, "SV3_POS_"); this.SV3_POS_.Name = "SV3_POS_"; - this.toolTip1.SetToolTip(this.SV3_POS_, resources.GetString("SV3_POS_.ToolTip")); this.SV3_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating); // // SV2_POS_ // resources.ApplyResources(this.SV2_POS_, "SV2_POS_"); this.SV2_POS_.Name = "SV2_POS_"; - this.toolTip1.SetToolTip(this.SV2_POS_, resources.GetString("SV2_POS_.ToolTip")); this.SV2_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating); // // SV1_POS_ // resources.ApplyResources(this.SV1_POS_, "SV1_POS_"); this.SV1_POS_.Name = "SV1_POS_"; - this.toolTip1.SetToolTip(this.SV1_POS_, resources.GetString("SV1_POS_.ToolTip")); this.SV1_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating); // // HS3_REV // resources.ApplyResources(this.HS3_REV, "HS3_REV"); this.HS3_REV.Name = "HS3_REV"; - this.toolTip1.SetToolTip(this.HS3_REV, resources.GetString("HS3_REV.ToolTip")); this.HS3_REV.UseVisualStyleBackColor = true; this.HS3_REV.CheckedChanged += new System.EventHandler(this.HS3_REV_CheckedChanged); // @@ -1372,7 +1247,6 @@ // resources.ApplyResources(this.HS2_REV, "HS2_REV"); this.HS2_REV.Name = "HS2_REV"; - this.toolTip1.SetToolTip(this.HS2_REV, resources.GetString("HS2_REV.ToolTip")); this.HS2_REV.UseVisualStyleBackColor = true; this.HS2_REV.CheckedChanged += new System.EventHandler(this.HS2_REV_CheckedChanged); // @@ -1380,7 +1254,6 @@ // resources.ApplyResources(this.HS1_REV, "HS1_REV"); this.HS1_REV.Name = "HS1_REV"; - this.toolTip1.SetToolTip(this.HS1_REV, resources.GetString("HS1_REV.ToolTip")); this.HS1_REV.UseVisualStyleBackColor = true; this.HS1_REV.CheckedChanged += new System.EventHandler(this.HS1_REV_CheckedChanged); // @@ -1388,47 +1261,44 @@ // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; - this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // HS4 // - resources.ApplyResources(this.HS4, "HS4"); this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.HS4.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.HS4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true)); this.HS4.Label = "Rudder"; + resources.ApplyResources(this.HS4, "HS4"); this.HS4.Maximum = 2200; this.HS4.maxline = 0; this.HS4.Minimum = 800; this.HS4.minline = 0; this.HS4.Name = "HS4"; - this.toolTip1.SetToolTip(this.HS4, resources.GetString("HS4.ToolTip")); this.HS4.Value = 1500; this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); this.HS4.Paint += new System.Windows.Forms.PaintEventHandler(this.HS4_Paint); // // HS3 // - resources.ApplyResources(this.HS3, "HS3"); this.HS3.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); this.HS3.BorderColor = System.Drawing.SystemColors.ActiveBorder; this.HS3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true)); this.HS3.Label = "Collective"; + resources.ApplyResources(this.HS3, "HS3"); this.HS3.Maximum = 2200; this.HS3.maxline = 0; this.HS3.Minimum = 800; this.HS3.minline = 0; this.HS3.Name = "HS3"; - this.toolTip1.SetToolTip(this.HS3, resources.GetString("HS3.ToolTip")); this.HS3.Value = 1500; this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); this.HS3.Paint += new System.Windows.Forms.PaintEventHandler(this.HS3_Paint); // // Gservoloc // - resources.ApplyResources(this.Gservoloc, "Gservoloc"); this.Gservoloc.BackColor = System.Drawing.Color.Transparent; this.Gservoloc.BackgroundImage = global::ArdupilotMega.Properties.Resources.Gaugebg; + resources.ApplyResources(this.Gservoloc, "Gservoloc"); this.Gservoloc.BaseArcColor = System.Drawing.Color.Transparent; this.Gservoloc.BaseArcRadius = 60; this.Gservoloc.BaseArcStart = 90; @@ -1561,7 +1431,6 @@ this.Gservoloc.ScaleNumbersRotation = 45; this.Gservoloc.ScaleNumbersStartScaleLine = 2; this.Gservoloc.ScaleNumbersStepScaleLines = 1; - this.toolTip1.SetToolTip(this.Gservoloc, resources.GetString("Gservoloc.ToolTip")); this.Gservoloc.Value = 0F; this.Gservoloc.Value0 = -60F; this.Gservoloc.Value1 = 60F; @@ -1575,7 +1444,6 @@ this.Controls.Add(this.tabControl1); this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow; this.Name = "Setup"; - this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing); this.Load += new System.EventHandler(this.Setup_Load); this.tabControl1.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs index 2b55175ff8..c40d138e23 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs @@ -1055,8 +1055,8 @@ namespace ArdupilotMega.Setup try { #if MAVLINK10 - int fixme; - // MainV2.comPort.doCommand(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC); + int fixme; // needs to be accel only + MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,1,1,1,1,1,1); #else MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC); #endif diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx index db16ceae3d..d1d8d1e2a1 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx @@ -117,2613 +117,1853 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 135 + + + NoControl - - 674, 419 - - - - 2, 0, 2, 0 - - - 94 - - - 129 - - - Zero - - - Zoom - - - 100 - - - 24, 13 - - - 170, 25 - - - 98 - - - - - - 305, 50 - - - 13 - - - 2 - - - label26 - - - HS2_TRIM - - - NoControl - - - 28, 227 - - - label3 - - - - - - NoControl - - - 390, 80 - - - CB_simple4 - - - 69, 23 - - - SV1_POS_ - - - NoControl - - - Hardware - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - PWM 1750 + - - - Enable Compass - - - Amperes per volt: - - - tabBattery - - - NoControl - - - True - - - 119 - - - NoControl - - - 2 - - - 15, 14 - - - Flight Mode 6 - - - 13, 13 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - - - - 10 - - - label40 - - - 103, 17 - - - 2 - - - 2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 23, 248 - - - 256, 345 - - - 25 - - - 245, 179 - - - True - - - Manual - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - pictureBox5 - - - 15 - - - NoControl - - - Flight Mode 5 - - - 0 - - - label41 - - - tabModes - - - label7 - - - tabModes - - - 3 - - - - - - tabBattery - - - Swash-Servo position - - - CHK_revch4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - label42 - - - 21 - - - 103 - - - pictureBox4 - - - False - - - TXT_divider - - - 0 - - - label46 - - - 7 - - - 114 - - - - - - groupBox3 - - - tabHardware - - - True - - - 122 - - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - 66, 17 - - - label22 - - - 41, 35 - - - 115 - - - Voltage divider: - - - 20 - - - tabBattery - - - 0: Disabled - - - tabHeli - - - tabArducopter - - - 29, 270 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - 5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2, 0, 2, 0 - - - PWM 1361 - 1490 - - - CMB_fmode2 - - - 16 - - - CB_simple2 - - - 506, 155 - - - tabModes - - - NoControl - - - pictureBox1 - - - 162, 180 - - - 93 - - - 14 - - - toolTip1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - Flight Mode 2 - - - 8 - - - - - - label100 - - - tabHardware - - - CHK_enablesonar - - - NoControl - - - 446, 185 - - - 1 - - - 162, 245 - - - HS4_MIN - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 168, 209 - - - 26 - - - - - - tabBattery - - - 94, 13 - - - tabHeli - - - 168, 155 - - - NoControl - - - 106 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 11 - - - tabBattery - - - 4, 22 - - - 1 - - - 87, 17 - - - textBox3 - - - False - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label29 - - - Trim - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 78, 25 - - - - - - tabHeli - - - 48, 13 - - - tabControl1 - - - 2, 0, 2, 0 - - - NOTE: images are for presentation only -will work with hexa's etc - - - 66, 17 - - - 2 - - - Calibrate Radio - - - 2, 2, 2, 2 - - - 5 - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Flight Mode 1 - - - NoControl - - - 94 - - - True - - - 101, 225 - - - 1 - - - - - - 6 - - - NoControl - - - 380, 154 - - - - - - label14 - - - - - - tabBattery - - - 2, 2, 2, 2 - - - - - - 76, 20 - - - label43 - - - NoControl - - - 315, 310 - - - tabModes - - - Flight Mode 4 - - - - - - True - - - 288, 23 - - - True - - - - - - 13, 13 - - - 2 - - - System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2, 2, 2, 2 - - - True - - - 96 - - - 23 - - - 104 - - - 39, 20 - - - - - - 1500 - - - 2, 2, 2, 2 - - - - - - 134, 23 - - - 256, 321 - - - 104, 13 - - - 76, 20 - - - 37 - - - 2 - - - Current Mode: - - - 121, 23 - - - 42, 13 - - - Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 - - - 3 - - - - - - tabBattery - - - 57, 19 - - - 82 - - - 1 - - - NoControl - - - 71, 13 - - - NoControl - - - 107 - - - 245, 98 - - - tabArducopter - - - True - - - pictureBoxQuad - - - tabArducopter - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - 12 - - - - - - tabBattery - - - 10 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - 25 - - - BUT_Calibrateradio - - - 30 - - - 69, 23 - - - CMB_fmode6 - - - 134 - - - True - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 12 - - - tabBattery - - - NoControl - - - - - - 2 - - - 3 - - - 44, 20 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 43, 20 - - - 11 - - - 6 - - - - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - True - - - - - - 87, 17 - - - NoControl - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 506, 209 - - - 5 - - - - - - 25 - - - True - - - Zoom - - - 90, 17 - - - 28 - - - 108 - - - True - - - 0 - - - 1 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Enable Airspeed - - - $this - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - BARthrottle - - - tabHeli - - - 168, 128 - - - 105 - - - - - - -60 - - - 126 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - 33 - - - NoControl - - - 32 - - - label16 - - - True - - - 27, 13 - - - NoControl - - - 32 - - - groupBox1 - - - tabBattery - - - 7 - - - tabRadioIn - - - 274, 67 - - - 22 - - - - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - HS3_REV - - - 95 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 105 - - - - - - True - - - groupBox1 - - - 0 - - - 4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label17 - - - 6 - - - 169, 78 - - - 22 - - - - - - CMB_batmontype - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 23 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2, 2, 2, 2 - - - 6 - - - 92 - - - 44, 20 - - - CMB_fmode4 - - - NoControl - - - - - - - - - 93 - - - 78, 106 - - - - - - tabBattery - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - NoControl - - - ROL_MAX_ - - - 18, 45 - - - 43, 20 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 47, 211 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 4, 22 - - - tabRadioIn - - - Gain - - - Min - - - - - - 10 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15, 14 - - - tabHeli - - - tabModes - - - False - - - 110 - - - Zoom - - - 506, 101 - - - 10 - - - tabHeli - - - tabModes - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - HS3_TRIM - - - 43, 20 - - - 83, 20 - - - 118 - - - True - - - 94, 13 - - - TXT_battcapacity - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 91 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - 3 - - - Enable - - - True - - - label2 - - - 102 - - - Zoom - - - label6 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 8 - - - tabModes - - - 24, 28 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - 42, 13 - - - Swash Travel - - - 210, 13 - - - label13 - - - 121, 21 - - - 9 - - - BAR8 - - - 54, 13 - - - 28 - - - 35 - - - tabArducopter - - - 132 - - - 117 - - - 0 - - - 7 - - - Monitor - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - Level your quad to set default accel offsets - - - 19 - - - 6 - - - - - - 3 - - - 162, 56 - - - Reverse - - - 121, 21 - - - 446, 130 - - - 36 - - - 2, 0, 2, 0 - - - 4: Volts & Current - - - tabHeli - - - 24 - - - 106, 40 - - - NoControl - - - True - - - 19 - - - 3 - - - True - - - 128 - - - Current PWM: - - - label31 - - - 13 - - - 23 - - - 499, 225 - - - 0 - - - tabBattery - - - 97 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - HS1_TRIM - - - - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - tabRadioIn - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - tabHeli - - - NoControl - - - 71, 13 - - - 44, 20 - - - 479, 138 - - - tabRadioIn - - - 12 - - - Top - - - - - - currentStateBindingSource - - - 383, 57 - - - 242, 67 - - - 21 - - - CHK_enableairspeed - - - 2 - - - HS1_REV - - - 76, 20 - - - tabModes - - - CHK_enablecompass - - - 132 - - - tabHeli - - - 28 - - - tabHeli - - - tabModes - - - True - - - 101, 248 - - - 29, 13 - - - 14 - - - tabModes - - - Flight Mode 3 - - - 20 - - - NoControl - - - 293, 52 - - - 87, 17 - - - 87, 17 - - - 121, 21 - - - 180 - - - 87, 17 - - - groupBox1 - - - 11 - - - NoControl - - - 131 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - tabHeli - - - 168, 101 - - - Microsoft Sans Serif, 9pt - - - NoControl - - - Rudder - - - label44 - - - - - - tabModes - - - Zoom - - - 135 - - - 674, 419 - - - 476, 23 - - - 190, 190 - - - 168, 236 - - - 94, 13 - - - 0 - - - 28, 183 - - - groupBox3 - - - Zoom - - - 482, 340 - - - 506, 128 - - - 4, 22 - - - tabModes - - - tabHeli - - - tabHeli - - - 123, 50 - - - 9 - - - 6 - - - PWM 0 - 1230 - - - True - - - 190, 190 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 15, 14 - - - True - - - tabRadioIn - - - 2 - - - True - - - Manual - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Level - - - 666, 393 - - - False - - - 2 - - - 4 - - - 242, 42 - - - CMB_fmode3 - - - 121, 21 - - - True - - - NoControl - - - TXT_measuredvoltage - - - tabHeli - - - tabHeli - - - True - - - 5 - - - 21, 304 + + 214, 161 195, 23 - - Simple Mode - - - 113 - - - 428, 62 - - - tabModes - - + + 0 - - 75, 75 + + Reset APM Hardware to Default - - 666, 393 - - - BUT_0collective - - - 5 - - - 111 - - - 235, 52 - - - label34 - - - 4 - - - tabHeli - - - - - - - - - 96 - - - Bottom - - - 359, 61 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 7 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 44, 20 - - - tabHeli - - - label33 - - - - - - 71, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 31 - - - 115 - - - Pitch Max - - - 109 - - - 245, 206 - - - label35 - - - True - - - - - - NoControl - - - 87, 17 - - - 112 - - - - - - 101 - - - 26 - - - groupBox2 - - - 106 - - - 71, 13 - - - 118 - - - NoControl + + BUT_reset - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - + + tabReset - - True + + 0 - - tabModes + + 4, 22 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 666, 393 - - NoControl + + 4 - - 5 + + Reset - + + tabReset + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + + tabControl1 - - 13, 13 + + 0 - + True - - 3 - - - 0, 0 - - - NoControl - - - 28, 205 - - - 192, 26 - - - 42, 213 - - - tabModes - - + NoControl 287, 158 - - 75, 75 + + 66, 17 - - 26, 13 + + 106 - - 81 + + Reverse - + + CHK_revch3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + + True - - tabModes - - + NoControl + + 315, 310 + + + 66, 17 + + + 105 + + + Reverse + + + CHK_revch4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 1 + + + True + + + NoControl + + + 71, 158 + + + 66, 17 + + + 104 + + + Reverse + + + CHK_revch2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 2 + + + True + + + NoControl + + + 315, 12 + + + 66, 17 + + + 103 + + + Reverse + + + CHK_revch1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 3 + NoControl - - 0 + + 482, 340 - - + + 134, 23 - - + + 102 - - PWM 1231 - 1360 + + Calibrate Radio - - NoControl + + BUT_Calibrateradio - - NoControl + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - 19, 157 - - - 72, 13 - - - BUT_reset - - - 93 - - - - - - tabControl1 - - - 75, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - Radio Input - - - label30 - - - 42, 13 - - - - - - 121, 20 - - - 15 - - - BARyaw - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 150, 150 - - - 125 - - - 177, 46 - - - 105, 17 - - - 76, 20 - - - 18, 173 - - - Rudder Travel - - - 2, 2, 2, 2 - - - GYR_GAIN_ - - - Battery voltage: - - - NoControl - - - 27 - - - Rev - - - 1500 - - - BUT_SaveModes - - - Enable Sonar - - - True - - - 31 - - - 217, 38 - - - 1500 - - - 38 - - - 1 - - - tabModes - - - 130 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label24 - - - 137 - - - - - - 380, 127 - - - 14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - - - - SV2_POS_ - - - - - - 4 - - - label36 - - - - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 27, 23 - - + tabRadioIn - - 27 + + 4 - - 4500 + + 17, 17 + + + 446, 240 - - tabHeli + + 170, 25 - - CB_simple1 + + 101 - - tabHeli + + BAR8 - - True + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - + + tabRadioIn - - tabArducopter + + 5 - + + 446, 185 + + + 170, 25 + + + 100 + + + BAR7 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 6 + + + 446, 130 + + + 170, 25 + + + 99 + + + BAR6 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 7 + + + 446, 75 + + + 170, 25 + + 98 - - CB_simple5 + + BAR5 - - + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + tabRadioIn - - groupBox2 + + 8 - - + + 143, 61 - - 2, 2, 2, 2 + + 47, 211 - - NoControl + + 96 - - + + BARpitch - - 116 + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - True - - - label37 + + tabRadioIn 9 - - 27, 13 + + 359, 61 + + + 47, 211 + + + 95 + + + BARthrottle + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 10 + + + 21, 304 288, 23 + + 94 + + + BARyaw + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 11 + + + 21, 6 + + + 288, 23 + + + 93 + + + BARroll + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabRadioIn + + + 12 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 0 + + + Radio Input + + + tabRadioIn + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 1 + + + True + + + NoControl + + + 380, 235 + + + 2, 2, 2, 2 + + + 87, 17 + + + 119 + + + Simple Mode + + + CB_simple6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 0 + + + True + + + NoControl + + + 380, 208 + + + 2, 2, 2, 2 + + + 87, 17 + + + 118 + + + Simple Mode + + + CB_simple5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 1 + + + True + + + NoControl + + + 380, 181 + + + 2, 2, 2, 2 + + + 87, 17 + + + 117 + + + Simple Mode + + + CB_simple4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 2 + + + True + + + NoControl + + + 380, 154 + + + 2, 2, 2, 2 + + + 87, 17 + + + 116 + + + Simple Mode + + + CB_simple3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 3 + + + True + + + NoControl + + + 380, 127 + + + 2, 2, 2, 2 + + + 87, 17 + + + 115 + + + Simple Mode + + + CB_simple2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 4 + + + True + + + 380, 100 + + + 2, 2, 2, 2 + + + 87, 17 + + + 114 + + + Simple Mode + + + CB_simple1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 5 + + + True + + + NoControl + + + 242, 67 + + + 74, 13 + + + 113 + + + Current PWM: + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 6 + + + True + + + NoControl + + + 322, 67 + + + 13, 13 + + + 112 + + + 0 + + + LBL_flightmodepwm + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 7 + + + True + + + NoControl + + + 242, 50 + + + 74, 13 + + + 111 + + + Current Mode: + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 8 + + + True + + + NoControl + + + 322, 50 + + + 42, 13 + + + 110 + + + Manual + + + lbl_currentmode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 9 + + + True + + + NoControl + + + 506, 101 + + + 76, 13 + + + 109 + + + PWM 0 - 1230 + + + False + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 10 + + + True + + + NoControl + + + 506, 236 + + + 70, 13 + + + 108 + + + PWM 1750 + + + + False + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 11 + + + True + + + NoControl + + + 506, 209 + + + 94, 13 + + + 107 + + + PWM 1621 - 1749 + + + False + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 12 + + + True + + + NoControl + + + 506, 182 + + + 94, 13 + + + 106 + + + PWM 1491 - 1620 + + + False + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 13 + + + True + + + NoControl + + + 506, 155 + + + 94, 13 + + + 105 + + + PWM 1361 - 1490 + + + False + + + label8 + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + tabModes + + + 14 + + + True + + + NoControl + + + 506, 128 + + + 94, 13 + + + 104 + + + PWM 1231 - 1360 + + + False + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 15 + + + True + NoControl - + + 168, 236 + + + 71, 13 + + + 11 + + + Flight Mode 6 + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 16 + + + 245, 233 + + + 121, 21 + + + 10 + + + CMB_fmode6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 17 + + True - + + NoControl + + + 168, 209 + + + 71, 13 + + + 9 + + + Flight Mode 5 + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 18 + + + 245, 206 + + + 121, 21 + + + 8 + + + CMB_fmode5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 19 + + + True + + + NoControl + + + 168, 182 + + + 71, 13 + + + 7 + + + Flight Mode 4 + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 20 + + + 245, 179 + + + 121, 21 + + + 6 + + + CMB_fmode4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 21 + + + True + + + NoControl + + + 168, 155 + + + 71, 13 + + + 5 + + + Flight Mode 3 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 22 + + + 245, 152 + + + 121, 21 + + + 4 + + + CMB_fmode3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 23 + + + True + + + NoControl + + + 168, 128 + + + 71, 13 + + + 3 + + + Flight Mode 2 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 24 + + + 245, 125 + + + 121, 21 + + + 2 + + + CMB_fmode2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 25 + + + True + + + NoControl + + + 168, 101 + + + 71, 13 + + + 1 + + + Flight Mode 1 + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 26 + + + 245, 98 + + + 121, 21 + + + 0 + + + CMB_fmode1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 27 + + NoControl 245, 260 - - tabBattery + + 121, 23 - - + + 103 - - 5 + + Save Modes - - HS4_TRIM + + BUT_SaveModes - - 16, 50 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - pictureBox3 + + tabModes - - 2, 2, 2, 2 + + 28 - - 117 + + 4, 22 - - tabHardware + + 666, 393 - - Servo + + 3 - - 8 + + Modes - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + tabModes - - tabHeli + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + tabControl1 + + + 2 + + + True + + NoControl - - Simple Mode + + 390, 80 - + + 104, 13 + + + 28 + + + Declination WebSite + + + linkLabelmagdec + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 0 + + + NoControl + + + 310, 57 + + + 60, 13 + + + 23 + + + Declination + + + label100 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - Simple Mode - - - Reset APM Hardware to Default - tabHardware - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Simple Mode - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2, 2, 2, 2 - - - Simple Mode - - - 15, 14 - - - 122, 271 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - ArduCopter2 - - - NoControl - - - 71, 13 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 133 - - - Position - - - tabRadioIn - - - - - - - - - 4 - - - NoControl - - - 5 - - - BAR6 - - - 119 - - - 76, 13 - - - NoControl - - - 89, 13 - - - 5 - - - 33 - - - 0 - - - 0 - - - label32 - - - - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3, 3, 3, 3 - - - label23 - - - PWM 1621 - 1749 - - - True - - - 114 - - - - - - 58, 23 - - - 127, 206 - - - tabModes - - - lbl_currentmode - - - True - - - NoControl - - - BUT_HS4save - - - 0 - - - True - - - - - - tabControl1 - - - groupBox3 - - - BARroll - - - 76, 20 - - - label4 - - - label28 - - - 30 - - - tabHeli - - - 11, 89 - - - label8 - - + 1 - - + + 383, 57 - - CMB_fmode1 - - - NoControl - - - tabBattery - - - 39, 20 - - - COL_MIN_ - - - 162, 214 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - Reverse - - - tabRadioIn - - - 4 - - - - - - tabModes - - - 502, 244 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - - label38 - - - 122 - - - 89 + + 121, 20 20 - - 133 + + 214, 17 + + + Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 - - 13, 206 + + TXT_declination + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 2 + + + NoControl + + + 162, 214 + + + 103, 17 + + + 24 + + + Enable Airspeed + + + CHK_enableairspeed + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 3 + + + NoControl + + + 159, 136 + + + 90, 17 + + + 25 + + + Enable Sonar + + + CHK_enablesonar + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 4 + + + NoControl + + + 162, 56 + + + 105, 17 + + + 27 + + + Enable Compass + + + CHK_enablecompass + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 5 + + + Zoom + + + NoControl + + + 78, 188 + + + 75, 75 + + + 3 + + + pictureBox4 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 tabHardware - - 53, 271 + + 6 - + + Zoom + + NoControl - - NoControl + + 78, 106 - - tabModes + + 75, 75 - - Simple Mode + + 2 - - 4 + + pictureBox3 - - Roll Max + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 5 - - - 38, 23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label39 + + tabHardware 7 - + + Zoom + + + + NoControl + + + + + + 78, 25 + + + 75, 75 + + + 0 + + + pictureBox1 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 8 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 1 + + + Hardware + + + tabHardware + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 3 + + + 162, 267 + + + 2, 2, 2, 2 + + + 76, 20 + + + 38 + + + TXT_ampspervolt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 0 + + + 162, 245 + + + 2, 2, 2, 2 + + + 76, 20 + + + 37 + + + TXT_divider + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 1 + + + 162, 224 + + + 2, 2, 2, 2 + + + 76, 20 + + + 36 + + + TXT_voltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 2 + + + 162, 202 + + + 2, 2, 2, 2 + + + 76, 20 + + + 35 + + + TXT_measuredvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 3 + + + 162, 180 + + + 2, 2, 2, 2 + + + 76, 20 + + + 34 + + + TXT_inputvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 4 + + + True + + + NoControl + + + 29, 270 + + + 2, 0, 2, 0 + + + 89, 13 + + + 33 + + + Amperes per volt: + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 5 + + + True + + + NoControl + + + 28, 248 + + + 2, 0, 2, 0 + + + 80, 13 + + + 32 + + + Voltage divider: + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 6 + + + True + + + NoControl + + + 28, 227 + + + 2, 0, 2, 0 + + + 81, 13 + + + 31 + + + Battery voltage: + + + label33 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 7 + + + True + + + NoControl + + + 28, 205 + + + 2, 0, 2, 0 + + + 130, 13 + + + 30 + + + Measured battery voltage: + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 8 + + + True + + + NoControl + + + 28, 183 + + + 2, 0, 2, 0 + + + 72, 13 + + + 29 + + + Input voltage: + + + label31 + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + tabBattery - + + 9 + + + 31, 110 + + + 2, 2, 2, 2 + + True - - + + 428, 62 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - True - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 170, 25 - - - - - - Gservoloc - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 4500 - - - 7 - - - - - - APMSetup - - - 74, 13 - - - tabHeli + + 28 Voltage sensor calibration: @@ -2731,1417 +1971,1781 @@ will work with hexa's etc 2. Measure battery voltage and enter it to the box below 3. From current sensor datasheet, enter amperes per volt value to the box below - - 170, 25 + + textBox3 - - tabModes - - - 232, 23 - - - Reset - - - 3 - - - 446, 75 - - + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + tabBattery + + + 10 + + True - - 75, 75 + + NoControl - - HS4_MAX + + 305, 50 - - Save Modes + + 48, 13 - - 25 + + 23 - - + + Capacity - - 44, 20 + + label29 - - 6, 13 - - - - - - tabHardware - - - tabHeli - - - 26 - - - 29 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 322, 67 - - - 446, 240 - - + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - CHK_revch1 + + tabBattery - - 245, 233 + + 11 - - Declination - - - 66, 17 - - + NoControl - - Gyro + + 123, 50 - - tabArducopter + + 42, 13 - - Measured battery voltage: + + 24 - - 0, 0, 0, 0 + + Monitor - - tabRadioIn + + label30 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + tabBattery - - 134 + + 12 - - tabHeli + + 366, 47 - - 3: Battery Volts + + 83, 20 + + + 25 + + + TXT_battcapacity + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 13 + + + 0: Disabled + + + 1: 3 Cell 2: 4 Cell - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 3: Battery Volts - - 35, 13 + + 4: Volts & Current - - Max + + 177, 46 - - + + 121, 21 - - 110 + + 26 - + + CMB_batmontype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 14 + + + Zoom + + NoControl - + + 31, 21 + + + 75, 75 + + + 2 + + + pictureBox5 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 15 + + + 4, 22 + + + 2, 2, 2, 2 + + + 666, 393 + + + 6 + + + Battery + + + tabBattery + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 4 + + + True + + + NoControl + + + 217, 38 + + + 210, 13 + + + 9 + + + Level your quad to set default accel offsets + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 0 + + + True + + + NoControl + + + 217, 333 + + + 192, 26 + + + 7 + + + NOTE: images are for presentation only +will work with hexa's etc + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + 1 - + + True + + + NoControl + + + 260, 124 + + + 102, 13 + + + 6 + + + Frame Setup (+ or x) + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 2 + + + NoControl + + + 319, 140 + + + 190, 190 + + + Zoom + + + 5 + + + pictureBoxQuadX + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 3 + + + NoControl + + + 112, 140 + + + 190, 190 + + + Zoom + + + 4 + + + pictureBoxQuad + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 4 + + + NoControl + + + 274, 67 + + + 75, 23 + + + 8 + + + Level + + + BUT_levelac2 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabArducopter + + + 5 + + + 4, 22 + + + 666, 393 + + + 2 + + + ArduCopter2 + + + tabArducopter + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 5 + + True NoControl - - - - - Rev - - - Zoom - - - NoControl - - - True - - - 31, 110 - - - 15, 14 - - - NoControl - - - 121, 21 - - - 0 - - - 170, 25 - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - linkLabelmagdec - - - 136 - - - 506, 182 - - - - - - pictureBoxQuadX - - - True - - - tabBattery - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 214, 161 - - - - - - - - - 506, 236 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 119 - - - - - - 98, 206 - - - True - - - - - - 6, 19 - - - tabRadioIn - - - System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 666, 393 - - - 380, 100 - - - tabHeli - - - Fill - - - COL_MID_ - - - NoControl - - - HS4 - - - 108 - - - 4, 22 - - - 18 - - - Battery - - - Reverse - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 21, 6 - - - - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 122, 219 - - - NoControl - - - 27, 13 - - - 380, 181 - - - PIT_MAX_ - - - 451, 245 - - - Capacity - - - label15 - - - HS4_REV - - - 162, 202 - - - HS2_REV - - - True - - - 112, 140 - - - - - - HS3 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2, 2, 2, 2 - - - Reverse - - - 366, 47 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 107 - - - 245, 152 - - - - - - - - - TXT_voltage - - - 53, 219 - - - SV3_POS_ - - - NoControl - - - 4 - - - 8 - - - 44, 13 - - - NoControl - - - tabBattery - - - NoControl - - - 34 - - - 117 - - - NoControl - - - 60, 13 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - 6, 38 - - 48, 13 + + 29, 13 - - tabHeli + + 137 - - + + Gain - - 6 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - BUT_levelac2 - - - 2 - - - - - - Modes - - - Trim - - - tabHardware - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 666, 393 - - - label9 - - - - - - tabHardware - - - tabModes - - - 2, 2, 2, 2 - - - BARpitch - - - - - - TXT_inputvoltage - - - 4, 22 - - - 28 - - - 666, 393 - - - tabReset - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15 - - - 11 - - - 109 - - - True - - - - - - 109, 13 - - - label10 - - - 2 - - - True - - - tabControl1 - - - 1 - - - 310, 316 - - - 122, 245 - - - 9 - - - 11 - - - True - - - 80, 209 - - - 78, 188 - - - label1 - - - tabControl1 - - - NoControl - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 27 - - - - - - 66, 17 - - - True - - - label11 - - - 242, 50 - - - 130, 13 - - - 380, 235 - - - tabHeli - - - 4 - - - tabHeli - - - tabHeli - - - BAR5 - - - tabHeli - - - tabModes - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - BAR7 - - - 3 - - - 535, 241 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - BUT_swash_manual - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 1000 - - - 40, 13 - - - tabModes - - - 23, 222 - - - NoControl - - - 47, 20 - - - 217, 333 - - - tabReset - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 162, 224 - - - NoControl - - - 4, 22 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - CHK_revch2 + + label46 System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 3, 3, 3, 3 - - - 24 - - - 121 - - - 101, 63 - - - 2 - - - 94, 13 - - - 168, 182 - - - 43, 20 - - - label5 - - - 50, 206 - - - True - - - 3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 24 - - - 47, 20 - - - - - - 10 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - LBL_flightmodepwm - - - True - - - NoControl - - - - - - - - - CB_simple3 - - - 75, 23 - - - - - - 116 - - - tabHeli - - - TXT_ampspervolt - - - 34 - - - tabModes - - - 666, 393 - - - 72, 13 - - - - - - CB_simple6 - - - - - - 115 - - + groupBox3 - - 47, 211 - - - True - - - NoControl - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 245, 125 - - - 319, 140 - - - - - - 28, 248 - - - NoControl - - - 27, 13 - - - 35 - - - 315, 12 - - - - - - True - - - GYR_ENABLE_ - - - 81, 13 - - - True - - - 74, 13 - - - tabModes - - - 143, 61 - - - 80, 13 - - - NoControl - - - 433, 143 - - - - - - 21, 40 - - - 121, 21 - - - NoControl - - - TXT_declination - - - - - - tabControl1 - - - 71, 158 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 0 - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - CHK_revch3 - - - - - - - - - 2, 2, 2, 2 - - - 127 - - - 3 - - - tabHeli - - - 6 - - - 104 - - - 99 - - - 2, 0, 2, 0 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - tabControl1 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 310, 342 - - - 7 - - - 6 - - - tabHeli - - - label18 - - - 159, 136 - - - tabControl1 - - - AC2 Heli - - - 18 - - - - - - True - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 124 - - - - - - 1500 - - - - - - 121, 21 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - - - - - - - NoControl - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 310, 57 - - - tabArducopter - - - 17, 117 - - - NoControl - - - Manual - - - Setup - - - 4 - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - label25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 120 - - - tabModes - - - 2, 2, 2, 2 - - - 70, 13 - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 102, 13 - - - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 40, 13 - - - 666, 393 - - - 101, 274 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - 123 - - - tabModes - - - 433, 271 - - - - - - Frame Setup (+ or x) - - - 1 - - - 103 - - - - - - Input voltage: - - - False - - - 17 - - - - - - tabRadioIn - - - 90 - - - - - - label19 - True - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - - - - 29 - - - - - - 322, 50 - - - CMB_fmode5 - - - - - - 0 - - - 75, 75 - - - 162, 267 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - + NoControl - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 6, 19 - - 23 + + 40, 13 - - + + 136 - - 101 - - - - - - 3 - - - tabHeli - - - tabBattery - - - 39, 20 - - - True - - - groupBox1 - - - 31, 21 - - - 112, 23 - - - 24 - - - 532, 225 - - - 9 - - - groupBox2 - - - 392, 50 - - - 298, 47 - - - 13, 13 - - - 60 - - - - - - NoControl - - - - - - - - - - - - label20 - - - 1 - - - 95 - - - tabHardware - - - tabHeli - - - COL_MAX_ - - - PWM 1491 - 1620 - - - - - - - - - 260, 124 - - - groupBox1 - - - Declination WebSite + + Enable label45 - - 4 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - False + + groupBox3 - + 1 - - 4, 22 + + True - - + + NoControl + + + 57, 19 + + + 15, 14 + + + 118 + + + GYR_ENABLE_ + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 2 + + + 41, 35 47, 20 - - 13 + + 119 - + + 1000 + + + GYR_GAIN_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 433, 271 + + + 101, 63 + + + 135 + + + Gyro + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + 0 - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + True - - 23, 274 + + NoControl - + + 532, 225 + + 27, 13 + + 134 + + + Trim + + + label44 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 1 + + + True + + + NoControl + + + 499, 225 + + + 27, 13 + + + 133 + + + Rev + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 2 + + + True + + + 451, 245 + + + 42, 13 + + + 132 + + + Rudder + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 3 + + + NoControl + + + 479, 138 + + + 69, 23 + + + 131 + + + Manual + + + BUT_HS4save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 4 + + + True + + + NoControl + + + 112, 23 + + + 27, 13 + + + 135 + + + Max + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + 21, 40 + + + 43, 20 + + + 132 + + + 1500 + + + HS4_MIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + 106, 40 + + + 43, 20 + + + 133 + + + 1500 + + + HS4_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + True + + + NoControl + + + 27, 23 + + + 24, 13 + + + 134 + + + Min + + + label40 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 433, 143 + + + 169, 78 + + + 130 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 5 + + + 298, 47 + + + 69, 23 + + + 0 + + + Manual + + + BUT_swash_manual + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 6 + + + True + + + NoControl + + + 19, 157 + + + 40, 13 + + + 122 + + + Bottom + + + label41 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 0 + + + True + + + 24, 28 + + + 26, 13 + + + 120 + + + Top + label21 - - 380, 208 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + groupBox1 - - 16 + + 1 - - 53, 245 + + 18, 173 + + + 43, 20 + + + 119 + + + 1500 + + + COL_MIN_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + 17, 117 + + + 44, 20 + + + 117 + + + 1500 + + + COL_MID_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + 18, 45 + + + 43, 20 + + + 115 1500 - - 1: 3 Cell + + COL_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + NoControl + + + 11, 89 + + + 58, 23 + + + 110 + + + Zero + + + BUT_0collective + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + groupBox1 + + + 5 + + + 293, 52 + + + 80, 209 + + + 129 + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 7 + + + 535, 241 + + + 44, 20 + + + 128 + + + HS4_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 8 + + + 122, 271 + + + 44, 20 + + + 127 + + + HS3_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 9 + + + 122, 245 + + + 44, 20 + + + 126 + + + HS2_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 10 + + + 122, 219 + + + 44, 20 + + + 125 + + + HS1_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 11 + + + True + + + NoControl + + + 127, 206 + + + 27, 13 + + + 124 + + + Trim + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 12 + + + True + + + NoControl + + + 98, 206 + + + 27, 13 + + + 123 + + + Rev + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 13 + + + True + + + NoControl + + + 50, 206 + + + 44, 13 + + + 122 + + + Position + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 14 + + + True + + + NoControl + + + 13, 206 + + + 35, 13 + + + 121 + + + Servo + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 15 + + + True + + + NoControl + + + 256, 345 + + + 54, 13 + + + 117 + + + Pitch Max + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 16 + + + 310, 342 + + + 47, 20 + + + 116 + + + 4500 + + + PIT_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 17 + + + True + + + NoControl + + + 256, 321 + + + 48, 13 + + + 115 + + + Roll Max + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 18 + + + 310, 316 + + + 47, 20 + + + 114 + + + 4500 + + + ROL_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 19 + + + True + + + NoControl + + + 476, 23 + + + 75, 13 + + + 109 + + + Rudder Travel + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 20 + + + True + + + NoControl + + + 232, 23 + + + 72, 13 + + + 101 + + + Swash Travel + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 21 + + + True + + + NoControl + + + 502, 244 + + + 15, 14 + + + 98 + + + HS4_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 22 + + + True + + + NoControl + + + 23, 274 + + + 13, 13 + + + 97 + + + 3 + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 23 + + + True + + + NoControl + + + 23, 248 + + + 13, 13 + + + 96 + + + 2 + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 24 + + + True + + + NoControl + + + 23, 222 + + + 13, 13 + + + 95 + + + 1 + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 25 + + + 53, 271 + + + 39, 20 + + + 94 + + + 180 + + + SV3_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 26 + + + 53, 245 + + + 39, 20 + + + 93 + + + 60 + + + SV2_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 27 + + + 53, 219 + + + 39, 20 + + + 92 + + + -60 + + + SV1_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 28 + + + True + + + NoControl + + + 101, 274 + + + 15, 14 + + + 91 + + + HS3_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 29 + + + True + + + NoControl + + + 101, 248 + + + 15, 14 + + + 90 + + + HS2_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 30 + + + True + + + NoControl + + + 101, 225 + + + 15, 14 + + + 89 + + + HS1_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 31 + + + True + + + NoControl + + + 38, 23 + + + 109, 13 + + + 82 + + + Swash-Servo position + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 32 + + + 392, 50 + + + 242, 42 + + + 108 + + + HS4 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 33 + + + 235, 52 + + + 42, 213 + + + 107 + + + HS3 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabHeli - - 17 + + 34 - - 71, 13 + + Zoom - - + + Microsoft Sans Serif, 9pt + + + 16, 50 + + + 0, 0, 0, 0 + + + 150, 150 + + + 81 + + + Gservoloc + + + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + tabHeli + + + 35 + + + 4, 22 + + + 666, 393 + + + 5 + + + AC2 Heli + + + tabHeli + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 6 + + + Fill + + + 0, 0 + + + 674, 419 + + + 93 + + + tabControl1 + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 True - - 17, 17 - - - 214, 17 - + + 6, 13 + + + 674, 419 + + + APMSetup + + + currentStateBindingSource + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Setup + + + System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/app.config b/Tools/ArdupilotMegaPlanner/app.config index 6b78cb190d..3c8a8135de 100644 --- a/Tools/ArdupilotMegaPlanner/app.config +++ b/Tools/ArdupilotMegaPlanner/app.config @@ -3,6 +3,10 @@ - + + + + + diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application index 2ad8510544..038f175f96 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application +++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application @@ -3,15 +3,18 @@ + + + - + - d1SWduiRJYsMADkinyiFASzMBV8= + l2Rn8qTiwOzQt8/BkJyqqyHeXA0= diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config index 6b78cb190d..3c8a8135de 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config +++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config @@ -3,6 +3,10 @@ - + + + + + diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx index 51ec819c4a..4495da6c9f 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx @@ -127,7 +127,7 @@ - 326, 31 + 213, 31 82, 17 @@ -148,7 +148,7 @@ panelWaypoints - 3 + 4 True @@ -157,7 +157,7 @@ NoControl - 411, 24 + 298, 24 98, 17 @@ -178,7 +178,7 @@ panelWaypoints - 8 + 9 Top, Bottom, Left, Right @@ -340,7 +340,7 @@ panelWaypoints - 10 + 11 True @@ -349,7 +349,7 @@ NoControl - 411, 40 + 298, 40 86, 17 @@ -370,10 +370,10 @@ panelWaypoints - 12 + 13 - 73, 32 + 23, 36 36, 20 @@ -394,10 +394,10 @@ panelWaypoints - 13 + 14 - 280, 32 + 154, 36 40, 20 @@ -418,7 +418,7 @@ panelWaypoints - 11 + 12 True @@ -427,7 +427,7 @@ NoControl - 9, 32 + 9, 24 61, 13 @@ -448,7 +448,7 @@ panelWaypoints - 4 + 5 True @@ -457,7 +457,7 @@ NoControl - 221, 32 + 151, 24 56, 13 @@ -478,10 +478,10 @@ panelWaypoints - 9 + 10 - 184, 32 + 89, 36 36, 20 @@ -502,7 +502,7 @@ panelWaypoints - 7 + 8 True @@ -511,7 +511,7 @@ NoControl - 112, 32 + 76, 24 69, 13 @@ -532,7 +532,7 @@ panelWaypoints - 6 + 7 Bottom, Right @@ -556,7 +556,7 @@ BUT_write - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -583,7 +583,7 @@ BUT_read - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -610,7 +610,7 @@ SaveFile - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -637,7 +637,7 @@ BUT_loadwpfile - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -1239,11 +1239,41 @@ 0 + + NoControl + + + 746, 26 + + + 62, 23 + + + 53 + + + Zoom To + + + Get Camera settings for overlap + + + BUT_zoomto + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + panelWaypoints + + + 0 + NoControl - 809, 26 + 692, 26 48, 23 @@ -1261,19 +1291,19 @@ BUT_Camera - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 0 + 1 NoControl - 755, 26 + 638, 26 48, 23 @@ -1291,19 +1321,19 @@ BUT_grid - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 1 + 2 NoControl - 693, 26 + 576, 26 56, 23 @@ -1321,19 +1351,19 @@ BUT_Prefetch - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 2 + 3 NoControl - 596, 26 + 479, 26 91, 23 @@ -1351,19 +1381,19 @@ button1 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 5 + 6 NoControl - 515, 26 + 398, 26 75, 23 @@ -1381,13 +1411,13 @@ BUT_Add - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints - 14 + 15 Bottom @@ -1823,7 +1853,7 @@ trackBar1 - ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelMap @@ -2105,6 +2135,6 @@ FlightPlanner - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml b/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml index 186d8d32da..6bb291dd77 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml +++ b/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml @@ -1,133 +1,133 @@ - - - Time - Sats - Lat - Long - Mix Alt - GPSAlt - GR Speed - CRS - - - Roll - Pitch - Yaw - rc1 servo - rc2 servo - rc3 servo - - - WP Dist - Target Bear - Long Err - Lat Err - nav lon - nav lat - nav lon I - nav lat I - Loiter Lon I - Loiter Lat I - - - Yaw Sensor - Nav Yaw - Yaw Error - Sonar Alt - Baro Alt - Next WP Alt - Nav Throttle - Angle boost - Manual boost - rc3 servo out - alt hold int - thro int - - - control mode - yaw mode - r p mode - thro mode - thro cruise - thro int - - - Gyro X - Gyro Y - Gyro Z - Accel X - Accel Y - Accel Z - - - Throttle in - Throttle intergrator - Voltage - Current - Current total - - - - - - Time - Fix - Sats - Lat - Long - Mix Alt - GPSAlt - GR Speed - CRS - - - Roll - Pitch - Yaw - - - Yaw - WP dist - Target Bear - Nav Bear - Alt Err - AS - NavGScaler - - - - - Servo Roll - nav_roll - roll_sensor - Servo Pitch - nav_pitch - pitch_sensor - Servo Throttle - Servo Rudder - AN 4 - - - loop time - Main count - G_Dt_max - Gyro Sat - adc constr - renorm_sqrt - renorm_blowup - gps_fix count - imu_health - - - Gyro X - Gyro Y - Gyro Z - Accel X - Accel Y - Accel Z - - - + + + Time + Sats + Lat + Long + Mix Alt + GPSAlt + GR Speed + CRS + + + Roll + Pitch + Yaw + rc1 servo + rc2 servo + rc3 servo + + + WP Dist + Target Bear + Long Err + Lat Err + nav lon + nav lat + nav lon I + nav lat I + Loiter Lon I + Loiter Lat I + + + Yaw Sensor + Nav Yaw + Yaw Error + Sonar Alt + Baro Alt + Next WP Alt + Nav Throttle + Angle boost + Manual boost + rc3 servo out + alt hold int + thro int + + + control mode + yaw mode + r p mode + thro mode + thro cruise + thro int + + + Gyro X + Gyro Y + Gyro Z + Accel X + Accel Y + Accel Z + + + Throttle in + Throttle intergrator + Voltage + Current + Current total + + + + + + Time + Fix + Sats + Lat + Long + Mix Alt + GPSAlt + GR Speed + CRS + + + Roll + Pitch + Yaw + + + Yaw + WP dist + Target Bear + Nav Bear + Alt Err + AS + NavGScaler + + + + + Servo Roll + nav_roll + roll_sensor + Servo Pitch + nav_pitch + pitch_sensor + Servo Throttle + Servo Rudder + AN 4 + + + loop time + Main count + G_Dt_max + Gyro Sat + adc constr + renorm_sqrt + renorm_blowup + gps_fix count + imu_health + + + Gyro X + Gyro Y + Gyro Z + Accel X + Accel Y + Accel Z + + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/mavcmd.xml b/Tools/ArdupilotMegaPlanner/bin/Release/mavcmd.xml index c7a8739df7..001638d71e 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/mavcmd.xml +++ b/Tools/ArdupilotMegaPlanner/bin/Release/mavcmd.xml @@ -1,62 +1,478 @@ - -DelayHit RadYaw AngLatLongAlt -LatLongAlt -TurnsLatLongAlt -Time sradyaw per -Alt - -Alt -MAV_ROIWP#ROI# - -Time (sec) -Rate (cm/sec)Alt -Dist (m) -DegSecDir 1=CWrel/abs - -WP #Repeat# -Type (0=as 1=gs)Throttle(%)Speed (m/s) -Current(1)/Spec(0) -#Value -off(0)/on(1)Delay (s) -Delay (s)Repeat# -Ser NoPWM -Ser NoRepeat#Delay (s)PWM - - - - - - - - -LatLongAlt -LatLongAlt -TurnsLatLongAlt -Time sLatLongAlt -LatLongAlt -LatLongAlt -AngleAlt - - -Time (sec) -Rate (cm/sec)Alt -Dist (m) - - -WP #Repeat# -Type (0=as 1=gs)Throttle(%)Speed (m/s) -Current(1)/Spec(0) -#Value -off(0)/on(1)Delay (s) -Delay (s)Repeat# -Ser NoPWM -Ser NoRepeat#Delay (s)PWM - - - - - + + + Delay + Hit Rad + + Yaw Ang + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + Turns + + + + Lat + Long + Alt + + + Time s + + rad + yaw per + + + + + + + + + + + + Alt + + + + + + + + + + + + + + + + + + Alt + + + MAV_ROI + WP# + ROI# + + + + + + + + + + + + + + + + Time (sec) + + + + + + + + + Rate (cm/sec) + + + + + + Alt + + + Dist (m) + + + + + + + + + Deg + Sec + Dir 1=CW + rel/abs + + + + + + + + + + + + + + + WP # + Repeat# + + + + + + + + Type (0=as 1=gs) + Throttle(%) + Speed (m/s) + + + + + + + Current(1)/Spec(0) + + + + + + + + + # + Value + + + + + + + + off(0)/on(1) + Delay (s) + + + + + + + + + Repeat# + Delay (s) + + + + + + + Ser No + PWM + + + + + + + + Ser No + Repeat# + Delay (s) + PWM + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + Turns + + + + Lat + Long + Alt + + + Time s + + + + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + Angle + + + + + + Alt + + + + + + + + + + + + + + + + + + + + + Time (sec) + + + + + + + + + Rate (cm/sec) + + + + + + Alt + + + Dist (m) + + + + + + + + + + + + + + + + + + + + + + + + + + + WP # + Repeat# + + + + + + + + Type (0=as 1=gs) + Throttle(%) + Speed (m/s) + + + + + + + Current(1)/Spec(0) + + + + + + + + + # + Value + + + + + + + + off(0)/on(1) + Delay (s) + + + + + + + + + Repeat# + Delay (s) + + + + + + + Ser No + PWM + + + + + + + + Ser No + Repeat# + Delay (s) + PWM + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Tools/ArdupilotMegaPlanner/dataflashlog.xml b/Tools/ArdupilotMegaPlanner/dataflashlog.xml index 186d8d32da..6bb291dd77 100644 --- a/Tools/ArdupilotMegaPlanner/dataflashlog.xml +++ b/Tools/ArdupilotMegaPlanner/dataflashlog.xml @@ -1,133 +1,133 @@ - - - Time - Sats - Lat - Long - Mix Alt - GPSAlt - GR Speed - CRS - - - Roll - Pitch - Yaw - rc1 servo - rc2 servo - rc3 servo - - - WP Dist - Target Bear - Long Err - Lat Err - nav lon - nav lat - nav lon I - nav lat I - Loiter Lon I - Loiter Lat I - - - Yaw Sensor - Nav Yaw - Yaw Error - Sonar Alt - Baro Alt - Next WP Alt - Nav Throttle - Angle boost - Manual boost - rc3 servo out - alt hold int - thro int - - - control mode - yaw mode - r p mode - thro mode - thro cruise - thro int - - - Gyro X - Gyro Y - Gyro Z - Accel X - Accel Y - Accel Z - - - Throttle in - Throttle intergrator - Voltage - Current - Current total - - - - - - Time - Fix - Sats - Lat - Long - Mix Alt - GPSAlt - GR Speed - CRS - - - Roll - Pitch - Yaw - - - Yaw - WP dist - Target Bear - Nav Bear - Alt Err - AS - NavGScaler - - - - - Servo Roll - nav_roll - roll_sensor - Servo Pitch - nav_pitch - pitch_sensor - Servo Throttle - Servo Rudder - AN 4 - - - loop time - Main count - G_Dt_max - Gyro Sat - adc constr - renorm_sqrt - renorm_blowup - gps_fix count - imu_health - - - Gyro X - Gyro Y - Gyro Z - Accel X - Accel Y - Accel Z - - - + + + Time + Sats + Lat + Long + Mix Alt + GPSAlt + GR Speed + CRS + + + Roll + Pitch + Yaw + rc1 servo + rc2 servo + rc3 servo + + + WP Dist + Target Bear + Long Err + Lat Err + nav lon + nav lat + nav lon I + nav lat I + Loiter Lon I + Loiter Lat I + + + Yaw Sensor + Nav Yaw + Yaw Error + Sonar Alt + Baro Alt + Next WP Alt + Nav Throttle + Angle boost + Manual boost + rc3 servo out + alt hold int + thro int + + + control mode + yaw mode + r p mode + thro mode + thro cruise + thro int + + + Gyro X + Gyro Y + Gyro Z + Accel X + Accel Y + Accel Z + + + Throttle in + Throttle intergrator + Voltage + Current + Current total + + + + + + Time + Fix + Sats + Lat + Long + Mix Alt + GPSAlt + GR Speed + CRS + + + Roll + Pitch + Yaw + + + Yaw + WP dist + Target Bear + Nav Bear + Alt Err + AS + NavGScaler + + + + + Servo Roll + nav_roll + roll_sensor + Servo Pitch + nav_pitch + pitch_sensor + Servo Throttle + Servo Rudder + AN 4 + + + loop time + Main count + G_Dt_max + Gyro Sat + adc constr + renorm_sqrt + renorm_blowup + gps_fix count + imu_health + + + Gyro X + Gyro Y + Gyro Z + Accel X + Accel Y + Accel Z + + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/hires.cs b/Tools/ArdupilotMegaPlanner/hires.cs new file mode 100644 index 0000000000..b647a9c856 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/hires.cs @@ -0,0 +1,48 @@ +using System; +using System.Runtime.InteropServices; + +namespace hires +{ + public class Stopwatch + { + [DllImport("Kernel32.dll")] + private static extern bool QueryPerformanceCounter( + out long lpPerformanceCount); + + [DllImport("Kernel32.dll")] + private static extern bool QueryPerformanceFrequency( + out long lpFrequency); + + private long start=0; + private long stop=0; + + // static - so this value used in all instances of + private static double frequency = getFrequency(); + + // Note this is static- called once, before any constructor! + private static double getFrequency() + { + long tempfrequency; + QueryPerformanceFrequency(out tempfrequency); + return tempfrequency; // implicit casting to double from long + } + + public void Start() + { + QueryPerformanceCounter(out start); + } + + public void Stop() + { + QueryPerformanceCounter(out stop); + } + + public double Elapsed + { + get + { + return (double)(stop - start) / frequency; + } + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/mavcmd.xml b/Tools/ArdupilotMegaPlanner/mavcmd.xml index c7a8739df7..001638d71e 100644 --- a/Tools/ArdupilotMegaPlanner/mavcmd.xml +++ b/Tools/ArdupilotMegaPlanner/mavcmd.xml @@ -1,62 +1,478 @@ - -DelayHit RadYaw AngLatLongAlt -LatLongAlt -TurnsLatLongAlt -Time sradyaw per -Alt - -Alt -MAV_ROIWP#ROI# - -Time (sec) -Rate (cm/sec)Alt -Dist (m) -DegSecDir 1=CWrel/abs - -WP #Repeat# -Type (0=as 1=gs)Throttle(%)Speed (m/s) -Current(1)/Spec(0) -#Value -off(0)/on(1)Delay (s) -Delay (s)Repeat# -Ser NoPWM -Ser NoRepeat#Delay (s)PWM - - - - - - - - -LatLongAlt -LatLongAlt -TurnsLatLongAlt -Time sLatLongAlt -LatLongAlt -LatLongAlt -AngleAlt - - -Time (sec) -Rate (cm/sec)Alt -Dist (m) - - -WP #Repeat# -Type (0=as 1=gs)Throttle(%)Speed (m/s) -Current(1)/Spec(0) -#Value -off(0)/on(1)Delay (s) -Delay (s)Repeat# -Ser NoPWM -Ser NoRepeat#Delay (s)PWM - - - - - + + + Delay + Hit Rad + + Yaw Ang + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + Turns + + + + Lat + Long + Alt + + + Time s + + rad + yaw per + + + + + + + + + + + + Alt + + + + + + + + + + + + + + + + + + Alt + + + MAV_ROI + WP# + ROI# + + + + + + + + + + + + + + + + Time (sec) + + + + + + + + + Rate (cm/sec) + + + + + + Alt + + + Dist (m) + + + + + + + + + Deg + Sec + Dir 1=CW + rel/abs + + + + + + + + + + + + + + + WP # + Repeat# + + + + + + + + Type (0=as 1=gs) + Throttle(%) + Speed (m/s) + + + + + + + Current(1)/Spec(0) + + + + + + + + + # + Value + + + + + + + + off(0)/on(1) + Delay (s) + + + + + + + + + Repeat# + Delay (s) + + + + + + + Ser No + PWM + + + + + + + + Ser No + Repeat# + Delay (s) + PWM + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + Turns + + + + Lat + Long + Alt + + + Time s + + + + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + + + + + Lat + Long + Alt + + + Angle + + + + + + Alt + + + + + + + + + + + + + + + + + + + + + Time (sec) + + + + + + + + + Rate (cm/sec) + + + + + + Alt + + + Dist (m) + + + + + + + + + + + + + + + + + + + + + + + + + + + WP # + Repeat# + + + + + + + + Type (0=as 1=gs) + Throttle(%) + Speed (m/s) + + + + + + + Current(1)/Spec(0) + + + + + + + + + # + Value + + + + + + + + off(0)/on(1) + Delay (s) + + + + + + + + + Repeat# + Delay (s) + + + + + + + Ser No + PWM + + + + + + + + Ser No + Repeat# + Delay (s) + PWM + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Tools/ArdupilotMegaPlanner/mykey.snk b/Tools/ArdupilotMegaPlanner/mykey.snk new file mode 100644 index 0000000000000000000000000000000000000000..fa40666d7db33edf33ad4d504a1ffd30072b9f2d GIT binary patch literal 596 zcmV-a0;~N80ssI2Bme+XQ$aES1ONa50096;-6C?UA$(p%Ylzj%;mJlnVeUoty~|q! zv8hHU@m@l1i!(tG2Lr0)$*{PGKr|K?w<(_a?8d|chezo_hgABYsSNe&0rWH@Vigke z4vA3xC`Ivf3Z$g!ETX}Tx`vie$s<0v05~M8&>7G}xQ~~u*lu;7J-k%)E9QSpmTrj; z*EM+^SCGgMRuQ7>y+aXktQ2qJ$fx?rr^2h%@yA8i?)gUS9jBiv_U+%+LGyl=heu?% z^ab-TJbu#?8KJ&O*4~ft-V*r~cneE+4O!0Y`2Lbf42S8gsA|OaU z8pQb3^Y+-2JBZh}h$_D8S6{JyEZSvOd$E8!t#qX#^md?K6_iJ~9!k3e-XCs`jJ>;E z{zAlruLt+WY$i!ab!Lp<5+^^AIZ}ffa_jTM2109(LwhLPypI+u+Cr#hoDyb(vSzXe zKlDIV#5`_M`N6(G;83Yo-bJpk6KiVOUjMLPjH?c|k(mb=#X!Txe=%v_PSgg zb6Fa!B!XQEJQZb69arwTDD{kDqA!cxW^-`h>*;GR<8O%{y&vq6O*!ta6Da(RPQAhe i8X=w65)jFP!i^EE)y(0Gw3q}x{Rxy7Yl1H2hdy6{3?0q@ literal 0 HcmV?d00001 From 85a5647f5dfeb778daa0e57b1d46d1dc4db13c5b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 21 Nov 2011 22:03:40 -0800 Subject: [PATCH 59/63] cleanup --- ArduCopter/APM_Config.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index a6b1801542..625f035186 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -41,9 +41,6 @@ #define ACCEL_ALT_HOLD 0 // disabled by default, work in progress -// See the config.h and defines.h files for how to set this up! -// - // lets use Manual throttle during Loiter //#define LOITER_THR THROTTLE_MANUAL # define RTL_YAW YAW_HOLD From 89e014c06aa641a4aed47e13f29680edadf60ccf Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 21 Nov 2011 22:12:19 -0800 Subject: [PATCH 60/63] Added alternate alt hold, New ESC Calibration Routine --- ArduCopter/ArduCopter.pde | 6 ++++-- ArduCopter/config.h | 2 +- ArduCopter/radio.pde | 38 ++++++++++++++++++++++++++++++-------- ArduCopter/setup.pde | 26 -------------------------- ArduCopter/system.pde | 1 - 5 files changed, 35 insertions(+), 38 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 0d466b480d..cb3e16f342 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1260,8 +1260,10 @@ static void update_altitude() baro_alt = (baro_alt + read_barometer()) >> 1; // calc the vertical accel rate - #if CLIMB_RATE_BARO == 1 - int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale + #if CLIMB_RATE_BARO == 0 + int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 2; // invert and scale + temp_baro_alt = (float)temp_baro_alt * .1 + (float)old_baro_alt * .9; + baro_rate = (temp_baro_alt - old_baro_alt) * 10; old_baro_alt = temp_baro_alt; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 17a2f879fb..2d6675ccdd 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -519,7 +519,7 @@ // RATE control #ifndef THROTTLE_P -# define THROTTLE_P 0.6 // +# define THROTTLE_P 0.5 // #endif #ifndef THROTTLE_I # define THROTTLE_I 0.0 // diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 937193d8c5..5e8fc92f70 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -69,22 +69,44 @@ static void init_rc_out() APM_RC.OutputCh(CH_5, 1500); APM_RC.OutputCh(CH_6, 1500); - // don't fuss if we are calibrating - if(g.esc_calibrate == 1) - return; - - output_min(); - for(byte i = 0; i < 5; i++){ delay(20); read_radio(); } - // sanity check + // sanity check - prevent unconfigured radios from outputting if(g.rc_3.radio_min >= 1300){ g.rc_3.radio_min = g.rc_3.radio_in; - output_min(); } + + // we are full throttle + if(g.rc_3.control_in == 800){ + if(g.esc_calibrate == 0){ + // we will enter esc_calibrate mode on next reboot + g.esc_calibrate.set_and_save(1); + // send miinimum throttle out to ESC + output_min(); + // block until we restart + while(1){ + //Serial.println("esc"); + delay(200); + dancing_light(); + } + }else{ + //Serial.println("esc init"); + // clear esc flag + g.esc_calibrate.set_and_save(0); + // block until we restart + init_esc(); + } + }else{ + // did we abort the calibration? + if(g.esc_calibrate == 1) + g.esc_calibrate.set_and_save(0); + + // send miinimum throttle out to ESC + output_min(); + } } void output_min() diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index fa2166e2db..9a18eab16b 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -16,7 +16,6 @@ static int8_t setup_compass (uint8_t argc, const Menu::arg *argv); static int8_t setup_tune (uint8_t argc, const Menu::arg *argv); //static int8_t setup_mag_offset (uint8_t argc, const Menu::arg *argv); static int8_t setup_declination (uint8_t argc, const Menu::arg *argv); -static int8_t setup_esc (uint8_t argc, const Menu::arg *argv); #ifdef OPTFLOW_ENABLED static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv); #endif @@ -36,7 +35,6 @@ const struct Menu::command setup_menu_commands[] PROGMEM = { {"radio", setup_radio}, {"frame", setup_frame}, {"motors", setup_motors}, - {"esc", setup_esc}, {"level", setup_accel}, {"modes", setup_flightmodes}, {"battery", setup_batt_monitor}, @@ -230,29 +228,6 @@ setup_radio(uint8_t argc, const Menu::arg *argv) return(0); } -static int8_t -setup_esc(uint8_t argc, const Menu::arg *argv) -{ - /*Serial.printf_P(PSTR("\nESC Calibration:\n" - "-1 Unplug USB and battery\n" - "-2 Move CLI/FLY switch to FLY mode\n" - "-3 Move throttle to max, connect battery\n" - "-4 After two long beeps, throttle to 0, then test\n\n" - " Press Enter to cancel.\n")); - */ - Serial.printf_P(PSTR("See wiki:\n")); - g.esc_calibrate.set_and_save(1); - - while(1){ - delay(20); - - if(Serial.available() > 0){ - g.esc_calibrate.set_and_save(0); - return(0); - } - } -} - static int8_t setup_motors(uint8_t argc, const Menu::arg *argv) { @@ -1122,7 +1097,6 @@ static void print_enabled(boolean b) static void init_esc() { - g.esc_calibrate.set_and_save(0); while(1){ read_radio(); delay(100); diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 73c97ffa00..116bebe3e8 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -243,7 +243,6 @@ static void init_ardupilot() if(g.log_bitmask != 0){ // TODO - Here we will check on the length of the last log // We don't want to create a bunch of little logs due to powering on and off - Serial.printf("start_new_log"); start_new_log(); } #endif From c5c5884006f15658e70d0cb8afa71855d0a8b8b2 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 21 Nov 2011 22:13:18 -0800 Subject: [PATCH 61/63] v number --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index cb3e16f342..620161588d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduCopter V2.0.50 Beta" +#define THISFIRMWARE "ArduCopter V2.0.51" /* ArduCopter Version 2.0 Beta Authors: Jason Short From 244eeea34afb8fd750c9e3ac690a96c9bac6af5c Mon Sep 17 00:00:00 2001 From: Doug Weibel Date: Tue, 22 Nov 2011 20:17:28 -0700 Subject: [PATCH 62/63] Rework logging file system to be more robust --- ArduPlane/Log.pde | 230 ++++++++++++++++++++++------------------------ 1 file changed, 110 insertions(+), 120 deletions(-) diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index af858b6dfd..0e2eef8c2f 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -52,9 +52,9 @@ print_log_menu(void) { int log_start; int log_end; - int temp; + int temp; + uint16_t num_logs = get_num_logs(); -//Serial.print("num logs: "); Serial.println(num_logs, DEC); Serial.printf_P(PSTR("logs enabled: ")); @@ -82,7 +82,7 @@ print_log_menu(void) Serial.println(); if (num_logs == 0) { - Serial.printf_P(PSTR("\nNo logs\nType 'dump 0'.\n\n")); + Serial.printf_P(PSTR("\nNo logs\n\n")); }else{ Serial.printf_P(PSTR("\n%d logs\n"), num_logs); @@ -109,17 +109,18 @@ dump_log(uint8_t argc, const Menu::arg *argv) last_log_num = g.log_last_filenumber; if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) { Serial.printf_P(PSTR("bad log number\n")); + Log_Read(0, 4095); return(-1); } get_log_boundaries(dump_log, dump_log_start, dump_log_end); - Serial.printf_P(PSTR("Dumping Log number %d, start page %d, end page %d\n"), + Serial.printf_P(PSTR("Dumping Log %d, start pg %d, end pg %d\n"), dump_log, dump_log_start, dump_log_end); Log_Read(dump_log_start, dump_log_end); - Serial.printf_P(PSTR("Log read complete\n")); + Serial.printf_P(PSTR("Done\n")); return 0; } @@ -204,6 +205,7 @@ static byte get_num_logs(void) if(g.log_last_filenumber < 1) return 0; DataFlash.StartRead(1); + if(DataFlash.GetFileNumber() == 0XFFFF) return 0; lastpage = find_last(); @@ -211,7 +213,7 @@ static byte get_num_logs(void) last = DataFlash.GetFileNumber(); DataFlash.StartRead(lastpage + 2); first = DataFlash.GetFileNumber(); - if(first == 0xFFFF) { + if(first > last) { DataFlash.StartRead(1); first = DataFlash.GetFileNumber(); } @@ -285,130 +287,118 @@ static int find_last(void) // This function finds the last page of a particular log file static int find_last_log_page(uint16_t log_number) { - int16_t bottom_page; - int16_t top_page; - int16_t bottom_page_file; - int16_t bottom_page_filepage; - int16_t top_page_file; - int16_t top_page_filepage; - int16_t look_page; - int16_t look_page_file; - int16_t look_page_filepage; - int16_t check; - bool XLflag = false; - // First see if the logs are empty - DataFlash.StartRead(1); - if(DataFlash.GetFileNumber() == 0XFFFF) { + uint16_t bottom_page; + uint16_t bottom_page_file; + uint16_t bottom_page_filepage; + uint16_t top_page; + uint16_t top_page_file; + uint16_t top_page_filepage; + uint16_t look_page; + uint16_t look_page_file; + uint16_t look_page_filepage; + + bottom_page = 1; + DataFlash.StartRead(bottom_page); + bottom_page_file = DataFlash.GetFileNumber(); + bottom_page_filepage = DataFlash.GetFilePage(); + + // First see if the logs are empty. If so we will exit right away. + if(bottom_page_file == 0XFFFF) { return 0; } + + top_page = DF_LAST_PAGE; + DataFlash.StartRead(top_page); + top_page_file = DataFlash.GetFileNumber(); + top_page_filepage = DataFlash.GetFilePage(); - // Next, see if logs wrap the top of the dataflash - DataFlash.StartRead(DF_LAST_PAGE); - if(DataFlash.GetFileNumber() == 0xFFFF) - { - // This case is that we have not wrapped the top of the dataflash - top_page = DF_LAST_PAGE; - bottom_page = 1; - while((top_page - bottom_page) > 1) { - look_page = (top_page + bottom_page) / 2; - DataFlash.StartRead(look_page); - if(DataFlash.GetFileNumber() > log_number) - top_page = look_page; - else + + while((top_page - bottom_page) > 1) { + look_page = ((long)top_page + (long)bottom_page) / 2L; + + DataFlash.StartRead(look_page); + look_page_file = DataFlash.GetFileNumber(); + look_page_filepage = DataFlash.GetFilePage(); + + // We have a lot of different logic cases dependant on if the log space is overwritten + // and where log breaks might occur relative to binary search points. + // Someone could make work up a logic table and simplify this perhaps, or perhaps + // it is easier to interpret as is. + + if (look_page_file == 0xFFFF) { + top_page = look_page; + top_page_file = look_page_file; + top_page_filepage = look_page_filepage; + + } else if (look_page_file == log_number && bottom_page_file == log_number && top_page_file == log_number) { + // This case is typical if a single file fills the log and partially overwrites itself + if (bottom_page_filepage < top_page_filepage) { bottom_page = look_page; - } - return bottom_page; - - } else { - // The else case is that the logs do wrap the top of the dataflash - bottom_page = 1; - top_page = DF_LAST_PAGE; - DataFlash.StartRead(bottom_page); - bottom_page_file = DataFlash.GetFileNumber(); - bottom_page_filepage = DataFlash.GetFilePage(); - DataFlash.StartRead(top_page); - top_page_file = DataFlash.GetFileNumber(); - top_page_filepage = DataFlash.GetFilePage(); - - // Check is we have exactly filled the dataflash but not wrapped. If so we can exit quickly. - if(top_page_file == log_number && bottom_page_file != log_number) { - return top_page_file; - } - - // Check if the top is 1 file higher than we want. If so we can exit quickly. - if(top_page_file == log_number+1) { - return top_page - top_page_filepage; - } - - // Check if the file has partially overwritten itself - if(top_page_filepage >= DF_LAST_PAGE) { - XLflag = true; - } else { - top_page = top_page - top_page_filepage; - DataFlash.StartRead(top_page); - top_page_file = DataFlash.GetFileNumber(); - } - if(top_page_file == log_number) { - bottom_page = top_page; - top_page = DF_LAST_PAGE; - DataFlash.StartRead(top_page); - top_page_filepage = DataFlash.GetFilePage(); - if(XLflag) bottom_page = 1; - - while((top_page - bottom_page) > 1) { - look_page = (top_page + bottom_page) / 2; - DataFlash.StartRead(look_page); - if(DataFlash.GetFilePage() < top_page_filepage) - { - top_page = look_page; - top_page_filepage = DataFlash.GetFilePage(); - } else { - bottom_page = look_page; - } + bottom_page_file = look_page_file; + bottom_page_filepage = look_page_filepage; + } else { + top_page = look_page; + top_page_file = look_page_file; + top_page_filepage = look_page_filepage; } - return bottom_page; - } - - - // Step down through the files to find the one we want - bottom_page = top_page; - bottom_page_filepage = top_page_filepage; - do - { - int16_t last_bottom_page_file; - top_page = bottom_page; - bottom_page = bottom_page - bottom_page_filepage; - if(bottom_page < 1) bottom_page = 1; - DataFlash.StartRead(bottom_page); - last_bottom_page_file = bottom_page_file; - bottom_page_file = DataFlash.GetFileNumber(); - bottom_page_filepage = DataFlash.GetFilePage(); - if (bottom_page_file == last_bottom_page_file && - bottom_page_filepage == 0) { - /* no progress can be made - give up. The log may be corrupt */ - return -1; - } - } while (bottom_page_file != log_number && bottom_page != 1); - - // Deal with stepping down too far due to overwriting a file - while((top_page - bottom_page) > 1) { - look_page = (top_page + bottom_page) / 2; - DataFlash.StartRead(look_page); - if(DataFlash.GetFileNumber() < log_number) - top_page = look_page; - else + + } else if (look_page_file == log_number && look_page_file ==bottom_page_file) { + if (bottom_page_filepage < look_page_filepage) { bottom_page = look_page; + bottom_page_file = look_page_file; + bottom_page_filepage = look_page_filepage; + } else { + top_page = look_page; + top_page_file = look_page_file; + top_page_filepage = look_page_filepage; + } + + } else if (look_page_file == log_number) { + bottom_page = look_page; + bottom_page_file = look_page_file; + bottom_page_filepage = look_page_filepage; + + } else if(look_page_file < log_number && bottom_page_file > look_page_file && bottom_page_file <= log_number) { + top_page = look_page; + top_page_file = look_page_file; + top_page_filepage = look_page_filepage; + } else if(look_page_file < log_number) { + bottom_page = look_page; + bottom_page_file = look_page_file; + bottom_page_filepage = look_page_filepage; + + } else if(look_page_file > log_number && top_page_file < look_page_file && top_page_file >= log_number) { + bottom_page = look_page; + bottom_page_file = look_page_file; + bottom_page_filepage = look_page_filepage; + } else { + top_page = look_page; + top_page_file = look_page_file; + top_page_filepage = look_page_filepage; } - - // The -1 return is for the case where a very short power up increments the log - // number counter but no log file is actually created. This happens if power is - // removed before the first page is written to flash. - if(bottom_page ==1 && DataFlash.GetFileNumber() != log_number) return -1; - - return bottom_page; + + // End while } + + if (bottom_page_file == log_number && top_page_file == log_number) { + if( bottom_page_filepage < top_page_filepage) + return top_page; + else + return bottom_page; + } else if (bottom_page_file == log_number) { + return bottom_page; + } else if (top_page_file == log_number) { + return top_page; + } else { + return -1; + } + } + + + + // Write an attitude packet. Total length : 10 bytes From 091f031d58e570fa9e3078f2935fcdecc18a5c03 Mon Sep 17 00:00:00 2001 From: Olivier ADLER Date: Wed, 23 Nov 2011 23:36:23 +0100 Subject: [PATCH 63/63] * ArduPPM 0.9.87 update : #define to allow Radio Passthrough mode was not working. Corrected. Removed older hex file --- Tools/ArduPPM/ATMega328p/Encoder-PPM.c | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c index 1d8159e57e..630052061f 100644 --- a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c +++ b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c @@ -1,5 +1,5 @@ // ------------------------------------------------------------------------------------------------------------------------------------------------------------ -// ArduPPM Version v0.9.86 +// ArduPPM Version v0.9.87 // ------------------------------------------------------------------------------------------------------------------------------------------------------------ // ARDUCOPTER 2 : PPM ENCODER for AT Mega 328p and APM v1.4 Boards // By:John Arne Birkeland - 2011 @@ -34,6 +34,7 @@ // 0.9.84 : Corrected pin and port names in Encoder-PPM.c according to #define for Mega32U2 compatibility // 0.9.85 : Added brownout reset detection flag // 0.9.86 : Added a #define to disable Radio Passthrough mode (hardware failsafe for Arduplane) +// 0.9.87 : #define correction for radio passthrough (was screwed up). // ------------------------------------------------------------------------------------------------------------------------------------------------------------ // PREPROCESSOR DIRECTIVES // ------------------------------------------------------------------------------------------------------------------------------------------------------------ @@ -46,7 +47,7 @@ #define ERROR_DETECTION_WINDOW 3000 * LOOP_TIMER_10MS // Detection window for error detection (default to 30s) #define ERROR_CONDITION_DELAY 500 * LOOP_TIMER_10MS // Servo error condition LED delay (LED blinking duration) -#define PASSTHROUGH_MODE ENABLED // Set it to "DISABLED" to remove radio passthrough mode (hardware failsafe for Arduplane) +#define PASSTHROUGH_MODE_ENABLED // Comment this line to remove CH8 radio passthrough mode support (hardware failsafe for Arduplane) #define PASSTHROUGH_CHANNEL 8 * 2 // Channel for passthrough mode selection #define PASSTHROUGH_CHANNEL_OFF_US ONE_US * 1600 - PPM_PRE_PULSE // Passthrough off threshold #define PASSTHROUGH_CHANNEL_ON_US ONE_US * 1800 - PPM_PRE_PULSE // Passthrough on threshold @@ -97,7 +98,7 @@ int main(void) static uint16_t servo_error_condition_timer=0; // Servo error condition timer static uint16_t blink_led_timer = 0; // Blink led timer - #if PASSTHROUGH_MODE == ENABLED + #ifdef PASSTHROUGH_MODE_ENABLED static uint8_t mux_timer = 0; // Mux timer static uint8_t mux_counter = 0; // Mux counter static int8_t mux_check = 0; @@ -314,7 +315,7 @@ int main(void) PWM_LOOP: // SERVO_PWM_MODE while( 1 ) { - #if PASSTHROUGH_MODE == ENABLED + #ifdef PASSTHROUGH_MODE_ENABLED // ------------------------------------------------------------------------------ // Radio passthrough control (mux chip A/B control) // ------------------------------------------------------------------------------