diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index be77599901..24e50c1ac0 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -922,9 +922,11 @@ void loop() // check for new GPS messages // -------------------------- - if(GPS_enabled){ - update_GPS(); - } + #if RETRO_LOITER_MODE == DISABLED + if(GPS_enabled){ + update_GPS(); + } + #endif // perform 10hz tasks // ------------------ @@ -996,9 +998,11 @@ static void medium_loop() case 0: medium_loopCounter++; - //if(GPS_enabled){ - // update_GPS(); - //} + #if RETRO_LOITER_MODE == ENABLED + if(GPS_enabled){ + update_GPS(); + } + #endif #if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode if(g.compass_enabled){ @@ -1036,7 +1040,11 @@ static void medium_loop() // this calculates the velocity for Loiter // only called when there is new data // ---------------------------------- + #if RETRO_LOITER_MODE == ENABLED + calc_GPS_velocity(); + #else calc_XY_velocity(); + #endif // If we have optFlow enabled we can grab a more accurate speed // here and override the speed from the GPS diff --git a/ArduCopter/CMakeLists.txt b/ArduCopter/CMakeLists.txt new file mode 100644 index 0000000000..6c88ad554d --- /dev/null +++ b/ArduCopter/CMakeLists.txt @@ -0,0 +1,48 @@ +set(CMAKE_TOOLCHAIN_FILE ../cmake/ArduinoToolchain.cmake) # Arduino Toolchain + +cmake_minimum_required(VERSION 2.8) + +project(ArduCopter C CXX) + +set(PROJECT_VERSION_MAJOR "2") +set(PROJECT_VERSION_MINOR "6") +set(PROJECT_VERSION_PATCH "0") + +set(PROJECT_DESCRIPTION "ArduPilotMega based Rotor-craft Autopilot.") + +# macro path +list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules") +include(CMakeParseArguments) +include(APMOption) + +# options +add_definitions(-DUSE_CMAKE_APM_CONFIG) +include(options.cmake) +include_directories(${CMAKE_BINARY_DIR}) +apm_option_generate_config(FILE "APM_Config_cmake.h" OPTIONS ${APM_OPTIONS}) + +# disallow in-source build +include(MacroEnsureOutOfSourceBuild) +macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build. +Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.") + +# built variables +set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}") +set(FIRMWARE_NAME "${PROJECT_NAME}-${APM_HARDWARE}-${APM_PROCESSOR}-${HIL_MODE}") + +# modify flags from default toolchain flags +set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${APM_OPT_FLAGS}") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${APM_OPT_FLAGS} -Wno-reorder") +set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${APM_OPT_FLAGS} -Wl,--relax") + +# build apm project +set(ARDUINO_EXTRA_LIBRARIES_PATH ${CMAKE_SOURCE_DIR}/../libraries) +set(${FIRMWARE_NAME}_SKETCH ${CMAKE_SOURCE_DIR}/../${PROJECT_NAME}) +set(${FIRMWARE_NAME}_BOARD ${APM_PROCESSOR}) +set(${FIRMWARE_NAME}_PORT ${APM_PROGRAMMING_PORT}) +generate_arduino_firmware(${FIRMWARE_NAME}) +install(FILES ${CMAKE_BINARY_DIR}/${FIRMWARE_NAME}.hex DESTINATION "/") + +# cpack +include(APMCPackConfig) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index db5fb8c52c..b0fd436fa2 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -28,7 +28,12 @@ /// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that /// change in your local copy of APM_Config.h. /// +#ifdef USE_CMAKE_APM_CONFIG +#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists +#else #include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER. +#endif + ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// @@ -947,4 +952,9 @@ # define QUATERNION_ENABLE DISABLED #endif +// TEMPORARY FOR TESTING +#ifndef RETRO_LOITER_MODE +# define RETRO_LOITER_MODE DISABLED +#endif + #endif // __ARDUCOPTER_CONFIG_H__ diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 83b6c8ce55..47648eb429 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -90,6 +90,15 @@ static void calc_XY_velocity(){ last_latitude = g_gps->latitude; } +#if RETRO_LOITER_MODE == ENABLED +static void calc_GPS_velocity() +{ + float temp = radians((float)g_gps->ground_course/100.0); + x_actual_speed = (float)g_gps->ground_speed * sin(temp); + y_actual_speed = (float)g_gps->ground_speed * cos(temp); +} +#endif + static void calc_location_error(struct Location *next_loc) { static int16_t last_lon_error = 0; @@ -152,8 +161,14 @@ static void calc_location_error(struct Location *next_loc) } #define NAV_ERR_MAX 600 +#define NAV_RATE_ERR_MAX 250 static void calc_loiter(int x_error, int y_error) { + #if RETRO_LOITER_MODE == ENABLED + x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX); + y_error = constrain(y_error, -NAV_ERR_MAX, NAV_ERR_MAX); + #endif + int32_t p,i,d; // used to capture pid values for logging int32_t output; int32_t x_target_speed, y_target_speed; @@ -169,6 +184,9 @@ static void calc_loiter(int x_error, int y_error) #endif x_rate_error = x_target_speed - x_actual_speed; // calc the speed error + #if RETRO_LOITER_MODE == ENABLED + x_rate_error = constrain(x_rate_error, -NAV_RATE_ERR_MAX, NAV_RATE_ERR_MAX); + #endif p = g.pid_loiter_rate_lon.get_p(x_rate_error); i = g.pid_loiter_rate_lon.get_i(x_rate_error, dTnav); d = g.pid_loiter_rate_lon.get_d(x_rate_error, dTnav); @@ -196,6 +214,9 @@ static void calc_loiter(int x_error, int y_error) #endif y_rate_error = y_target_speed - y_actual_speed; + #if RETRO_LOITER_MODE == ENABLED + y_rate_error = constrain(y_rate_error, -NAV_RATE_ERR_MAX, NAV_RATE_ERR_MAX); + #endif p = g.pid_loiter_rate_lat.get_p(y_rate_error); i = g.pid_loiter_rate_lat.get_i(y_rate_error, dTnav); d = g.pid_loiter_rate_lat.get_d(y_rate_error, dTnav); diff --git a/ArduCopter/options.cmake b/ArduCopter/options.cmake new file mode 100644 index 0000000000..9f3a234422 --- /dev/null +++ b/ArduCopter/options.cmake @@ -0,0 +1,183 @@ +# +# This files is used by cmake to present options to the +# user in the cmake-gui, it can also be used directly to +# set options in the cmake command line. +# +# This file generates APM_Config_cmake.h +# which overrides the APM_Config.h file. When disributing +# to the Arduino IDE user. APM_Confg_cmake.h could be copied to +# APM_Config.h, but this is not necessary. The +# advantage would be that the Arduino user would have +# a more up-to-date/ complete list of options and the developers +# using cmake have a nice gui/ command-line interface. +# + +apm_option("APM_PROGRAMMING_PORT" TYPE STRING + DESCRIPTION "Programming upload port?" + DEFAULT "/dev/ttyACM0") + +apm_option("CONFIG_APM_HARDWARE" TYPE STRING + DESCRIPTION "APM Hardware?" + OPTIONS "APM_HARDWARE_APM2" "APM_HARDWARE_APM1" + DEFAULT "APM_HARDWARE_APM2") + +apm_option("APM2_BETA_HARDWARE" TYPE BOOL DEFINE_ONLY + DESCRIPTION "Is this an APM 2.0 Beta board?" + DEFAULT OFF) + +apm_option("APM_PROCESSOR" TYPE STRING + DESCRIPTION "ArduPilotMega processor (2560 for APM2 and later APM1)?" + DEFAULT "mega2560" + OPTIONS "mega" "mega2560") + +apm_option("CLI_SLIDER_ENABLED" TYPE BOOL + DESCRIPTION "Enable command line interface switch?" + DEFAULT OFF) + +apm_option("LOGGING_ENABLED" TYPE BOOL + DESCRIPTION "Enable logging?" + DEFAULT OFF) + +apm_option("QUATERNION_ENABLE" TYPE BOOL ADVANCED + DESCRIPTION "Enable quaterion navigation?" + DEFAULT OFF) + +apm_option("GPS_PROTOCOL" TYPE STRING + DESCRIPTION "GPS protocol?" + DEFAULT "GPS_PROTOCOL_AUTO" + OPTIONS + "GPS_PROTOOCL_NONE" + "GPS_PROTOCOL_AUTO" + "GPS_PROTOCOL_NONE" + "GPS_PROTOCOL_IMU" + "GPS_PROTOCOL_MTK" + "GPS_PROTOCOL_MTK16" + "GPS_PROTOCOL_UBLOX" + "GPS_PROTOCOL_SIRF" + "GPS_PROTOCOL_NMEA") + +apm_option("AIRSPEED_SENSOR" TYPE BOOL + DESCRIPTION "Enable airspeed sensor?" + DEFAULT OFF) + +apm_option("AIRSPEED_RATIO" TYPE STRING ADVANCED + DESCRIPTION "Airspeed ratio?" + DEFAULT "1.9936") + +apm_option("MAGNETOMETER" TYPE BOOL + DESCRIPTION "Enable airspeed sensor?" + DEFAULT OFF) + +apm_option("MAG_ORIENTATION" TYPE STRING ADVANCED + DESCRIPTION "Magnetometer orientation?" + DEFAULT "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" + OPTIONS + "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" + "AP_COMPASS_COMPONENTS_DOWN_PINS_BACK" + "AP_COMPASS_COMPONENTS_UP_PINS_FORWARD" + "AP_COMPASS_COMPONENTS_UP_PINS_BACK") + +apm_option("HIL_MODE" TYPE STRING + DESCRIPTION "Hardware-in-the-loop- mode?" + DEFAULT "HIL_MODE_DISABLED" + OPTIONS + "HIL_MODE_DISABLED" + "HIL_MODE_ATTITUDE" + "HIL_MODE_SENSORS") + +apm_option("HIL_PORT" TYPE STRING + DESCRIPTION "Port for Hardware-in-the-loop communication" + DEFAULT "0" + OPTIONS "0" "1" "2" "3") + +apm_option("HIL_PROTOCOL" TYPE STRING + DESCRIPTION "Hardware-in-the-loop protocol?" + DEFAULT "HIL_PROTOCOL_MAVLINK" + OPTIONS "HIL_PROTOCOL_MAVLINK" "HIL_PROTOCOL_XPLANE") + +apm_option("GCS_PROTOCOL" TYPE STRING + DESCRIPTION "Ground station protocol?" + DEFAULT "GCS_PROTOCOL_MAVLINK" + OPTIONS "GCS_PROTOCOL_NONE" "GCS_PROTOCOL_MAVLINK") + +apm_option("GCS_PORT" TYPE STRING ADVANCED + DESCRIPTION "Ground station port?" + DEFAULT "3" + OPTIONS "0" "1" "2" "3") + +apm_option("MAV_SYSTEM_ID" TYPE STRING ADVANCED + DESCRIPTION "MAVLink System ID?" + DEFAULT "1") + +apm_option("MAVLINKV10" TYPE BOOL DEFINE_ONLY + DESCRIPTION "Use mavlink version 1.0?" + DEFAULT OFF) + +apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED + DESCRIPTION "Serial 0 baudrate?" + DEFAULT "115200" + OPTIONS "57600" "115200") + +apm_option("SERIAL3_BAUD" TYPE STRING ADVANCED + DESCRIPTION "Serial 3 baudrate?" + DEFAULT "57600" + OPTIONS "57600" "115200") + +apm_option("BATTERY_EVENT" TYPE BOOL ADVANCED + DESCRIPTION "Enable low voltage/ high discharge warnings?" + DEFAULT OFF) + +apm_option("LOW_VOLTAGE" TYPE STRING ADVANCED + DESCRIPTION "Voltage to consider low (volts)?" + DEFAULT "9.6") + +apm_option("VOLT_DIV_RATIO" TYPE STRING ADVANCED + DESCRIPTION "Voltage division ratio?" + DEFAULT "3.56") + +apm_option("CUR_AMPS_PER_VOLT" TYPE STRING ADVANCED + DESCRIPTION "Current amps/volt?" + DEFAULT "27.32") + +apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED + DESCRIPTION "Current amps offset?" + DEFAULT "0.0") + +# arducopter specific +apm_option("FRAME_CONFIG" TYPE STRING + DESCRIPTION "Vehicle type?" + DEFAULT "QUAD_FRAME" + OPTIONS + "QUAD_FRAME" + "TRI_FRAME" + "HEXA_FRAME" + "Y6_FRAME" + "OCTA_FRAME" + "OCTA_QUAD_FRAME" + "HELI_FRAME" + ) + +apm_option("FRAME_ORIENTATION" TYPE STRING + DESCRIPTION "Vehicle type?" + DEFAULT "QUAD_FRAME" + OPTIONS + "PLUS_FRAME" + "X_FRAME" + "V_FRAME" + ) + +apm_option("CH7_OPTION" TYPE STRING + DESCRIPTION "Channel 7 option? (ADC_FILTER is experimental)" + DEFAULT "CH7_SAVE_WP" + OPTIONS + "CH7_DO_NOTHING" + "CH7_SET_HOVER" + "CH7_FLIP" + "CH7_RTL" + "CH7_AUTO_TRIM" + "CH7_ADC_FILTER" + "CH7_SAVE_WP") + +apm_option("ACCEL_ALT_HOLD" TYPE BOOL ADVANCED + DESCRIPTION "Disabled by default, work in progress." + DEFAULT OFF) diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index 571cfe4e92..18b5794ca7 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -16,9 +16,7 @@ // The following are the recommended settings for Xplane // simulation. Remove the leading "/* and trailing "*/" to enable: -/* -#define HIL_MODE HIL_MODE_ATTITUDE -*/ +#define HIL_MODE HIL_MODE_DISABLED /* // HIL_MODE SELECTION diff --git a/ArduPlane/CMakeLists.txt b/ArduPlane/CMakeLists.txt new file mode 100644 index 0000000000..061888e067 --- /dev/null +++ b/ArduPlane/CMakeLists.txt @@ -0,0 +1,52 @@ +set(CMAKE_TOOLCHAIN_FILE ../cmake/ArduinoToolchain.cmake) # Arduino Toolchain + +cmake_minimum_required(VERSION 2.8) + +project(ArduPlane C CXX) + +set(PROJECT_VERSION_MAJOR "2") +set(PROJECT_VERSION_MINOR "3") +set(PROJECT_VERSION_PATCH "3") + +set(PROJECT_DESCRIPTION "ArduPilotMega based Airplane Autopilot.") + +# macro path +list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules") +include(CMakeParseArguments) +include(APMOption) + +# options +include(options.cmake) +include_directories(${CMAKE_BINARY_DIR}) +add_definitions(-DUSE_CMAKE_APM_CONFIG) +apm_option_generate_config(FILE "APM_Config_cmake.h" BUILD_FLAGS APM_BUILD_FLAGS) +add_definitions(${APM_BUILD_FLAGS}) +message(STATUS "build flags: ${APM_BUILD_FLAGS}") +#configure_file(APM_Config2.h.cmake APM_Config2.h) + +# disallow in-source build +include(MacroEnsureOutOfSourceBuild) +macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build. +Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.") + +# built variables +set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}") +set(FIRMWARE_NAME "${PROJECT_NAME}-${CONFIG_APM_HARDWARE}-${APM_PROCESSOR}-${HIL_MODE}") + +# modify flags from default toolchain flags +set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${APM_OPT_FLAGS}") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${APM_OPT_FLAGS} -Wno-reorder") +set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${APM_OPT_FLAGS} -Wl,--relax") + +# build apm project +set(ARDUINO_EXTRA_LIBRARIES_PATH ${CMAKE_SOURCE_DIR}/../libraries) +set(${FIRMWARE_NAME}_SKETCH ${CMAKE_SOURCE_DIR}/../${PROJECT_NAME}) +set(${FIRMWARE_NAME}_BOARD ${APM_PROCESSOR}) +set(${FIRMWARE_NAME}_PORT ${APM_PROGRAMMING_PORT}) +set(${FIRMWARE_NAME}_SRCS ${CMAKE_BINARY_DIR}/APM_Config_cmake.h) +generate_arduino_firmware(${FIRMWARE_NAME}) +install(FILES ${CMAKE_BINARY_DIR}/${FIRMWARE_NAME}.hex DESTINATION "/") + +# cpack +include(APMCPackConfig) diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 07b777f4b4..65a48cd7dc 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -26,7 +26,11 @@ /// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that /// change in your local copy of APM_Config.h. /// +#ifdef USE_CMAKE_APM_CONFIG +#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists +#else #include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER. +#endif /// /// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that /// change in your local copy of APM_Config.h. diff --git a/ArduPlane/options.cmake b/ArduPlane/options.cmake new file mode 100644 index 0000000000..f984b36aba --- /dev/null +++ b/ArduPlane/options.cmake @@ -0,0 +1,209 @@ +# +# This files is used by cmake to present options to the +# user in the cmake-gui, it can also be used directly to +# set options in the cmake command line. +# +# This file generates APM_Config_cmake.h +# which overrides the APM_Config.h file. When disributing +# to the Arduino IDE user. APM_Confg_cmake.h could be copied to +# APM_Config.h, but this is not necessary. The +# advantage would be that the Arduino user would have +# a more up-to-date/ complete list of options and the developers +# using cmake have a nice gui/ command-line interface. +# + +apm_option("APM_PROGRAMMING_PORT" TYPE STRING + DESCRIPTION "Programming upload port?" + DEFAULT "/dev/ttyACM0") + +apm_option("CONFIG_APM_HARDWARE" TYPE STRING + DESCRIPTION "APM Hardware?" + OPTIONS "APM_HARDWARE_APM2" "APM_HARDWARE_APM1" + DEFAULT "APM_HARDWARE_APM2") + +apm_option("APM2_BETA_HARDWARE" TYPE BOOL DEFINE_ONLY + DESCRIPTION "Is this an APM 2.0 Beta board?" + DEFAULT OFF) + +apm_option("APM_PROCESSOR" TYPE STRING + DESCRIPTION "ArduPilotMega processor (2560 for APM2 and later APM1)?" + DEFAULT "mega2560" + OPTIONS "mega" "mega2560") + +#apm_option("CLI_SLIDER_ENABLED" TYPE BOOL + #DESCRIPTION "Enable command line interface switch?" + #DEFAULT OFF) + +apm_option("LOGGING_ENABLED" TYPE BOOL + DESCRIPTION "Enable logging?" + DEFAULT OFF) + +apm_option("QUATERNION_ENABLE" TYPE BOOL + DESCRIPTION "Enable quaterion navigation?" + DEFAULT OFF) + +apm_option("GPS_PROTOCOL" TYPE STRING + DESCRIPTION "GPS protocol?" + DEFAULT "GPS_PROTOCOL_AUTO" + OPTIONS + "GPS_PROTOOCL_NONE" + "GPS_PROTOCOL_AUTO" + "GPS_PROTOCOL_NONE" + "GPS_PROTOCOL_IMU" + "GPS_PROTOCOL_MTK" + "GPS_PROTOCOL_MTK16" + "GPS_PROTOCOL_UBLOX" + "GPS_PROTOCOL_SIRF" + "GPS_PROTOCOL_NMEA") + +apm_option("AIRSPEED_SENSOR" TYPE BOOL + DESCRIPTION "Enable airspeed sensor?" + DEFAULT OFF) + +apm_option("PITOT_ENABLED" TYPE BOOL + DESCRIPTION "Enable pitot static system?" + DEFAULT OFF) + +apm_option("SONAR_ENABLED" TYPE BOOL + DESCRIPTION "Enable sonar?" + DEFAULT OFF) + +apm_option("AIRSPEED_RATIO" TYPE STRING ADVANCED + DESCRIPTION "Airspeed ratio?" + DEFAULT "1.9936") + +#apm_option("MAGNETOMETER" TYPE BOOL + #DESCRIPTION "Enable airspeed sensor?" + #DEFAULT OFF) + +#apm_option("MAG_ORIENTATION" TYPE STRING ADVANCED + #DESCRIPTION "Magnetometer orientation?" + #DEFAULT "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" + #OPTIONS + #"AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" + #"AP_COMPASS_COMPONENTS_DOWN_PINS_BACK" + #"AP_COMPASS_COMPONENTS_UP_PINS_FORWARD" + #"AP_COMPASS_COMPONENTS_UP_PINS_BACK") + +apm_option("HIL_MODE" TYPE STRING + DESCRIPTION "Hardware-in-the-loop- mode?" + DEFAULT "HIL_MODE_DISABLED" + OPTIONS + "HIL_MODE_DISABLED" + "HIL_MODE_ATTITUDE" + "HIL_MODE_SENSORS") + +apm_option("MAV_SYSTEM_ID" TYPE STRING ADVANCED + DESCRIPTION "MAVLink System ID?" + DEFAULT "1") + +apm_option("MAVLINK10" TYPE BOOL DEFINE_ONLY BUILD_FLAG + DESCRIPTION "Use mavlink version 1.0?" + DEFAULT OFF) + +apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED + DESCRIPTION "Serial 0 baudrate?" + DEFAULT "115200" + OPTIONS "57600" "115200") + +apm_option("SERIAL3_BAUD" TYPE STRING ADVANCED + DESCRIPTION "Serial 3 baudrate?" + DEFAULT "57600" + OPTIONS "57600" "115200") + +apm_option("BATTERY_EVENT" TYPE BOOL ADVANCED + DESCRIPTION "Enable low voltage/ high discharge warnings?" + DEFAULT OFF) + +apm_option("LOW_VOLTAGE" TYPE STRING ADVANCED + DESCRIPTION "Voltage to consider low (volts)?" + DEFAULT "9.6") + +apm_option("VOLT_DIV_RATIO" TYPE STRING ADVANCED + DESCRIPTION "Voltage division ratio?" + DEFAULT "3.56") + +apm_option("CUR_AMPS_PER_VOLT" TYPE STRING ADVANCED + DESCRIPTION "Current amps/volt?" + DEFAULT "27.32") + +apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED + DESCRIPTION "Current amps offset?" + DEFAULT "0.0") + +apm_option("HIGH_DISCHARGE" TYPE STRING ADVANCED + DESCRIPTION "What to consider high discharge rate (milliamps)?" + DEFAULT "1760") + +apm_option("INPUT_VOLTAGE" TYPE STRING ADVANCED + DESCRIPTION "Voltage measured at the process (V)? (affects ADC measurements)" + DEFAULT "4.68") + +set(RADIO_CHANNELS "1" "2" "3" "4" "5" "6" "7" "8") +apm_option("FLIGHT_MODE_CHANNEL" TYPE STRING ADVANCED + DESCRIPTION "The radio channel to control the flight mode." + DEFAULT "8" + OPTIONS ${RADIO_CHANNELS}) + +set(FLIGHT_MODES + MANUAL STABILIZE + FLY_BY_WIRE_A + FLY_BY_WIRE_B + RTL + AUTO + LOITER CIRCLE) + +set(FLIGHT_MODES_RADIO_PWM 1165 1295 1425 1555 1685 1815) + +set(FLIGHT_MODES_DEFAULT + RTL + RTL + STABILIZE + STABILIZE + MANUAL + MANUAL) + +foreach(MODE 1 2 3 4 5 6) + math(EXPR INDEX "${MODE} -1") + list(GET FLIGHT_MODES_RADIO_PWM ${INDEX} RADIO_PWM) + list(GET FLIGHT_MODES_DEFAULT ${INDEX} FLIGHT_MODE_DEFAULT) + apm_option("FLIGHT_MODE_${MODE}" TYPE STRING ADVANCED + DESCRIPTION "Flight mode ${MODE} (pwm ${RADIO_PWM} ms)?" + DEFAULT "${FLIGHT_MODE_DEFAULT}" + OPTIONS ${FLIGHT_MODES}) +endforeach() + +#set(FLAP_1_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?") +#set(FLAP_1_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?") + +#set(FLAP_2_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?") +#set(FLAP_2_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?") + +#set(THROTTLE_FAILSAFE "ENABLED" CACHE STRING "Enable throttle shuttoff when radio below failsafe value?") +#set_property(CACHE THROTTLE_FAILSAFE PROPERTY STRINGS ENABLED DISABLED) + +#set(THROTTLE_FS_VALUE "950" CACHE STRING "Radio value at which to disable throttle (ms).") + +#set(GCS_HEARTBEAT_FAILSAFE "DISABLED" CACHE STRING "Enable failsafe when ground station communication lost?") +#set_property(CACHE GCS_HEARTBEAT_FAILSAFE PROPERTY STRINGS ENABLED DISABLED) +#set(SHORT_FAILSAFE_ACTION "0" CACHE STRING "Failsafe mode RTL, then return to AUTO/LOITER") +#set(LONG_FAILSAFE_ACTION "0" CACHE STRING "Failsafe mode RTL") + +#set(AUTO_TRIM "DISABLED" CACHE STRING "Update trim with manual radio input when leaving MANUAL mode?") +#set_property(CACHE AUTO_TRIM PROPERTY STRINGS ENABLED DISABLED) + +#set(THROTTLE_REVERSE "DISABLED" CACHE STRING "Reverse throttle output signal?") +#set_property(CACHE THROTTLE_REVERSE PROPERTY STRINGS ENABLED DISABLED) + +#set(ENABLE_STICK_MIXING "DISABLED" CACHE STRING "Enable manual input in autopilot modes?") +#set_property(CACHE THROTTLE_REVERSE PROPERTY STRINGS ENABLED DISABLED) + +#set(THROTTLE_OUT "ENABLED" CACHE STRING "Disabled throttle output? (useful for debugging)?") +#set_property(CACHE THROTTLE_OUT PROPERTY STRINGS ENABLED DISABLED) + +#set(GROUND_START_DELAY "0" CACHE STRING "Delay between power-up and IMU calibration (s)?") + +#set(ENABLE_AIR_START "DISABLED" CACHE STRING "Enable in-air restart?") +#set_property(CACHE ENABLE_AIR_START PROPERTY STRINGS ENABLED DISABLED) + + diff --git a/CMakeLists.txt b/CMakeLists.txt deleted file mode 100644 index e7a3783400..0000000000 --- a/CMakeLists.txt +++ /dev/null @@ -1,162 +0,0 @@ -cmake_minimum_required(VERSION 2.8.5) - -set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules) -set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake) - -# modify flags from default toolchain flags -set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") - -set(ARDUINO_C_FLAGS "${APM_OPT_FLAGS} -mcall-prologues -ffunction-sections -fdata-sections") -set(ARDUINO_CXX_FLAGS "${APM_OPT_FLAGS} -mcall-prologues -ffunction-sections -fdata-sections -fno-exceptions -Wno-reorder") -set(ARDUINO_LINKER_FLAGS "-lc -lm ${APM_OPT_FLAGS} -Wl,--gc-sections") - -project(ArduPilotMega C CXX) - -# set default cmake build type to RelWithDebInfo (None Debug Release RelWithDebInfo MinSizeRel) -if( NOT DEFINED CMAKE_BUILD_TYPE ) - set( CMAKE_BUILD_TYPE "RelWithDebInfo" ) -endif() - -# set these for release -set(APPLICATION_VERSION_MAJOR "1") -set(APPLICATION_VERSION_MINOR "2") -set(APPLICATION_VERSION_PATCH "0") - -# dependencies -find_package(Arduino 22 REQUIRED) - -# cmake settigns -set(APPLICATION_NAME ${PROJECT_NAME}) -set(APPLICATION_VERSION "${APPLICATION_VERSION_MAJOR}.${APPLICATION_VERSION_MINOR}.${APPLICATION_VERSION_PATCH}") - -# macros -include(MacroEnsureOutOfSourceBuild) -#include(UseDoxygen) - -# disallow in-source build -macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build. -Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.") - -# options -if (NOT DEFINED BOARD) - message(STATUS "please define the board type (for example: cmake -DBOARD=mega, assuming mega2560") - set(BOARD "mega2560") -endif() - -if (NOT DEFINED PORT) - message(STATUS "please define the upload port (for example: cmake - -DPORT=/dev/ttyUSB0, assuming /dev/ttyUSB0") - set(PORT "/dev/ttyUSB0") -endif() - -# cpack settings -set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "A universal autopilot system for the ArduPilotMega board.") -set(CPACK_PACKAGE_VENDOR "DIYDRONES") -set(CPACK_DEBIAN_PACKAGE_MAINTAINER "james.goppert@gmail.com") -set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com") -set(CPACK_PACKAGE_DESCRIPTION_FILE "${CMAKE_SOURCE_DIR}/README.txt") -set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_SOURCE_DIR}/COPYING.txt") -set(CPACK_RESOURCE_FILE_README "${CMAKE_SOURCE_DIR}/README.txt") -set(CPACK_PACKAGE_VERSION_MAJOR "${APPLICATION_VERSION_MAJOR}") -set(CPACK_PACKAGE_VERSION_MINOR "${APPLICATION_VERSION_MINOR}") -set(CPACK_PACKAGE_VERSION_PATCH "${APPLICATION_VERSION_PATCH}") -set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}") -set(CPACK_SET_DESTDIR TRUE) -set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES} - /.git/;/build/;~$;.*\\\\.bin$;.*\\\\.swp$) -set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") -set(CPACK_SOURCE_GENERATOR "ZIP") -set(CPACK_GENERATOR "ZIP") -set(CPACK_PACKAGE_NAME "${APPLICATION_NAME}_${BOARD}") -include(CPack) - -find_package(Arduino 22 REQUIRED) - -# determine board being used -if (NOT DEFINED BOARD) - message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify") - set(BOARD "mega") -endif() -message(STATUS "Board configured as: ${BOARD}") - -# add a sketch -macro(add_sketch SKETCH_NAME BOARD PORT) - - message(STATUS "Generating sketch ${SKETCH_NAME}") - - # files - set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}/${SKETCH_NAME}.cpp) - set(SKETCH_PDE ${CMAKE_CURRENT_SOURCE_DIR}/${SKETCH_NAME}/${SKETCH_NAME}.pde) - #message(STATUS "SKETCH_PDE:\n${SKETCH_PDE}") - #message(STATUS "SKETCH_CPP:\n${SKETCH_CPP}") - - # settings - set(${SKETCH_NAME}_BOARD ${BOARD}) - set(${SKETCH_NAME}_PORT ${PORT}) - set(${SKETCH_NAME}_SRCS ${SKETCH_CPP}) - set(${SKETCH_NAME}_LIBS m c) - - # find pde files - file(GLOB PDE_SOURCES ${SKETCH_NAME}/*.pde) - - # find the head of the main pde - file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n") - file(READ ${SKETCH_PDE} FILE) - - string(FIND "${FILE}" "#include" POS1 REVERSE) - string(LENGTH "${FILE}" FILE_LENGTH) - math(EXPR LENGTH_STR1 "${FILE_LENGTH}-${POS1}") - string(SUBSTRING "${FILE}" ${POS1} ${LENGTH_STR1} STR1) - string(FIND "${STR1}" "\n" POS2) - math(EXPR POS3 "${POS1}+${POS2}") - string(SUBSTRING "${FILE}" 0 ${POS3} FILE_HEAD) - #message(STATUS "FILE_HEAD:\n${FILE_HEAD}") - - # find the body of the main pde - math(EXPR BODY_LENGTH "${FILE_LENGTH}-${POS3}-1") - string(SUBSTRING "${FILE}" "${POS3}+1" "${BODY_LENGTH}" FILE_BODY) - #message(STATUS "BODY:\n${FILE_BODY}") - - # write the file head - file(APPEND ${SKETCH_CPP} "${FILE_HEAD}") - file(APPEND ${SKETCH_CPP} "\n#include \"WProgram.h\"\n") - - # write prototypes - foreach(PDE ${PDE_SOURCES}) - #message(STATUS "pde: ${PDE}") - file(READ ${PDE} FILE) - string(REGEX MATCHALL "[\n]([a-zA-Z]+[ ])*[_a-zA-Z0-9]+([ ]*[\n][\t]*|[ ])[_a-zA-Z0-9]+[ ]?[\n]?[\t]*[ ]*[(]([\t]*[ ]*[*]?[ ]?[a-zA-Z0-9_][,]?[ ]*[\n]?)*[)]" PROTOTYPES ${FILE}) - foreach(PROTOTYPE ${PROTOTYPES}) - #message(STATUS "\tprototype: ${PROTOTYPE};") - file(APPEND ${SKETCH_CPP} "${PROTOTYPE};") - endforeach() - endforeach() - - - # write source - file(APPEND ${SKETCH_CPP} "\n${FILE_BODY}") - list(REMOVE_ITEM PDE_SOURCES ${SKETCH_PDE}) - list(SORT PDE_SOURCES) - foreach (PDE ${PDE_SOURCES}) - file(READ ${PDE} FILE) - file(APPEND ${SKETCH_CPP} "${FILE}") - endforeach() - - # generate firmware - include_directories(${CMAKE_CURRENT_SOURCE_DIR}/${SKETCH_NAME}) - generate_arduino_firmware(${SKETCH_NAME}) - set_target_properties(${SKETCH_NAME} PROPERTIES LINKER_LANGUAGE CXX) - - # install settings - install(FILES - ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}.hex - DESTINATION bin - ) -endmacro() - -# projects -add_sketch(apo ${BOARD} ${PORT}) -add_sketch(ArduRover ${BOARD} ${PORT}) -add_sketch(ArduBoat ${BOARD} ${PORT}) -#add_sketch(ArduPlane ${BOARD} ${PORT}) -#add_sketch(ArduCopter ${BOARD} ${PORT}) diff --git a/README.txt b/README.txt index 874f6393f7..fe2ea5d9c5 100644 --- a/README.txt +++ b/README.txt @@ -13,17 +13,17 @@ Building using make Building using cmake ----------------------------------------------- + - cd ArduPlane (ArduCopter etc ..) - mkdir build - cd build - - cmake .. -DBOARD=mega -DPORT=/dev/ttyUSB0 + - cmake .. -DAPM_BOARD=mega -DAPM_PORT=/dev/ttyUSB0 You can select from mega/mega2560. If you have arduino installed in a non-standard location you by specify it by using: -DARDUINO_SDK_PATH=/path/to/arduino .. - - make (will build every sketch) - - make ArduPlane (will build just ArduPlane etc.) - - make ArduPloat-upload (will upload the sketch) + - make (will build the sketch) + - make ArduPlane-upload (will upload the sketch ArduPlane etc.) - If you have a sync error during upload reset the board/power cycle the board + If you have a sync error during upload reset the board or power cycle the board before the upload starts. @@ -42,6 +42,8 @@ Building using eclipse cd /home/name/apm-build cmake -G"Eclipse CDT4 - Unix Makefiles" -D CMAKE_BUILD_TYPE=Debug ../apm-src -D BOARD=mega -D PORT=/dev/ttyUSB0 + Here apm-src can be any sketch, ArduPlane/ ArduCopter etc. + Note: Unix can be substituted for MinGW/ MSYS/ NMake (for windows) (see http://www.vtk.org/Wiki/Eclipse_CDT4_Generator) diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs index 448ceb7e10..7ac7ab2cdc 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs @@ -1,384 +1,293 @@ -namespace ArdupilotMega.Antenna -{ - partial class Tracker - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Windows Form Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - this.CMB_interface = new System.Windows.Forms.ComboBox(); - this.label1 = new System.Windows.Forms.Label(); - this.CMB_baudrate = new System.Windows.Forms.ComboBox(); - this.CMB_serialport = new System.Windows.Forms.ComboBox(); - this.TRK_pantrim = new System.Windows.Forms.TrackBar(); - this.TXT_panrange = new System.Windows.Forms.TextBox(); - this.label3 = new System.Windows.Forms.Label(); - this.label4 = new System.Windows.Forms.Label(); - this.label5 = new System.Windows.Forms.Label(); - this.label6 = new System.Windows.Forms.Label(); - this.TXT_tiltrange = new System.Windows.Forms.TextBox(); - this.TRK_tilttrim = new System.Windows.Forms.TrackBar(); - this.label2 = new System.Windows.Forms.Label(); - this.label7 = new System.Windows.Forms.Label(); - this.CHK_revpan = new System.Windows.Forms.CheckBox(); - this.CHK_revtilt = new System.Windows.Forms.CheckBox(); - this.TXT_pwmrangepan = new System.Windows.Forms.TextBox(); - this.TXT_pwmrangetilt = new System.Windows.Forms.TextBox(); - this.label8 = new System.Windows.Forms.Label(); - this.label9 = new System.Windows.Forms.Label(); - this.label10 = new System.Windows.Forms.Label(); - this.label11 = new System.Windows.Forms.Label(); - this.label12 = new System.Windows.Forms.Label(); - this.BUT_connect = new ArdupilotMega.MyButton(); - this.LBL_pantrim = new System.Windows.Forms.Label(); - this.LBL_tilttrim = new System.Windows.Forms.Label(); - ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).BeginInit(); - this.SuspendLayout(); - // - // CMB_interface - // - this.CMB_interface.FormattingEnabled = true; - this.CMB_interface.Items.AddRange(new object[] { - "Maestro", - "ArduTracker"}); - this.CMB_interface.Location = new System.Drawing.Point(83, 10); - this.CMB_interface.Name = "CMB_interface"; - this.CMB_interface.Size = new System.Drawing.Size(121, 21); - this.CMB_interface.TabIndex = 0; - this.CMB_interface.Text = "Maestro"; - // - // label1 - // - this.label1.AutoSize = true; - this.label1.Location = new System.Drawing.Point(13, 13); - this.label1.Name = "label1"; - this.label1.Size = new System.Drawing.Size(49, 13); - this.label1.TabIndex = 1; - this.label1.Text = "Interface"; - // - // CMB_baudrate - // - this.CMB_baudrate.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; - this.CMB_baudrate.FormattingEnabled = true; - this.CMB_baudrate.Items.AddRange(new object[] { - "4800", - "9600", - "14400", - "19200", - "28800", - "38400", - "57600", - "115200"}); - this.CMB_baudrate.Location = new System.Drawing.Point(337, 9); - this.CMB_baudrate.Name = "CMB_baudrate"; - this.CMB_baudrate.Size = new System.Drawing.Size(121, 21); - this.CMB_baudrate.TabIndex = 2; - // - // CMB_serialport - // - this.CMB_serialport.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; - this.CMB_serialport.FormattingEnabled = true; - this.CMB_serialport.Location = new System.Drawing.Point(210, 10); - this.CMB_serialport.Name = "CMB_serialport"; - this.CMB_serialport.Size = new System.Drawing.Size(121, 21); - this.CMB_serialport.TabIndex = 1; - // - // TRK_pantrim - // - this.TRK_pantrim.Location = new System.Drawing.Point(153, 81); - this.TRK_pantrim.Maximum = 360; - this.TRK_pantrim.Minimum = -360; - this.TRK_pantrim.Name = "TRK_pantrim"; - this.TRK_pantrim.Size = new System.Drawing.Size(375, 45); - this.TRK_pantrim.TabIndex = 5; - this.TRK_pantrim.TickFrequency = 5; - this.TRK_pantrim.Scroll += new System.EventHandler(this.TRK_pantrim_Scroll); - // - // TXT_panrange - // - this.TXT_panrange.Location = new System.Drawing.Point(83, 81); - this.TXT_panrange.Name = "TXT_panrange"; - this.TXT_panrange.Size = new System.Drawing.Size(64, 20); - this.TXT_panrange.TabIndex = 4; - this.TXT_panrange.Text = "360"; - this.TXT_panrange.TextChanged += new System.EventHandler(this.TXT_panrange_TextChanged); - // - // label3 - // - this.label3.AutoSize = true; - this.label3.Location = new System.Drawing.Point(326, 65); - this.label3.Name = "label3"; - this.label3.Size = new System.Drawing.Size(27, 13); - this.label3.TabIndex = 10; - this.label3.Text = "Trim"; - // - // label4 - // - this.label4.AutoSize = true; - this.label4.Location = new System.Drawing.Point(83, 65); - this.label4.Name = "label4"; - this.label4.Size = new System.Drawing.Size(39, 13); - this.label4.TabIndex = 11; - this.label4.Text = "Range"; - // - // label5 - // - this.label5.AutoSize = true; - this.label5.Location = new System.Drawing.Point(83, 141); - this.label5.Name = "label5"; - this.label5.Size = new System.Drawing.Size(39, 13); - this.label5.TabIndex = 17; - this.label5.Text = "Range"; - // - // label6 - // - this.label6.AutoSize = true; - this.label6.Location = new System.Drawing.Point(326, 141); - this.label6.Name = "label6"; - this.label6.Size = new System.Drawing.Size(27, 13); - this.label6.TabIndex = 16; - this.label6.Text = "Trim"; - // - // TXT_tiltrange - // - this.TXT_tiltrange.Location = new System.Drawing.Point(83, 157); - this.TXT_tiltrange.Name = "TXT_tiltrange"; - this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20); - this.TXT_tiltrange.TabIndex = 6; - this.TXT_tiltrange.Text = "90"; - this.TXT_tiltrange.TextChanged += new System.EventHandler(this.TXT_tiltrange_TextChanged); - // - // TRK_tilttrim - // - this.TRK_tilttrim.Location = new System.Drawing.Point(153, 157); - this.TRK_tilttrim.Maximum = 180; - this.TRK_tilttrim.Minimum = -180; - this.TRK_tilttrim.Name = "TRK_tilttrim"; - this.TRK_tilttrim.Size = new System.Drawing.Size(375, 45); - this.TRK_tilttrim.TabIndex = 7; - this.TRK_tilttrim.TickFrequency = 5; - this.TRK_tilttrim.Scroll += new System.EventHandler(this.TRK_tilttrim_Scroll); - // - // label2 - // - this.label2.AutoSize = true; - this.label2.Location = new System.Drawing.Point(12, 65); - this.label2.Name = "label2"; - this.label2.Size = new System.Drawing.Size(26, 13); - this.label2.TabIndex = 18; - this.label2.Text = "Pan"; - // - // label7 - // - this.label7.AutoSize = true; - this.label7.Location = new System.Drawing.Point(12, 141); - this.label7.Name = "label7"; - this.label7.Size = new System.Drawing.Size(21, 13); - this.label7.TabIndex = 19; - this.label7.Text = "Tilt"; - // - // CHK_revpan - // - this.CHK_revpan.AutoSize = true; - this.CHK_revpan.Location = new System.Drawing.Point(534, 83); - this.CHK_revpan.Name = "CHK_revpan"; - this.CHK_revpan.Size = new System.Drawing.Size(46, 17); - this.CHK_revpan.TabIndex = 20; - this.CHK_revpan.Text = "Rev"; - this.CHK_revpan.UseVisualStyleBackColor = true; - this.CHK_revpan.CheckedChanged += new System.EventHandler(this.CHK_revpan_CheckedChanged); - // - // CHK_revtilt - // - this.CHK_revtilt.AutoSize = true; - this.CHK_revtilt.Location = new System.Drawing.Point(534, 159); - this.CHK_revtilt.Name = "CHK_revtilt"; - this.CHK_revtilt.Size = new System.Drawing.Size(46, 17); - this.CHK_revtilt.TabIndex = 21; - this.CHK_revtilt.Text = "Rev"; - this.CHK_revtilt.UseVisualStyleBackColor = true; - this.CHK_revtilt.CheckedChanged += new System.EventHandler(this.CHK_revtilt_CheckedChanged); - // - // TXT_pwmrangepan - // - this.TXT_pwmrangepan.Location = new System.Drawing.Point(83, 107); - this.TXT_pwmrangepan.Name = "TXT_pwmrangepan"; - this.TXT_pwmrangepan.Size = new System.Drawing.Size(64, 20); - this.TXT_pwmrangepan.TabIndex = 22; - this.TXT_pwmrangepan.Text = "1000"; - // - // TXT_pwmrangetilt - // - this.TXT_pwmrangetilt.Location = new System.Drawing.Point(83, 183); - this.TXT_pwmrangetilt.Name = "TXT_pwmrangetilt"; - this.TXT_pwmrangetilt.Size = new System.Drawing.Size(64, 20); - this.TXT_pwmrangetilt.TabIndex = 23; - this.TXT_pwmrangetilt.Text = "1000"; - // - // label8 - // - this.label8.AutoSize = true; - this.label8.Location = new System.Drawing.Point(43, 110); - this.label8.Name = "label8"; - this.label8.Size = new System.Drawing.Size(34, 13); - this.label8.TabIndex = 24; - this.label8.Text = "PWM"; - // - // label9 - // - this.label9.AutoSize = true; - this.label9.Location = new System.Drawing.Point(43, 186); - this.label9.Name = "label9"; - this.label9.Size = new System.Drawing.Size(34, 13); - this.label9.TabIndex = 25; - this.label9.Text = "PWM"; - // - // label10 - // - this.label10.AutoSize = true; - this.label10.Location = new System.Drawing.Point(45, 160); - this.label10.Name = "label10"; - this.label10.Size = new System.Drawing.Size(34, 13); - this.label10.TabIndex = 27; - this.label10.Text = "Angle"; - // - // label11 - // - this.label11.AutoSize = true; - this.label11.Location = new System.Drawing.Point(45, 84); - this.label11.Name = "label11"; - this.label11.Size = new System.Drawing.Size(34, 13); - this.label11.TabIndex = 26; - this.label11.Text = "Angle"; - // - // label12 - // - this.label12.AutoSize = true; - this.label12.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Bold, System.Drawing.GraphicsUnit.Point, ((byte)(0))); - this.label12.Location = new System.Drawing.Point(94, 40); - this.label12.Name = "label12"; - this.label12.Size = new System.Drawing.Size(403, 13); - this.label12.TabIndex = 28; - this.label12.Text = "Miss using this interface can cause servo damage, use with caution!!!"; - // - // BUT_connect - // - this.BUT_connect.Location = new System.Drawing.Point(476, 9); - this.BUT_connect.Name = "BUT_connect"; - this.BUT_connect.Size = new System.Drawing.Size(75, 23); - this.BUT_connect.TabIndex = 3; - this.BUT_connect.Text = "Connect"; - this.BUT_connect.UseVisualStyleBackColor = true; - this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click); - // - // LBL_pantrim - // - this.LBL_pantrim.AutoSize = true; - this.LBL_pantrim.Location = new System.Drawing.Point(326, 113); - this.LBL_pantrim.Name = "LBL_pantrim"; - this.LBL_pantrim.Size = new System.Drawing.Size(34, 13); - this.LBL_pantrim.TabIndex = 29; - this.LBL_pantrim.Text = "Angle"; - // - // LBL_tilttrim - // - this.LBL_tilttrim.AutoSize = true; - this.LBL_tilttrim.Location = new System.Drawing.Point(326, 190); - this.LBL_tilttrim.Name = "LBL_tilttrim"; - this.LBL_tilttrim.Size = new System.Drawing.Size(34, 13); - this.LBL_tilttrim.TabIndex = 30; - this.LBL_tilttrim.Text = "Angle"; - // - // Tracker - // - this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.LBL_tilttrim); - this.Controls.Add(this.LBL_pantrim); - this.Controls.Add(this.label12); - this.Controls.Add(this.label10); - this.Controls.Add(this.label11); - this.Controls.Add(this.label9); - this.Controls.Add(this.label8); - this.Controls.Add(this.TXT_pwmrangetilt); - this.Controls.Add(this.TXT_pwmrangepan); - this.Controls.Add(this.CHK_revtilt); - this.Controls.Add(this.CHK_revpan); - this.Controls.Add(this.label7); - this.Controls.Add(this.label2); - this.Controls.Add(this.label5); - this.Controls.Add(this.label6); - this.Controls.Add(this.TXT_tiltrange); - this.Controls.Add(this.TRK_tilttrim); - this.Controls.Add(this.label4); - this.Controls.Add(this.label3); - this.Controls.Add(this.TXT_panrange); - this.Controls.Add(this.TRK_pantrim); - this.Controls.Add(this.CMB_baudrate); - this.Controls.Add(this.BUT_connect); - this.Controls.Add(this.CMB_serialport); - this.Controls.Add(this.label1); - this.Controls.Add(this.CMB_interface); - this.Name = "Tracker"; - this.Size = new System.Drawing.Size(587, 212); - this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Tracker_FormClosing); - ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).EndInit(); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private System.Windows.Forms.ComboBox CMB_interface; - private System.Windows.Forms.Label label1; - private System.Windows.Forms.ComboBox CMB_baudrate; - private MyButton BUT_connect; - private System.Windows.Forms.ComboBox CMB_serialport; - private System.Windows.Forms.TrackBar TRK_pantrim; - private System.Windows.Forms.TextBox TXT_panrange; - private System.Windows.Forms.Label label3; - private System.Windows.Forms.Label label4; - private System.Windows.Forms.Label label5; - private System.Windows.Forms.Label label6; - private System.Windows.Forms.TextBox TXT_tiltrange; - private System.Windows.Forms.TrackBar TRK_tilttrim; - private System.Windows.Forms.Label label2; - private System.Windows.Forms.Label label7; - private System.Windows.Forms.CheckBox CHK_revpan; - private System.Windows.Forms.CheckBox CHK_revtilt; - private System.Windows.Forms.TextBox TXT_pwmrangepan; - private System.Windows.Forms.TextBox TXT_pwmrangetilt; - private System.Windows.Forms.Label label8; - private System.Windows.Forms.Label label9; - private System.Windows.Forms.Label label10; - private System.Windows.Forms.Label label11; - private System.Windows.Forms.Label label12; - private System.Windows.Forms.Label LBL_pantrim; - private System.Windows.Forms.Label LBL_tilttrim; - } +namespace ArdupilotMega.Antenna +{ + partial class Tracker + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Windows Form Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Tracker)); + this.CMB_interface = new System.Windows.Forms.ComboBox(); + this.label1 = new System.Windows.Forms.Label(); + this.CMB_baudrate = new System.Windows.Forms.ComboBox(); + this.CMB_serialport = new System.Windows.Forms.ComboBox(); + this.TRK_pantrim = new System.Windows.Forms.TrackBar(); + this.TXT_panrange = new System.Windows.Forms.TextBox(); + this.label3 = new System.Windows.Forms.Label(); + this.label4 = new System.Windows.Forms.Label(); + this.label5 = new System.Windows.Forms.Label(); + this.label6 = new System.Windows.Forms.Label(); + this.TXT_tiltrange = new System.Windows.Forms.TextBox(); + this.TRK_tilttrim = new System.Windows.Forms.TrackBar(); + this.label2 = new System.Windows.Forms.Label(); + this.label7 = new System.Windows.Forms.Label(); + this.CHK_revpan = new System.Windows.Forms.CheckBox(); + this.CHK_revtilt = new System.Windows.Forms.CheckBox(); + this.TXT_pwmrangepan = new System.Windows.Forms.TextBox(); + this.TXT_pwmrangetilt = new System.Windows.Forms.TextBox(); + this.label8 = new System.Windows.Forms.Label(); + this.label9 = new System.Windows.Forms.Label(); + this.label10 = new System.Windows.Forms.Label(); + this.label11 = new System.Windows.Forms.Label(); + this.label12 = new System.Windows.Forms.Label(); + this.BUT_connect = new ArdupilotMega.MyButton(); + this.LBL_pantrim = new System.Windows.Forms.Label(); + this.LBL_tilttrim = new System.Windows.Forms.Label(); + ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).BeginInit(); + this.SuspendLayout(); + // + // CMB_interface + // + this.CMB_interface.FormattingEnabled = true; + this.CMB_interface.Items.AddRange(new object[] { + resources.GetString("CMB_interface.Items"), + resources.GetString("CMB_interface.Items1")}); + resources.ApplyResources(this.CMB_interface, "CMB_interface"); + this.CMB_interface.Name = "CMB_interface"; + // + // label1 + // + resources.ApplyResources(this.label1, "label1"); + this.label1.Name = "label1"; + // + // CMB_baudrate + // + this.CMB_baudrate.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + this.CMB_baudrate.FormattingEnabled = true; + this.CMB_baudrate.Items.AddRange(new object[] { + resources.GetString("CMB_baudrate.Items"), + resources.GetString("CMB_baudrate.Items1"), + resources.GetString("CMB_baudrate.Items2"), + resources.GetString("CMB_baudrate.Items3"), + resources.GetString("CMB_baudrate.Items4"), + resources.GetString("CMB_baudrate.Items5"), + resources.GetString("CMB_baudrate.Items6"), + resources.GetString("CMB_baudrate.Items7")}); + resources.ApplyResources(this.CMB_baudrate, "CMB_baudrate"); + this.CMB_baudrate.Name = "CMB_baudrate"; + // + // CMB_serialport + // + this.CMB_serialport.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + this.CMB_serialport.FormattingEnabled = true; + resources.ApplyResources(this.CMB_serialport, "CMB_serialport"); + this.CMB_serialport.Name = "CMB_serialport"; + // + // TRK_pantrim + // + resources.ApplyResources(this.TRK_pantrim, "TRK_pantrim"); + this.TRK_pantrim.Maximum = 360; + this.TRK_pantrim.Minimum = -360; + this.TRK_pantrim.Name = "TRK_pantrim"; + this.TRK_pantrim.TickFrequency = 5; + this.TRK_pantrim.Scroll += new System.EventHandler(this.TRK_pantrim_Scroll); + // + // TXT_panrange + // + resources.ApplyResources(this.TXT_panrange, "TXT_panrange"); + this.TXT_panrange.Name = "TXT_panrange"; + this.TXT_panrange.TextChanged += new System.EventHandler(this.TXT_panrange_TextChanged); + // + // label3 + // + resources.ApplyResources(this.label3, "label3"); + this.label3.Name = "label3"; + // + // label4 + // + resources.ApplyResources(this.label4, "label4"); + this.label4.Name = "label4"; + // + // label5 + // + resources.ApplyResources(this.label5, "label5"); + this.label5.Name = "label5"; + // + // label6 + // + resources.ApplyResources(this.label6, "label6"); + this.label6.Name = "label6"; + // + // TXT_tiltrange + // + resources.ApplyResources(this.TXT_tiltrange, "TXT_tiltrange"); + this.TXT_tiltrange.Name = "TXT_tiltrange"; + this.TXT_tiltrange.TextChanged += new System.EventHandler(this.TXT_tiltrange_TextChanged); + // + // TRK_tilttrim + // + resources.ApplyResources(this.TRK_tilttrim, "TRK_tilttrim"); + this.TRK_tilttrim.Maximum = 180; + this.TRK_tilttrim.Minimum = -180; + this.TRK_tilttrim.Name = "TRK_tilttrim"; + this.TRK_tilttrim.TickFrequency = 5; + this.TRK_tilttrim.Scroll += new System.EventHandler(this.TRK_tilttrim_Scroll); + // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // + // label7 + // + resources.ApplyResources(this.label7, "label7"); + this.label7.Name = "label7"; + // + // CHK_revpan + // + resources.ApplyResources(this.CHK_revpan, "CHK_revpan"); + this.CHK_revpan.Name = "CHK_revpan"; + this.CHK_revpan.UseVisualStyleBackColor = true; + this.CHK_revpan.CheckedChanged += new System.EventHandler(this.CHK_revpan_CheckedChanged); + // + // CHK_revtilt + // + resources.ApplyResources(this.CHK_revtilt, "CHK_revtilt"); + this.CHK_revtilt.Name = "CHK_revtilt"; + this.CHK_revtilt.UseVisualStyleBackColor = true; + this.CHK_revtilt.CheckedChanged += new System.EventHandler(this.CHK_revtilt_CheckedChanged); + // + // TXT_pwmrangepan + // + resources.ApplyResources(this.TXT_pwmrangepan, "TXT_pwmrangepan"); + this.TXT_pwmrangepan.Name = "TXT_pwmrangepan"; + // + // TXT_pwmrangetilt + // + resources.ApplyResources(this.TXT_pwmrangetilt, "TXT_pwmrangetilt"); + this.TXT_pwmrangetilt.Name = "TXT_pwmrangetilt"; + // + // label8 + // + resources.ApplyResources(this.label8, "label8"); + this.label8.Name = "label8"; + // + // label9 + // + resources.ApplyResources(this.label9, "label9"); + this.label9.Name = "label9"; + // + // label10 + // + resources.ApplyResources(this.label10, "label10"); + this.label10.Name = "label10"; + // + // label11 + // + resources.ApplyResources(this.label11, "label11"); + this.label11.Name = "label11"; + // + // label12 + // + resources.ApplyResources(this.label12, "label12"); + this.label12.Name = "label12"; + // + // BUT_connect + // + resources.ApplyResources(this.BUT_connect, "BUT_connect"); + this.BUT_connect.Name = "BUT_connect"; + this.BUT_connect.UseVisualStyleBackColor = true; + this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click); + // + // LBL_pantrim + // + resources.ApplyResources(this.LBL_pantrim, "LBL_pantrim"); + this.LBL_pantrim.Name = "LBL_pantrim"; + // + // LBL_tilttrim + // + resources.ApplyResources(this.LBL_tilttrim, "LBL_tilttrim"); + this.LBL_tilttrim.Name = "LBL_tilttrim"; + // + // Tracker + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.LBL_tilttrim); + this.Controls.Add(this.LBL_pantrim); + this.Controls.Add(this.label12); + this.Controls.Add(this.label10); + this.Controls.Add(this.label11); + this.Controls.Add(this.label9); + this.Controls.Add(this.label8); + this.Controls.Add(this.TXT_pwmrangetilt); + this.Controls.Add(this.TXT_pwmrangepan); + this.Controls.Add(this.CHK_revtilt); + this.Controls.Add(this.CHK_revpan); + this.Controls.Add(this.label7); + this.Controls.Add(this.label2); + this.Controls.Add(this.label5); + this.Controls.Add(this.label6); + this.Controls.Add(this.TXT_tiltrange); + this.Controls.Add(this.TRK_tilttrim); + this.Controls.Add(this.label4); + this.Controls.Add(this.label3); + this.Controls.Add(this.TXT_panrange); + this.Controls.Add(this.TRK_pantrim); + this.Controls.Add(this.CMB_baudrate); + this.Controls.Add(this.BUT_connect); + this.Controls.Add(this.CMB_serialport); + this.Controls.Add(this.label1); + this.Controls.Add(this.CMB_interface); + this.Name = "Tracker"; + this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Tracker_FormClosing); + ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.ComboBox CMB_interface; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.ComboBox CMB_baudrate; + private MyButton BUT_connect; + private System.Windows.Forms.ComboBox CMB_serialport; + private System.Windows.Forms.TrackBar TRK_pantrim; + private System.Windows.Forms.TextBox TXT_panrange; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.Label label4; + private System.Windows.Forms.Label label5; + private System.Windows.Forms.Label label6; + private System.Windows.Forms.TextBox TXT_tiltrange; + private System.Windows.Forms.TrackBar TRK_tilttrim; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.Label label7; + private System.Windows.Forms.CheckBox CHK_revpan; + private System.Windows.Forms.CheckBox CHK_revtilt; + private System.Windows.Forms.TextBox TXT_pwmrangepan; + private System.Windows.Forms.TextBox TXT_pwmrangetilt; + private System.Windows.Forms.Label label8; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label12; + private System.Windows.Forms.Label LBL_pantrim; + private System.Windows.Forms.Label LBL_tilttrim; + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx index 7080a7d118..ee9137adcd 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx @@ -1,120 +1,830 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Maestro + + + ArduTracker + + + + 83, 10 + + + 121, 21 + + + + 0 + + + Maestro + + + CMB_interface + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 25 + + + True + + + 13, 13 + + + 49, 13 + + + 1 + + + Interface + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + 4800 + + + 9600 + + + 14400 + + + 19200 + + + 28800 + + + 38400 + + + 57600 + + + 115200 + + + 337, 9 + + + 121, 21 + + + 2 + + + CMB_baudrate + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + 210, 10 + + + 121, 21 + + + 1 + + + CMB_serialport + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + 153, 81 + + + 375, 45 + + + 5 + + + TRK_pantrim + + + System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 83, 81 + + + 64, 20 + + + 4 + + + 360 + + + TXT_panrange + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + True + + + 326, 65 + + + 27, 13 + + + 10 + + + Trim + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 18 + + + True + + + 83, 65 + + + 39, 13 + + + 11 + + + Range + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + True + + + 83, 141 + + + 39, 13 + + + 17 + + + Range + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + True + + + 326, 141 + + + 27, 13 + + + 16 + + + Trim + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 83, 157 + + + 64, 20 + + + 6 + + + 90 + + + TXT_tiltrange + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + 153, 157 + + + 375, 45 + + + 7 + + + TRK_tilttrim + + + System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + True + + + 12, 65 + + + 26, 13 + + + 18 + + + Pan + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + True + + + 12, 141 + + + 21, 13 + + + 19 + + + Tilt + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + True + + + 534, 83 + + + 46, 17 + + + 20 + + + Rev + + + CHK_revpan + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + True + + + 534, 159 + + + 46, 17 + + + 21 + + + Rev + + + CHK_revtilt + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + 83, 107 + + + 64, 20 + + + 22 + + + 1000 + + + TXT_pwmrangepan + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 83, 183 + + + 64, 20 + + + 23 + + + 1000 + + + TXT_pwmrangetilt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + True + + + 43, 110 + + + 34, 13 + + + 24 + + + PWM + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + True + + + 43, 186 + + + 34, 13 + + + 25 + + + PWM + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + True + + + 45, 160 + + + 34, 13 + + + 27 + + + Angle + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + True + + + 45, 84 + + + 34, 13 + + + 26 + + + Angle + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + True + + + Microsoft Sans Serif, 8.25pt, style=Bold + + + 94, 40 + + + 403, 13 + + + 28 + + + Miss using this interface can cause servo damage, use with caution!!! + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 476, 9 + + + 75, 23 + + + 3 + + + Connect + + + BUT_connect + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 22 + + + True + + + 326, 113 + + + 34, 13 + + + 29 + + + Angle + + + LBL_pantrim + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + 326, 190 + + + 34, 13 + + + 30 + + + Angle + + + LBL_tilttrim + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + True + + + 6, 13 + + + 587, 212 + + + Tracker + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.zh-Hans.resx new file mode 100644 index 0000000000..65b14041b3 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.zh-Hans.resx @@ -0,0 +1,208 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + 31, 13 + + + 接口 + + + 31, 13 + + + 微调 + + + 31, 13 + + + 范围 + + + 31, 13 + + + 范围 + + + 31, 13 + + + 微调 + + + 31, 13 + + + 旋转 + + + 31, 13 + + + 倾斜 + + + 50, 17 + + + 逆转 + + + 50, 17 + + + 逆转 + + + 31, 13 + + + 角度 + + + 31, 13 + + + 角度 + + + 275, 13 + + + 错误的接口可能导致舵机损坏。务必小心使用!!! + + + 连接 + + + 31, 13 + + + 角度 + + + 31, 13 + + + 角度 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 8a91b148d9..d51d37b3a7 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -546,6 +546,12 @@ Tracker.cs + + Tracker.cs + + + Camera.cs + BackstageView.cs @@ -748,6 +754,9 @@ MavlinkLog.cs + + 3DRradio.cs + RAW_Sensor.cs diff --git a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs index 3e6eb16e5d..a748b9749f 100644 --- a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs @@ -1,384 +1,384 @@ -namespace ArdupilotMega -{ - partial class Camera - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Windows Form Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Camera)); - this.num_agl = new System.Windows.Forms.NumericUpDown(); - this.label2 = new System.Windows.Forms.Label(); - this.num_focallength = new System.Windows.Forms.NumericUpDown(); - this.TXT_fovH = new System.Windows.Forms.TextBox(); - this.TXT_fovV = new System.Windows.Forms.TextBox(); - this.TXT_fovAV = new System.Windows.Forms.TextBox(); - this.TXT_fovAH = new System.Windows.Forms.TextBox(); - this.TXT_cmpixel = new System.Windows.Forms.TextBox(); - this.TXT_imgwidth = new System.Windows.Forms.TextBox(); - this.TXT_imgheight = new System.Windows.Forms.TextBox(); - this.label1 = new System.Windows.Forms.Label(); - this.label6 = new System.Windows.Forms.Label(); - this.label7 = new System.Windows.Forms.Label(); - this.label8 = new System.Windows.Forms.Label(); - this.label10 = new System.Windows.Forms.Label(); - this.label12 = new System.Windows.Forms.Label(); - this.label13 = new System.Windows.Forms.Label(); - this.label14 = new System.Windows.Forms.Label(); - this.label3 = new System.Windows.Forms.Label(); - this.label4 = new System.Windows.Forms.Label(); - this.TXT_sensheight = new System.Windows.Forms.TextBox(); - this.TXT_senswidth = new System.Windows.Forms.TextBox(); - this.label5 = new System.Windows.Forms.Label(); - this.num_overlap = new System.Windows.Forms.NumericUpDown(); - this.label15 = new System.Windows.Forms.Label(); - this.num_sidelap = new System.Windows.Forms.NumericUpDown(); - this.CHK_camdirection = new System.Windows.Forms.CheckBox(); - this.label9 = new System.Windows.Forms.Label(); - this.label11 = new System.Windows.Forms.Label(); - this.TXT_distacflphotos = new System.Windows.Forms.TextBox(); - this.TXT_distflphotos = new System.Windows.Forms.TextBox(); - this.CMB_camera = new System.Windows.Forms.ComboBox(); - this.BUT_save = new ArdupilotMega.MyButton(); - ((System.ComponentModel.ISupportInitialize)(this.num_agl)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.num_overlap)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.num_sidelap)).BeginInit(); - this.SuspendLayout(); - // - // num_agl - // - this.num_agl.Increment = new decimal(new int[] { - 10, - 0, - 0, - 0}); - resources.ApplyResources(this.num_agl, "num_agl"); - this.num_agl.Maximum = new decimal(new int[] { - 10000, - 0, - 0, - 0}); - this.num_agl.Name = "num_agl"; - this.num_agl.Value = new decimal(new int[] { - 200, - 0, - 0, - 0}); - this.num_agl.ValueChanged += new System.EventHandler(this.num_agl_ValueChanged); - // - // label2 - // - resources.ApplyResources(this.label2, "label2"); - this.label2.Name = "label2"; - // - // num_focallength - // - this.num_focallength.DecimalPlaces = 1; - this.num_focallength.Increment = new decimal(new int[] { - 1, - 0, - 0, - 65536}); - resources.ApplyResources(this.num_focallength, "num_focallength"); - this.num_focallength.Maximum = new decimal(new int[] { - 180, - 0, - 0, - 0}); - this.num_focallength.Minimum = new decimal(new int[] { - 1, - 0, - 0, - 0}); - this.num_focallength.Name = "num_focallength"; - this.num_focallength.Value = new decimal(new int[] { - 5, - 0, - 0, - 0}); - this.num_focallength.ValueChanged += new System.EventHandler(this.num_focallength_ValueChanged); - // - // TXT_fovH - // - resources.ApplyResources(this.TXT_fovH, "TXT_fovH"); - this.TXT_fovH.Name = "TXT_fovH"; - // - // TXT_fovV - // - resources.ApplyResources(this.TXT_fovV, "TXT_fovV"); - this.TXT_fovV.Name = "TXT_fovV"; - // - // TXT_fovAV - // - resources.ApplyResources(this.TXT_fovAV, "TXT_fovAV"); - this.TXT_fovAV.Name = "TXT_fovAV"; - // - // TXT_fovAH - // - resources.ApplyResources(this.TXT_fovAH, "TXT_fovAH"); - this.TXT_fovAH.Name = "TXT_fovAH"; - // - // TXT_cmpixel - // - resources.ApplyResources(this.TXT_cmpixel, "TXT_cmpixel"); - this.TXT_cmpixel.Name = "TXT_cmpixel"; - // - // TXT_imgwidth - // - resources.ApplyResources(this.TXT_imgwidth, "TXT_imgwidth"); - this.TXT_imgwidth.Name = "TXT_imgwidth"; - this.TXT_imgwidth.TextChanged += new System.EventHandler(this.TXT_imgwidth_TextChanged); - // - // TXT_imgheight - // - resources.ApplyResources(this.TXT_imgheight, "TXT_imgheight"); - this.TXT_imgheight.Name = "TXT_imgheight"; - this.TXT_imgheight.TextChanged += new System.EventHandler(this.TXT_imgheight_TextChanged); - // - // label1 - // - resources.ApplyResources(this.label1, "label1"); - this.label1.Name = "label1"; - // - // label6 - // - resources.ApplyResources(this.label6, "label6"); - this.label6.Name = "label6"; - // - // label7 - // - resources.ApplyResources(this.label7, "label7"); - this.label7.Name = "label7"; - // - // label8 - // - resources.ApplyResources(this.label8, "label8"); - this.label8.Name = "label8"; - // - // label10 - // - resources.ApplyResources(this.label10, "label10"); - this.label10.Name = "label10"; - // - // label12 - // - resources.ApplyResources(this.label12, "label12"); - this.label12.Name = "label12"; - // - // label13 - // - resources.ApplyResources(this.label13, "label13"); - this.label13.Name = "label13"; - // - // label14 - // - resources.ApplyResources(this.label14, "label14"); - this.label14.Name = "label14"; - // - // label3 - // - resources.ApplyResources(this.label3, "label3"); - this.label3.Name = "label3"; - // - // label4 - // - resources.ApplyResources(this.label4, "label4"); - this.label4.Name = "label4"; - // - // TXT_sensheight - // - resources.ApplyResources(this.TXT_sensheight, "TXT_sensheight"); - this.TXT_sensheight.Name = "TXT_sensheight"; - this.TXT_sensheight.TextChanged += new System.EventHandler(this.TXT_sensheight_TextChanged); - // - // TXT_senswidth - // - resources.ApplyResources(this.TXT_senswidth, "TXT_senswidth"); - this.TXT_senswidth.Name = "TXT_senswidth"; - this.TXT_senswidth.TextChanged += new System.EventHandler(this.TXT_senswidth_TextChanged); - // - // label5 - // - resources.ApplyResources(this.label5, "label5"); - this.label5.Name = "label5"; - // - // num_overlap - // - this.num_overlap.DecimalPlaces = 1; - resources.ApplyResources(this.num_overlap, "num_overlap"); - this.num_overlap.Name = "num_overlap"; - this.num_overlap.Value = new decimal(new int[] { - 60, - 0, - 0, - 0}); - this.num_overlap.ValueChanged += new System.EventHandler(this.num_overlap_ValueChanged); - // - // label15 - // - resources.ApplyResources(this.label15, "label15"); - this.label15.Name = "label15"; - // - // num_sidelap - // - this.num_sidelap.DecimalPlaces = 1; - resources.ApplyResources(this.num_sidelap, "num_sidelap"); - this.num_sidelap.Name = "num_sidelap"; - this.num_sidelap.Value = new decimal(new int[] { - 30, - 0, - 0, - 0}); - this.num_sidelap.ValueChanged += new System.EventHandler(this.num_sidelap_ValueChanged); - // - // CHK_camdirection - // - resources.ApplyResources(this.CHK_camdirection, "CHK_camdirection"); - this.CHK_camdirection.Checked = true; - this.CHK_camdirection.CheckState = System.Windows.Forms.CheckState.Checked; - this.CHK_camdirection.Name = "CHK_camdirection"; - this.CHK_camdirection.UseVisualStyleBackColor = true; - this.CHK_camdirection.CheckedChanged += new System.EventHandler(this.CHK_camdirection_CheckedChanged); - // - // label9 - // - resources.ApplyResources(this.label9, "label9"); - this.label9.Name = "label9"; - // - // label11 - // - resources.ApplyResources(this.label11, "label11"); - this.label11.Name = "label11"; - // - // TXT_distacflphotos - // - resources.ApplyResources(this.TXT_distacflphotos, "TXT_distacflphotos"); - this.TXT_distacflphotos.Name = "TXT_distacflphotos"; - // - // TXT_distflphotos - // - resources.ApplyResources(this.TXT_distflphotos, "TXT_distflphotos"); - this.TXT_distflphotos.Name = "TXT_distflphotos"; - // - // CMB_camera - // - this.CMB_camera.FormattingEnabled = true; - resources.ApplyResources(this.CMB_camera, "CMB_camera"); - this.CMB_camera.Name = "CMB_camera"; - this.CMB_camera.SelectedIndexChanged += new System.EventHandler(this.CMB_camera_SelectedIndexChanged); - // - // BUT_save - // - resources.ApplyResources(this.BUT_save, "BUT_save"); - this.BUT_save.Name = "BUT_save"; - this.BUT_save.UseVisualStyleBackColor = true; - this.BUT_save.Click += new System.EventHandler(this.BUT_save_Click); - // - // Camera - // - resources.ApplyResources(this, "$this"); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.BUT_save); - this.Controls.Add(this.CMB_camera); - this.Controls.Add(this.label9); - this.Controls.Add(this.label11); - this.Controls.Add(this.TXT_distacflphotos); - this.Controls.Add(this.TXT_distflphotos); - this.Controls.Add(this.CHK_camdirection); - this.Controls.Add(this.label15); - this.Controls.Add(this.num_sidelap); - this.Controls.Add(this.label5); - this.Controls.Add(this.num_overlap); - this.Controls.Add(this.label3); - this.Controls.Add(this.label4); - this.Controls.Add(this.TXT_sensheight); - this.Controls.Add(this.TXT_senswidth); - this.Controls.Add(this.label14); - this.Controls.Add(this.label13); - this.Controls.Add(this.label12); - this.Controls.Add(this.label10); - this.Controls.Add(this.label8); - this.Controls.Add(this.label7); - this.Controls.Add(this.label6); - this.Controls.Add(this.label1); - this.Controls.Add(this.TXT_imgheight); - this.Controls.Add(this.TXT_imgwidth); - this.Controls.Add(this.TXT_cmpixel); - this.Controls.Add(this.TXT_fovAV); - this.Controls.Add(this.TXT_fovAH); - this.Controls.Add(this.TXT_fovV); - this.Controls.Add(this.TXT_fovH); - this.Controls.Add(this.num_focallength); - this.Controls.Add(this.label2); - this.Controls.Add(this.num_agl); - this.Name = "Camera"; - this.Load += new System.EventHandler(this.Camera_Load); - ((System.ComponentModel.ISupportInitialize)(this.num_agl)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.num_overlap)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.num_sidelap)).EndInit(); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private System.Windows.Forms.NumericUpDown num_agl; - private System.Windows.Forms.Label label2; - private System.Windows.Forms.NumericUpDown num_focallength; - private System.Windows.Forms.TextBox TXT_fovH; - private System.Windows.Forms.TextBox TXT_fovV; - private System.Windows.Forms.TextBox TXT_fovAV; - private System.Windows.Forms.TextBox TXT_fovAH; - private System.Windows.Forms.TextBox TXT_cmpixel; - private System.Windows.Forms.TextBox TXT_imgwidth; - private System.Windows.Forms.TextBox TXT_imgheight; - private System.Windows.Forms.Label label1; - private System.Windows.Forms.Label label6; - private System.Windows.Forms.Label label7; - private System.Windows.Forms.Label label8; - private System.Windows.Forms.Label label10; - private System.Windows.Forms.Label label12; - private System.Windows.Forms.Label label13; - private System.Windows.Forms.Label label14; - private System.Windows.Forms.Label label3; - private System.Windows.Forms.Label label4; - private System.Windows.Forms.TextBox TXT_sensheight; - private System.Windows.Forms.TextBox TXT_senswidth; - private System.Windows.Forms.Label label5; - private System.Windows.Forms.NumericUpDown num_overlap; - private System.Windows.Forms.Label label15; - private System.Windows.Forms.NumericUpDown num_sidelap; - private System.Windows.Forms.CheckBox CHK_camdirection; - private System.Windows.Forms.Label label9; - private System.Windows.Forms.Label label11; - private System.Windows.Forms.TextBox TXT_distacflphotos; - private System.Windows.Forms.TextBox TXT_distflphotos; - private System.Windows.Forms.ComboBox CMB_camera; - private MyButton BUT_save; - } +namespace ArdupilotMega +{ + partial class Camera + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Windows Form Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Camera)); + this.num_agl = new System.Windows.Forms.NumericUpDown(); + this.label2 = new System.Windows.Forms.Label(); + this.num_focallength = new System.Windows.Forms.NumericUpDown(); + this.TXT_fovH = new System.Windows.Forms.TextBox(); + this.TXT_fovV = new System.Windows.Forms.TextBox(); + this.TXT_fovAV = new System.Windows.Forms.TextBox(); + this.TXT_fovAH = new System.Windows.Forms.TextBox(); + this.TXT_cmpixel = new System.Windows.Forms.TextBox(); + this.TXT_imgwidth = new System.Windows.Forms.TextBox(); + this.TXT_imgheight = new System.Windows.Forms.TextBox(); + this.label1 = new System.Windows.Forms.Label(); + this.label6 = new System.Windows.Forms.Label(); + this.label7 = new System.Windows.Forms.Label(); + this.label8 = new System.Windows.Forms.Label(); + this.label10 = new System.Windows.Forms.Label(); + this.label12 = new System.Windows.Forms.Label(); + this.label13 = new System.Windows.Forms.Label(); + this.label14 = new System.Windows.Forms.Label(); + this.label3 = new System.Windows.Forms.Label(); + this.label4 = new System.Windows.Forms.Label(); + this.TXT_sensheight = new System.Windows.Forms.TextBox(); + this.TXT_senswidth = new System.Windows.Forms.TextBox(); + this.label5 = new System.Windows.Forms.Label(); + this.num_overlap = new System.Windows.Forms.NumericUpDown(); + this.label15 = new System.Windows.Forms.Label(); + this.num_sidelap = new System.Windows.Forms.NumericUpDown(); + this.CHK_camdirection = new System.Windows.Forms.CheckBox(); + this.label9 = new System.Windows.Forms.Label(); + this.label11 = new System.Windows.Forms.Label(); + this.TXT_distacflphotos = new System.Windows.Forms.TextBox(); + this.TXT_distflphotos = new System.Windows.Forms.TextBox(); + this.CMB_camera = new System.Windows.Forms.ComboBox(); + this.BUT_save = new ArdupilotMega.MyButton(); + ((System.ComponentModel.ISupportInitialize)(this.num_agl)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_overlap)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_sidelap)).BeginInit(); + this.SuspendLayout(); + // + // num_agl + // + this.num_agl.Increment = new decimal(new int[] { + 10, + 0, + 0, + 0}); + resources.ApplyResources(this.num_agl, "num_agl"); + this.num_agl.Maximum = new decimal(new int[] { + 10000, + 0, + 0, + 0}); + this.num_agl.Name = "num_agl"; + this.num_agl.Value = new decimal(new int[] { + 200, + 0, + 0, + 0}); + this.num_agl.ValueChanged += new System.EventHandler(this.num_agl_ValueChanged); + // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // + // num_focallength + // + this.num_focallength.DecimalPlaces = 1; + this.num_focallength.Increment = new decimal(new int[] { + 1, + 0, + 0, + 65536}); + resources.ApplyResources(this.num_focallength, "num_focallength"); + this.num_focallength.Maximum = new decimal(new int[] { + 180, + 0, + 0, + 0}); + this.num_focallength.Minimum = new decimal(new int[] { + 1, + 0, + 0, + 0}); + this.num_focallength.Name = "num_focallength"; + this.num_focallength.Value = new decimal(new int[] { + 5, + 0, + 0, + 0}); + this.num_focallength.ValueChanged += new System.EventHandler(this.num_focallength_ValueChanged); + // + // TXT_fovH + // + resources.ApplyResources(this.TXT_fovH, "TXT_fovH"); + this.TXT_fovH.Name = "TXT_fovH"; + // + // TXT_fovV + // + resources.ApplyResources(this.TXT_fovV, "TXT_fovV"); + this.TXT_fovV.Name = "TXT_fovV"; + // + // TXT_fovAV + // + resources.ApplyResources(this.TXT_fovAV, "TXT_fovAV"); + this.TXT_fovAV.Name = "TXT_fovAV"; + // + // TXT_fovAH + // + resources.ApplyResources(this.TXT_fovAH, "TXT_fovAH"); + this.TXT_fovAH.Name = "TXT_fovAH"; + // + // TXT_cmpixel + // + resources.ApplyResources(this.TXT_cmpixel, "TXT_cmpixel"); + this.TXT_cmpixel.Name = "TXT_cmpixel"; + // + // TXT_imgwidth + // + resources.ApplyResources(this.TXT_imgwidth, "TXT_imgwidth"); + this.TXT_imgwidth.Name = "TXT_imgwidth"; + this.TXT_imgwidth.TextChanged += new System.EventHandler(this.TXT_imgwidth_TextChanged); + // + // TXT_imgheight + // + resources.ApplyResources(this.TXT_imgheight, "TXT_imgheight"); + this.TXT_imgheight.Name = "TXT_imgheight"; + this.TXT_imgheight.TextChanged += new System.EventHandler(this.TXT_imgheight_TextChanged); + // + // label1 + // + resources.ApplyResources(this.label1, "label1"); + this.label1.Name = "label1"; + // + // label6 + // + resources.ApplyResources(this.label6, "label6"); + this.label6.Name = "label6"; + // + // label7 + // + resources.ApplyResources(this.label7, "label7"); + this.label7.Name = "label7"; + // + // label8 + // + resources.ApplyResources(this.label8, "label8"); + this.label8.Name = "label8"; + // + // label10 + // + resources.ApplyResources(this.label10, "label10"); + this.label10.Name = "label10"; + // + // label12 + // + resources.ApplyResources(this.label12, "label12"); + this.label12.Name = "label12"; + // + // label13 + // + resources.ApplyResources(this.label13, "label13"); + this.label13.Name = "label13"; + // + // label14 + // + resources.ApplyResources(this.label14, "label14"); + this.label14.Name = "label14"; + // + // label3 + // + resources.ApplyResources(this.label3, "label3"); + this.label3.Name = "label3"; + // + // label4 + // + resources.ApplyResources(this.label4, "label4"); + this.label4.Name = "label4"; + // + // TXT_sensheight + // + resources.ApplyResources(this.TXT_sensheight, "TXT_sensheight"); + this.TXT_sensheight.Name = "TXT_sensheight"; + this.TXT_sensheight.TextChanged += new System.EventHandler(this.TXT_sensheight_TextChanged); + // + // TXT_senswidth + // + resources.ApplyResources(this.TXT_senswidth, "TXT_senswidth"); + this.TXT_senswidth.Name = "TXT_senswidth"; + this.TXT_senswidth.TextChanged += new System.EventHandler(this.TXT_senswidth_TextChanged); + // + // label5 + // + resources.ApplyResources(this.label5, "label5"); + this.label5.Name = "label5"; + // + // num_overlap + // + this.num_overlap.DecimalPlaces = 1; + resources.ApplyResources(this.num_overlap, "num_overlap"); + this.num_overlap.Name = "num_overlap"; + this.num_overlap.Value = new decimal(new int[] { + 70, + 0, + 0, + 0}); + this.num_overlap.ValueChanged += new System.EventHandler(this.num_overlap_ValueChanged); + // + // label15 + // + resources.ApplyResources(this.label15, "label15"); + this.label15.Name = "label15"; + // + // num_sidelap + // + this.num_sidelap.DecimalPlaces = 1; + resources.ApplyResources(this.num_sidelap, "num_sidelap"); + this.num_sidelap.Name = "num_sidelap"; + this.num_sidelap.Value = new decimal(new int[] { + 60, + 0, + 0, + 0}); + this.num_sidelap.ValueChanged += new System.EventHandler(this.num_sidelap_ValueChanged); + // + // CHK_camdirection + // + resources.ApplyResources(this.CHK_camdirection, "CHK_camdirection"); + this.CHK_camdirection.Checked = true; + this.CHK_camdirection.CheckState = System.Windows.Forms.CheckState.Checked; + this.CHK_camdirection.Name = "CHK_camdirection"; + this.CHK_camdirection.UseVisualStyleBackColor = true; + this.CHK_camdirection.CheckedChanged += new System.EventHandler(this.CHK_camdirection_CheckedChanged); + // + // label9 + // + resources.ApplyResources(this.label9, "label9"); + this.label9.Name = "label9"; + // + // label11 + // + resources.ApplyResources(this.label11, "label11"); + this.label11.Name = "label11"; + // + // TXT_distacflphotos + // + resources.ApplyResources(this.TXT_distacflphotos, "TXT_distacflphotos"); + this.TXT_distacflphotos.Name = "TXT_distacflphotos"; + // + // TXT_distflphotos + // + resources.ApplyResources(this.TXT_distflphotos, "TXT_distflphotos"); + this.TXT_distflphotos.Name = "TXT_distflphotos"; + // + // CMB_camera + // + this.CMB_camera.FormattingEnabled = true; + resources.ApplyResources(this.CMB_camera, "CMB_camera"); + this.CMB_camera.Name = "CMB_camera"; + this.CMB_camera.SelectedIndexChanged += new System.EventHandler(this.CMB_camera_SelectedIndexChanged); + // + // BUT_save + // + resources.ApplyResources(this.BUT_save, "BUT_save"); + this.BUT_save.Name = "BUT_save"; + this.BUT_save.UseVisualStyleBackColor = true; + this.BUT_save.Click += new System.EventHandler(this.BUT_save_Click); + // + // Camera + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.BUT_save); + this.Controls.Add(this.CMB_camera); + this.Controls.Add(this.label9); + this.Controls.Add(this.label11); + this.Controls.Add(this.TXT_distacflphotos); + this.Controls.Add(this.TXT_distflphotos); + this.Controls.Add(this.CHK_camdirection); + this.Controls.Add(this.label15); + this.Controls.Add(this.num_sidelap); + this.Controls.Add(this.label5); + this.Controls.Add(this.num_overlap); + this.Controls.Add(this.label3); + this.Controls.Add(this.label4); + this.Controls.Add(this.TXT_sensheight); + this.Controls.Add(this.TXT_senswidth); + this.Controls.Add(this.label14); + this.Controls.Add(this.label13); + this.Controls.Add(this.label12); + this.Controls.Add(this.label10); + this.Controls.Add(this.label8); + this.Controls.Add(this.label7); + this.Controls.Add(this.label6); + this.Controls.Add(this.label1); + this.Controls.Add(this.TXT_imgheight); + this.Controls.Add(this.TXT_imgwidth); + this.Controls.Add(this.TXT_cmpixel); + this.Controls.Add(this.TXT_fovAV); + this.Controls.Add(this.TXT_fovAH); + this.Controls.Add(this.TXT_fovV); + this.Controls.Add(this.TXT_fovH); + this.Controls.Add(this.num_focallength); + this.Controls.Add(this.label2); + this.Controls.Add(this.num_agl); + this.Name = "Camera"; + this.Load += new System.EventHandler(this.Camera_Load); + ((System.ComponentModel.ISupportInitialize)(this.num_agl)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_overlap)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_sidelap)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.NumericUpDown num_agl; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.NumericUpDown num_focallength; + private System.Windows.Forms.TextBox TXT_fovH; + private System.Windows.Forms.TextBox TXT_fovV; + private System.Windows.Forms.TextBox TXT_fovAV; + private System.Windows.Forms.TextBox TXT_fovAH; + private System.Windows.Forms.TextBox TXT_cmpixel; + private System.Windows.Forms.TextBox TXT_imgwidth; + private System.Windows.Forms.TextBox TXT_imgheight; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.Label label6; + private System.Windows.Forms.Label label7; + private System.Windows.Forms.Label label8; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.Label label12; + private System.Windows.Forms.Label label13; + private System.Windows.Forms.Label label14; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.Label label4; + private System.Windows.Forms.TextBox TXT_sensheight; + private System.Windows.Forms.TextBox TXT_senswidth; + private System.Windows.Forms.Label label5; + private System.Windows.Forms.NumericUpDown num_overlap; + private System.Windows.Forms.Label label15; + private System.Windows.Forms.NumericUpDown num_sidelap; + private System.Windows.Forms.CheckBox CHK_camdirection; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.TextBox TXT_distacflphotos; + private System.Windows.Forms.TextBox TXT_distflphotos; + private System.Windows.Forms.ComboBox CMB_camera; + private MyButton BUT_save; + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Camera.resx b/Tools/ArdupilotMegaPlanner/Camera.resx index f9635c451b..b5668d74bf 100644 --- a/Tools/ArdupilotMegaPlanner/Camera.resx +++ b/Tools/ArdupilotMegaPlanner/Camera.resx @@ -1,944 +1,944 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - 12, 38 - - - 64, 20 - - - - 1 - - - num_agl - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 32 - - - True - - - 82, 40 - - - 72, 13 - - - 4 - - - Height m (agl) - - - label2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 31 - - - 12, 64 - - - 64, 20 - - - 6 - - - num_focallength - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 30 - - - 361, 12 - - - 100, 20 - - - 10 - - - TXT_fovH - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 29 - - - 361, 39 - - - 100, 20 - - - 11 - - - TXT_fovV - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 28 - - - 361, 92 - - - 100, 20 - - - 14 - - - TXT_fovAV - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 26 - - - 361, 65 - - - 100, 20 - - - 13 - - - TXT_fovAH - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 27 - - - 361, 118 - - - 100, 20 - - - 16 - - - TXT_cmpixel - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 25 - - - 12, 90 - - - 64, 20 - - - 17 - - - 4608 - - - TXT_imgwidth - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 24 - - - 12, 116 - - - 64, 20 - - - 18 - - - 3456 - - - TXT_imgheight - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 23 - - - True - - - 82, 71 - - - 69, 13 - - - 19 - - - Focal Length - - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 22 - - - True - - - 298, 19 - - - 56, 13 - - - 21 - - - FOV H (m) - - - label6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 21 - - - True - - - 299, 72 - - - 45, 13 - - - 22 - - - Angle H - - - label7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 20 - - - True - - - 300, 99 - - - 44, 13 - - - 23 - - - Angle V - - - label8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 19 - - - True - - - 299, 46 - - - 55, 13 - - - 25 - - - FOV V (m) - - - label10 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 18 - - - True - - - 299, 125 - - - 50, 13 - - - 27 - - - CM/Pixel - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 17 - - - True - - - 82, 93 - - - 60, 13 - - - 28 - - - Pixel Width - - - label13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 16 - - - True - - - 82, 119 - - - 63, 13 - - - 29 - - - Pixel Height - - - label14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 15 - - - True - - - 82, 171 - - - 74, 13 - - - 33 - - - Sensor Height - - - label3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 11 - - - True - - - 82, 145 - - - 71, 13 - - - 32 - - - Sensor Width - - - label4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 12 - - - 12, 168 - - - 64, 20 - - - 31 - - - 4.62 - - - TXT_sensheight - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 13 - - - 12, 142 - - - 64, 20 - - - 30 - - - 6.16 - - - TXT_senswidth - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 14 - - - True - - - 82, 201 - - - 44, 13 - - - 35 - - - Overlap - - - label5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 9 - - - 12, 194 - - - 64, 20 - - - 34 - - - num_overlap - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - - True - - - 82, 227 - - - 42, 13 - - - 37 - - - Sidelap - - - label15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - 12, 220 - - - 64, 20 - - - 36 - - - num_sidelap - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 8 - - - True - - - 13, 247 - - - 150, 17 - - - 38 - - - Camera top facing forward - - - CHK_camdirection - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - True - - - 261, 198 - - - 86, 13 - - - 42 - - - Across Flight line - - - label9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - True - - - 261, 171 - - - 94, 13 - - - 41 - - - Flight line distance - - - label11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - - - 361, 195 - - - 100, 20 - - - 40 - - - TXT_distacflphotos - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 4 - - - 361, 168 - - - 100, 20 - - - 39 - - - TXT_distflphotos - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - 13, 13 - - - 143, 21 - - - 43 - - - CMB_camera - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 1 - - - 163, 10 - - - 75, 23 - - - 44 - - - Save - - - BUT_save - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc - - - $this - - - 0 - - - True - - - 6, 13 - - - 473, 275 - - - Camera - - - Camera - - - System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + 12, 38 + + + 64, 20 + + + + 1 + + + num_agl + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 32 + + + True + + + 82, 40 + + + 72, 13 + + + 4 + + + Height m (agl) + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 31 + + + 12, 64 + + + 64, 20 + + + 6 + + + num_focallength + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 30 + + + 361, 12 + + + 100, 20 + + + 10 + + + TXT_fovH + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 29 + + + 361, 39 + + + 100, 20 + + + 11 + + + TXT_fovV + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 28 + + + 361, 92 + + + 100, 20 + + + 14 + + + TXT_fovAV + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 26 + + + 361, 65 + + + 100, 20 + + + 13 + + + TXT_fovAH + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 27 + + + 361, 118 + + + 100, 20 + + + 16 + + + TXT_cmpixel + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 25 + + + 12, 90 + + + 64, 20 + + + 17 + + + 4608 + + + TXT_imgwidth + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + 12, 116 + + + 64, 20 + + + 18 + + + 3456 + + + TXT_imgheight + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + True + + + 82, 71 + + + 69, 13 + + + 19 + + + Focal Length + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + True + + + 298, 19 + + + 56, 13 + + + 21 + + + FOV H (m) + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + True + + + 299, 72 + + + 45, 13 + + + 22 + + + Angle H + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + True + + + 300, 99 + + + 44, 13 + + + 23 + + + Angle V + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + True + + + 299, 46 + + + 55, 13 + + + 25 + + + FOV V (m) + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 18 + + + True + + + 299, 125 + + + 50, 13 + + + 27 + + + CM/Pixel + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + True + + + 82, 93 + + + 60, 13 + + + 28 + + + Pixel Width + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + True + + + 82, 119 + + + 63, 13 + + + 29 + + + Pixel Height + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + True + + + 82, 171 + + + 74, 13 + + + 33 + + + Sensor Height + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + True + + + 82, 145 + + + 71, 13 + + + 32 + + + Sensor Width + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + 12, 168 + + + 64, 20 + + + 31 + + + 4.62 + + + TXT_sensheight + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + 12, 142 + + + 64, 20 + + + 30 + + + 6.16 + + + TXT_senswidth + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + True + + + 82, 201 + + + 44, 13 + + + 35 + + + Overlap + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + 12, 194 + + + 64, 20 + + + 34 + + + num_overlap + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + True + + + 82, 227 + + + 42, 13 + + + 37 + + + Sidelap + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + 12, 220 + + + 64, 20 + + + 36 + + + num_sidelap + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + True + + + 13, 247 + + + 150, 17 + + + 38 + + + Camera top facing forward + + + CHK_camdirection + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + True + + + 261, 198 + + + 86, 13 + + + 42 + + + Across Flight line + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + True + + + 261, 171 + + + 94, 13 + + + 41 + + + Flight line distance + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + 361, 195 + + + 100, 20 + + + 40 + + + TXT_distacflphotos + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + 361, 168 + + + 100, 20 + + + 39 + + + TXT_distflphotos + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + 13, 13 + + + 143, 21 + + + 43 + + + CMB_camera + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + 163, 10 + + + 75, 23 + + + 44 + + + Save + + + BUT_save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + + + True + + + 6, 13 + + + 473, 275 + + + Camera + + + Camera + + + 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/Camera.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/Camera.zh-Hans.resx new file mode 100644 index 0000000000..b19968c3d9 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Camera.zh-Hans.resx @@ -0,0 +1,208 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + 52, 13 + + + 航高 (米) + + + 31, 13 + + + 焦距 + + + 278, 19 + + + 76, 13 + + + 水平视野 (米) + + + 55, 13 + + + 水平视角 + + + 55, 13 + + + 垂直视角 + + + 278, 46 + + + 76, 13 + + + 垂直视野 (米) + + + 55, 13 + + + 像素宽度 + + + 55, 13 + + + 像素高度 + + + 67, 13 + + + 传感器高度 + + + 67, 13 + + + 传感器宽度 + + + 55, 13 + + + 前后重叠 + + + 55, 13 + + + 两侧重叠 + + + 98, 17 + + + 相机顶部朝前 + + + 保存 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index 0967c9ccec..6ef337178a 100644 --- a/Tools/ArdupilotMegaPlanner/Common.cs +++ b/Tools/ArdupilotMegaPlanner/Common.cs @@ -132,6 +132,41 @@ namespace ArdupilotMega 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); // anti NaN + try + { + + float desired_lead_dist = 100; + + float alpha = (desired_lead_dist / MainV2.cs.radius) * rad2deg; + + if (MainV2.cs.radius < 0) + { + // fixme + + float p1 = (float)Math.Cos((cog) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + float p2 = (float)Math.Sin((cog) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + g.DrawArc(new Pen(Color.HotPink, 2), p1, p2, Math.Abs(MainV2.cs.radius) * 2, Math.Abs(MainV2.cs.radius) * 2, cog, alpha); + + } + + else + { + // correct + + float p1 = (float)Math.Cos((cog - 180) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + float p2 = (float)Math.Sin((cog - 180) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + g.DrawArc(new Pen(Color.HotPink, 2), -p1, -p2, MainV2.cs.radius * 2, MainV2.cs.radius * 2, cog - 180, alpha); + } + + } + + catch { } + + try { g.RotateTransform(heading); } catch{} diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index e4d083d322..ffd2da68ef 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -81,6 +81,8 @@ namespace ArdupilotMega // calced turn rate public float turnrate { get { if (groundspeed <= 1) return 0; return (roll * 9.8f) / groundspeed; } } + // turn radius + public float radius { get { if (groundspeed <= 1) return 0; return ((groundspeed * groundspeed)/(float)(9.8f*Math.Tan(roll * deg2rad))); } } //radio public float ch1in { get; set; } @@ -533,6 +535,9 @@ namespace ArdupilotMega case (byte)(100 + Common.ac2modes.APPROACH): mode = EnumTranslator.GetDisplayText(Common.ac2modes.APPROACH); break; + case (byte)(100 + Common.ac2modes.APPROACH): + mode = "APPROACH"; + break; case (byte)(100 + Common.ac2modes.POSITION): mode = EnumTranslator.GetDisplayText(Common.ac2modes.POSITION); break; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs index f34863ea54..a67ec30bdb 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs @@ -29,6 +29,7 @@ private void InitializeComponent() { this.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigArducopter)); this.myLabel3 = new ArdupilotMega.MyLabel(); this.TUNE_LOW = new System.Windows.Forms.NumericUpDown(); this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown(); @@ -180,35 +181,25 @@ // // myLabel3 // - this.myLabel3.Location = new System.Drawing.Point(540, 302); + resources.ApplyResources(this.myLabel3, "myLabel3"); this.myLabel3.Name = "myLabel3"; this.myLabel3.resize = false; - this.myLabel3.Size = new System.Drawing.Size(29, 23); - this.myLabel3.TabIndex = 42; - this.myLabel3.Text = "Min"; // // TUNE_LOW // - this.TUNE_LOW.Location = new System.Drawing.Point(575, 305); + resources.ApplyResources(this.TUNE_LOW, "TUNE_LOW"); this.TUNE_LOW.Name = "TUNE_LOW"; - this.TUNE_LOW.Size = new System.Drawing.Size(51, 20); - this.TUNE_LOW.TabIndex = 41; // // TUNE_HIGH // - this.TUNE_HIGH.Location = new System.Drawing.Point(665, 305); + resources.ApplyResources(this.TUNE_HIGH, "TUNE_HIGH"); this.TUNE_HIGH.Name = "TUNE_HIGH"; - this.TUNE_HIGH.Size = new System.Drawing.Size(46, 20); - this.TUNE_HIGH.TabIndex = 40; // // myLabel2 // - this.myLabel2.Location = new System.Drawing.Point(540, 277); + resources.ApplyResources(this.myLabel2, "myLabel2"); this.myLabel2.Name = "myLabel2"; this.myLabel2.resize = false; - this.myLabel2.Size = new System.Drawing.Size(53, 23); - this.myLabel2.TabIndex = 39; - this.myLabel2.Text = "Ch6 Opt"; // // TUNE // @@ -216,41 +207,36 @@ this.TUNE.DropDownWidth = 150; this.TUNE.FormattingEnabled = true; this.TUNE.Items.AddRange(new object[] { - "CH6_NONE", - "CH6_STABILIZE_KP", - "CH6_STABILIZE_KI", - "CH6_YAW_KP", - "CH6_RATE_KP", - "CH6_RATE_KI", - "CH6_YAW_RATE_KP", - "CH6_THROTTLE_KP", - "CH6_TOP_BOTTOM_RATIO", - "CH6_RELAY", - "CH6_TRAVERSE_SPEED", - "CH6_NAV_P", - "CH6_LOITER_P", - "CH6_HELI_EXTERNAL_GYRO", - "CH6_THR_HOLD_KP", - "CH6_Z_GAIN", - "CH6_DAMP", - "CH6_OPTFLOW_KP", - "CH6_OPTFLOW_KI", - "CH6_OPTFLOW_KD", - "CH6_NAV_I", - "CH6_RATE_KD"}); - this.TUNE.Location = new System.Drawing.Point(599, 277); + resources.GetString("TUNE.Items"), + resources.GetString("TUNE.Items1"), + resources.GetString("TUNE.Items2"), + resources.GetString("TUNE.Items3"), + resources.GetString("TUNE.Items4"), + resources.GetString("TUNE.Items5"), + resources.GetString("TUNE.Items6"), + resources.GetString("TUNE.Items7"), + resources.GetString("TUNE.Items8"), + resources.GetString("TUNE.Items9"), + resources.GetString("TUNE.Items10"), + resources.GetString("TUNE.Items11"), + resources.GetString("TUNE.Items12"), + resources.GetString("TUNE.Items13"), + resources.GetString("TUNE.Items14"), + resources.GetString("TUNE.Items15"), + resources.GetString("TUNE.Items16"), + resources.GetString("TUNE.Items17"), + resources.GetString("TUNE.Items18"), + resources.GetString("TUNE.Items19"), + resources.GetString("TUNE.Items20"), + resources.GetString("TUNE.Items21")}); + resources.ApplyResources(this.TUNE, "TUNE"); this.TUNE.Name = "TUNE"; - this.TUNE.Size = new System.Drawing.Size(112, 21); - this.TUNE.TabIndex = 38; // // myLabel1 // - this.myLabel1.Location = new System.Drawing.Point(540, 329); + resources.ApplyResources(this.myLabel1, "myLabel1"); this.myLabel1.Name = "myLabel1"; this.myLabel1.resize = false; - this.myLabel1.Size = new System.Drawing.Size(53, 23); - this.myLabel1.TabIndex = 37; - this.myLabel1.Text = "Ch7 Opt"; // // CH7_OPT // @@ -258,18 +244,16 @@ this.CH7_OPT.DropDownWidth = 150; this.CH7_OPT.FormattingEnabled = true; this.CH7_OPT.Items.AddRange(new object[] { - "Do Nothing", - "", - "", - "Simple Mode", - "RTL", - "", - "", - "Save WP"}); - this.CH7_OPT.Location = new System.Drawing.Point(599, 329); + resources.GetString("CH7_OPT.Items"), + resources.GetString("CH7_OPT.Items1"), + resources.GetString("CH7_OPT.Items2"), + resources.GetString("CH7_OPT.Items3"), + resources.GetString("CH7_OPT.Items4"), + resources.GetString("CH7_OPT.Items5"), + resources.GetString("CH7_OPT.Items6"), + resources.GetString("CH7_OPT.Items7")}); + resources.ApplyResources(this.CH7_OPT, "CH7_OPT"); this.CH7_OPT.Name = "CH7_OPT"; - this.CH7_OPT.Size = new System.Drawing.Size(112, 21); - this.CH7_OPT.TabIndex = 36; // // groupBox5 // @@ -281,88 +265,56 @@ this.groupBox5.Controls.Add(this.label20); this.groupBox5.Controls.Add(this.THR_RATE_P); this.groupBox5.Controls.Add(this.label25); - this.groupBox5.Location = new System.Drawing.Point(12, 267); + resources.ApplyResources(this.groupBox5, "groupBox5"); this.groupBox5.Name = "groupBox5"; - this.groupBox5.Size = new System.Drawing.Size(170, 110); - this.groupBox5.TabIndex = 35; this.groupBox5.TabStop = false; - this.groupBox5.Text = "Throttle Rate"; // // THR_RATE_D // - this.THR_RATE_D.Location = new System.Drawing.Point(80, 60); + resources.ApplyResources(this.THR_RATE_D, "THR_RATE_D"); this.THR_RATE_D.Name = "THR_RATE_D"; - this.THR_RATE_D.Size = new System.Drawing.Size(78, 20); - this.THR_RATE_D.TabIndex = 14; // // label29 // - this.label29.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label29.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label29, "label29"); this.label29.Name = "label29"; - this.label29.Size = new System.Drawing.Size(10, 13); - this.label29.TabIndex = 15; - this.label29.Text = "D"; // // label14 // - this.label14.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label14.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; - this.label14.Size = new System.Drawing.Size(65, 13); - this.label14.TabIndex = 16; - this.label14.Text = "IMAX"; // // THR_RATE_IMAX // - this.THR_RATE_IMAX.Location = new System.Drawing.Point(80, 83); + resources.ApplyResources(this.THR_RATE_IMAX, "THR_RATE_IMAX"); this.THR_RATE_IMAX.Name = "THR_RATE_IMAX"; - this.THR_RATE_IMAX.Size = new System.Drawing.Size(78, 20); - this.THR_RATE_IMAX.TabIndex = 11; // // THR_RATE_I // - this.THR_RATE_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.THR_RATE_I, "THR_RATE_I"); this.THR_RATE_I.Name = "THR_RATE_I"; - this.THR_RATE_I.Size = new System.Drawing.Size(78, 20); - this.THR_RATE_I.TabIndex = 7; // // label20 // - this.label20.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label20.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; - this.label20.Size = new System.Drawing.Size(10, 13); - this.label20.TabIndex = 14; - this.label20.Text = "I"; // // THR_RATE_P // - this.THR_RATE_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.THR_RATE_P, "THR_RATE_P"); this.THR_RATE_P.Name = "THR_RATE_P"; - this.THR_RATE_P.Size = new System.Drawing.Size(78, 20); - this.THR_RATE_P.TabIndex = 5; // // label25 // - this.label25.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label25.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; - this.label25.Size = new System.Drawing.Size(14, 13); - this.label25.TabIndex = 15; - this.label25.Text = "P"; // // CHK_lockrollpitch // - this.CHK_lockrollpitch.AutoSize = true; + resources.ApplyResources(this.CHK_lockrollpitch, "CHK_lockrollpitch"); this.CHK_lockrollpitch.Checked = true; this.CHK_lockrollpitch.CheckState = System.Windows.Forms.CheckState.Checked; - this.CHK_lockrollpitch.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_lockrollpitch.Location = new System.Drawing.Point(9, 247); this.CHK_lockrollpitch.Name = "CHK_lockrollpitch"; - this.CHK_lockrollpitch.Size = new System.Drawing.Size(154, 17); - this.CHK_lockrollpitch.TabIndex = 34; - this.CHK_lockrollpitch.Text = "Lock Pitch and Roll Values"; this.CHK_lockrollpitch.UseVisualStyleBackColor = true; // // groupBox4 @@ -377,119 +329,77 @@ this.groupBox4.Controls.Add(this.label15); this.groupBox4.Controls.Add(this.NAV_LAT_P); this.groupBox4.Controls.Add(this.label16); - this.groupBox4.Location = new System.Drawing.Point(540, 133); + resources.ApplyResources(this.groupBox4, "groupBox4"); this.groupBox4.Name = "groupBox4"; - this.groupBox4.Size = new System.Drawing.Size(170, 131); - this.groupBox4.TabIndex = 24; this.groupBox4.TabStop = false; - this.groupBox4.Text = "Nav WP"; // // NAV_LAT_D // - this.NAV_LAT_D.Location = new System.Drawing.Point(80, 60); + resources.ApplyResources(this.NAV_LAT_D, "NAV_LAT_D"); this.NAV_LAT_D.Name = "NAV_LAT_D"; - this.NAV_LAT_D.Size = new System.Drawing.Size(78, 20); - this.NAV_LAT_D.TabIndex = 18; // // label27 // - this.label27.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label27.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label27, "label27"); this.label27.Name = "label27"; - this.label27.Size = new System.Drawing.Size(10, 13); - this.label27.TabIndex = 19; - this.label27.Text = "D"; // // WP_SPEED_MAX // - this.WP_SPEED_MAX.Location = new System.Drawing.Point(80, 107); + resources.ApplyResources(this.WP_SPEED_MAX, "WP_SPEED_MAX"); this.WP_SPEED_MAX.Name = "WP_SPEED_MAX"; - this.WP_SPEED_MAX.Size = new System.Drawing.Size(78, 20); - this.WP_SPEED_MAX.TabIndex = 16; // // label9 // - this.label9.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label9.Location = new System.Drawing.Point(6, 110); + resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; - this.label9.Size = new System.Drawing.Size(54, 13); - this.label9.TabIndex = 17; - this.label9.Text = "m/s"; // // NAV_LAT_IMAX // - this.NAV_LAT_IMAX.Location = new System.Drawing.Point(80, 84); + resources.ApplyResources(this.NAV_LAT_IMAX, "NAV_LAT_IMAX"); this.NAV_LAT_IMAX.Name = "NAV_LAT_IMAX"; - this.NAV_LAT_IMAX.Size = new System.Drawing.Size(78, 20); - this.NAV_LAT_IMAX.TabIndex = 11; // // label13 // - this.label13.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label13.Location = new System.Drawing.Point(6, 87); + resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; - this.label13.Size = new System.Drawing.Size(65, 13); - this.label13.TabIndex = 12; - this.label13.Text = "IMAX"; // // NAV_LAT_I // - this.NAV_LAT_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.NAV_LAT_I, "NAV_LAT_I"); this.NAV_LAT_I.Name = "NAV_LAT_I"; - this.NAV_LAT_I.Size = new System.Drawing.Size(78, 20); - this.NAV_LAT_I.TabIndex = 7; // // label15 // - this.label15.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label15.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; - this.label15.Size = new System.Drawing.Size(10, 13); - this.label15.TabIndex = 14; - this.label15.Text = "I"; // // NAV_LAT_P // - this.NAV_LAT_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.NAV_LAT_P, "NAV_LAT_P"); this.NAV_LAT_P.Name = "NAV_LAT_P"; - this.NAV_LAT_P.Size = new System.Drawing.Size(78, 20); - this.NAV_LAT_P.TabIndex = 5; // // label16 // - this.label16.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label16.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; - this.label16.Size = new System.Drawing.Size(14, 13); - this.label16.TabIndex = 15; - this.label16.Text = "P"; // // groupBox6 // this.groupBox6.Controls.Add(this.XTRK_GAIN_SC1); this.groupBox6.Controls.Add(this.label18); - this.groupBox6.Location = new System.Drawing.Point(364, 267); + resources.ApplyResources(this.groupBox6, "groupBox6"); this.groupBox6.Name = "groupBox6"; - this.groupBox6.Size = new System.Drawing.Size(170, 43); - this.groupBox6.TabIndex = 25; this.groupBox6.TabStop = false; - this.groupBox6.Text = "Crosstrack Correction"; // // XTRK_GAIN_SC1 // - this.XTRK_GAIN_SC1.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.XTRK_GAIN_SC1, "XTRK_GAIN_SC1"); this.XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC1"; - this.XTRK_GAIN_SC1.Size = new System.Drawing.Size(78, 20); - this.XTRK_GAIN_SC1.TabIndex = 5; // // label18 // - this.label18.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label18.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label18, "label18"); this.label18.Name = "label18"; - this.label18.Size = new System.Drawing.Size(38, 13); - this.label18.TabIndex = 15; - this.label18.Text = "Gain"; // // groupBox7 // @@ -499,60 +409,39 @@ this.groupBox7.Controls.Add(this.label21); this.groupBox7.Controls.Add(this.THR_ALT_P); this.groupBox7.Controls.Add(this.label22); - this.groupBox7.Location = new System.Drawing.Point(188, 267); + resources.ApplyResources(this.groupBox7, "groupBox7"); this.groupBox7.Name = "groupBox7"; - this.groupBox7.Size = new System.Drawing.Size(170, 110); - this.groupBox7.TabIndex = 26; this.groupBox7.TabStop = false; - this.groupBox7.Text = "Altitude Hold"; // // THR_ALT_IMAX // - this.THR_ALT_IMAX.Location = new System.Drawing.Point(80, 63); + resources.ApplyResources(this.THR_ALT_IMAX, "THR_ALT_IMAX"); this.THR_ALT_IMAX.Name = "THR_ALT_IMAX"; - this.THR_ALT_IMAX.Size = new System.Drawing.Size(78, 20); - this.THR_ALT_IMAX.TabIndex = 11; // // label19 // - this.label19.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label19.Location = new System.Drawing.Point(6, 66); + resources.ApplyResources(this.label19, "label19"); this.label19.Name = "label19"; - this.label19.Size = new System.Drawing.Size(65, 13); - this.label19.TabIndex = 12; - this.label19.Text = "IMAX"; // // THR_ALT_I // - this.THR_ALT_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.THR_ALT_I, "THR_ALT_I"); this.THR_ALT_I.Name = "THR_ALT_I"; - this.THR_ALT_I.Size = new System.Drawing.Size(78, 20); - this.THR_ALT_I.TabIndex = 7; // // label21 // - this.label21.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label21.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; - this.label21.Size = new System.Drawing.Size(10, 13); - this.label21.TabIndex = 14; - this.label21.Text = "I"; // // THR_ALT_P // - this.THR_ALT_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.THR_ALT_P, "THR_ALT_P"); this.THR_ALT_P.Name = "THR_ALT_P"; - this.THR_ALT_P.Size = new System.Drawing.Size(78, 20); - this.THR_ALT_P.TabIndex = 5; // // label22 // - this.label22.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label22.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; - this.label22.Size = new System.Drawing.Size(14, 13); - this.label22.TabIndex = 15; - this.label22.Text = "P"; // // groupBox19 // @@ -562,60 +451,39 @@ this.groupBox19.Controls.Add(this.label30); this.groupBox19.Controls.Add(this.HLD_LAT_P); this.groupBox19.Controls.Add(this.label31); - this.groupBox19.Location = new System.Drawing.Point(537, 13); + resources.ApplyResources(this.groupBox19, "groupBox19"); this.groupBox19.Name = "groupBox19"; - this.groupBox19.Size = new System.Drawing.Size(170, 95); - this.groupBox19.TabIndex = 27; this.groupBox19.TabStop = false; - this.groupBox19.Text = "Loiter"; // // HLD_LAT_IMAX // - this.HLD_LAT_IMAX.Location = new System.Drawing.Point(80, 61); + resources.ApplyResources(this.HLD_LAT_IMAX, "HLD_LAT_IMAX"); this.HLD_LAT_IMAX.Name = "HLD_LAT_IMAX"; - this.HLD_LAT_IMAX.Size = new System.Drawing.Size(78, 20); - this.HLD_LAT_IMAX.TabIndex = 11; // // label28 // - this.label28.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label28.Location = new System.Drawing.Point(6, 64); + resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; - this.label28.Size = new System.Drawing.Size(65, 13); - this.label28.TabIndex = 12; - this.label28.Text = "IMAX"; // // HLD_LAT_I // - this.HLD_LAT_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.HLD_LAT_I, "HLD_LAT_I"); this.HLD_LAT_I.Name = "HLD_LAT_I"; - this.HLD_LAT_I.Size = new System.Drawing.Size(78, 20); - this.HLD_LAT_I.TabIndex = 7; // // label30 // - this.label30.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label30.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; - this.label30.Size = new System.Drawing.Size(10, 13); - this.label30.TabIndex = 14; - this.label30.Text = "I"; // // HLD_LAT_P // - this.HLD_LAT_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.HLD_LAT_P, "HLD_LAT_P"); this.HLD_LAT_P.Name = "HLD_LAT_P"; - this.HLD_LAT_P.Size = new System.Drawing.Size(78, 20); - this.HLD_LAT_P.TabIndex = 5; // // label31 // - this.label31.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label31.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label31, "label31"); this.label31.Name = "label31"; - this.label31.Size = new System.Drawing.Size(14, 13); - this.label31.TabIndex = 15; - this.label31.Text = "P"; // // groupBox20 // @@ -625,60 +493,39 @@ this.groupBox20.Controls.Add(this.label34); this.groupBox20.Controls.Add(this.STB_YAW_P); this.groupBox20.Controls.Add(this.label35); - this.groupBox20.Location = new System.Drawing.Point(364, 13); + resources.ApplyResources(this.groupBox20, "groupBox20"); this.groupBox20.Name = "groupBox20"; - this.groupBox20.Size = new System.Drawing.Size(170, 95); - this.groupBox20.TabIndex = 28; this.groupBox20.TabStop = false; - this.groupBox20.Text = "Stabilize Yaw"; // // STB_YAW_IMAX // - this.STB_YAW_IMAX.Location = new System.Drawing.Point(80, 63); + resources.ApplyResources(this.STB_YAW_IMAX, "STB_YAW_IMAX"); this.STB_YAW_IMAX.Name = "STB_YAW_IMAX"; - this.STB_YAW_IMAX.Size = new System.Drawing.Size(78, 20); - this.STB_YAW_IMAX.TabIndex = 11; // // label32 // - this.label32.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label32.Location = new System.Drawing.Point(6, 66); + resources.ApplyResources(this.label32, "label32"); this.label32.Name = "label32"; - this.label32.Size = new System.Drawing.Size(65, 13); - this.label32.TabIndex = 12; - this.label32.Text = "IMAX "; // // STB_YAW_I // - this.STB_YAW_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.STB_YAW_I, "STB_YAW_I"); this.STB_YAW_I.Name = "STB_YAW_I"; - this.STB_YAW_I.Size = new System.Drawing.Size(78, 20); - this.STB_YAW_I.TabIndex = 7; // // label34 // - this.label34.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label34.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label34, "label34"); this.label34.Name = "label34"; - this.label34.Size = new System.Drawing.Size(10, 13); - this.label34.TabIndex = 14; - this.label34.Text = "I"; // // STB_YAW_P // - this.STB_YAW_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.STB_YAW_P, "STB_YAW_P"); this.STB_YAW_P.Name = "STB_YAW_P"; - this.STB_YAW_P.Size = new System.Drawing.Size(78, 20); - this.STB_YAW_P.TabIndex = 5; // // label35 // - this.label35.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label35.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label35, "label35"); this.label35.Name = "label35"; - this.label35.Size = new System.Drawing.Size(14, 13); - this.label35.TabIndex = 15; - this.label35.Text = "P"; // // groupBox21 // @@ -690,76 +537,49 @@ this.groupBox21.Controls.Add(this.label41); this.groupBox21.Controls.Add(this.STB_PIT_P); this.groupBox21.Controls.Add(this.label42); - this.groupBox21.Location = new System.Drawing.Point(188, 13); + resources.ApplyResources(this.groupBox21, "groupBox21"); this.groupBox21.Name = "groupBox21"; - this.groupBox21.Size = new System.Drawing.Size(170, 114); - this.groupBox21.TabIndex = 29; this.groupBox21.TabStop = false; - this.groupBox21.Text = "Stabilize Pitch"; // // STAB_D // - this.STAB_D.Location = new System.Drawing.Point(80, 88); + resources.ApplyResources(this.STAB_D, "STAB_D"); this.STAB_D.Name = "STAB_D"; - this.STAB_D.Size = new System.Drawing.Size(78, 20); - this.STAB_D.TabIndex = 16; // // lblSTAB_D // - this.lblSTAB_D.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.lblSTAB_D.Location = new System.Drawing.Point(6, 91); + resources.ApplyResources(this.lblSTAB_D, "lblSTAB_D"); this.lblSTAB_D.Name = "lblSTAB_D"; - this.lblSTAB_D.Size = new System.Drawing.Size(65, 13); - this.lblSTAB_D.TabIndex = 17; - this.lblSTAB_D.Text = "Stabilize D"; // // STB_PIT_IMAX // - this.STB_PIT_IMAX.Location = new System.Drawing.Point(80, 63); + resources.ApplyResources(this.STB_PIT_IMAX, "STB_PIT_IMAX"); this.STB_PIT_IMAX.Name = "STB_PIT_IMAX"; - this.STB_PIT_IMAX.Size = new System.Drawing.Size(78, 20); - this.STB_PIT_IMAX.TabIndex = 11; // // label36 // - this.label36.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label36.Location = new System.Drawing.Point(6, 66); + resources.ApplyResources(this.label36, "label36"); this.label36.Name = "label36"; - this.label36.Size = new System.Drawing.Size(65, 13); - this.label36.TabIndex = 12; - this.label36.Text = "IMAX"; // // STB_PIT_I // - this.STB_PIT_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.STB_PIT_I, "STB_PIT_I"); this.STB_PIT_I.Name = "STB_PIT_I"; - this.STB_PIT_I.Size = new System.Drawing.Size(78, 20); - this.STB_PIT_I.TabIndex = 7; // // label41 // - this.label41.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label41.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label41, "label41"); this.label41.Name = "label41"; - this.label41.Size = new System.Drawing.Size(10, 13); - this.label41.TabIndex = 14; - this.label41.Text = "I"; // // STB_PIT_P // - this.STB_PIT_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.STB_PIT_P, "STB_PIT_P"); this.STB_PIT_P.Name = "STB_PIT_P"; - this.STB_PIT_P.Size = new System.Drawing.Size(78, 20); - this.STB_PIT_P.TabIndex = 5; // // label42 // - this.label42.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label42.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label42, "label42"); this.label42.Name = "label42"; - this.label42.Size = new System.Drawing.Size(14, 13); - this.label42.TabIndex = 15; - this.label42.Text = "P"; // // groupBox22 // @@ -769,60 +589,39 @@ this.groupBox22.Controls.Add(this.label45); this.groupBox22.Controls.Add(this.STB_RLL_P); this.groupBox22.Controls.Add(this.label46); - this.groupBox22.Location = new System.Drawing.Point(12, 13); + resources.ApplyResources(this.groupBox22, "groupBox22"); this.groupBox22.Name = "groupBox22"; - this.groupBox22.Size = new System.Drawing.Size(170, 95); - this.groupBox22.TabIndex = 30; this.groupBox22.TabStop = false; - this.groupBox22.Text = "Stabilize Roll"; // // STB_RLL_IMAX // - this.STB_RLL_IMAX.Location = new System.Drawing.Point(80, 63); + resources.ApplyResources(this.STB_RLL_IMAX, "STB_RLL_IMAX"); this.STB_RLL_IMAX.Name = "STB_RLL_IMAX"; - this.STB_RLL_IMAX.Size = new System.Drawing.Size(78, 20); - this.STB_RLL_IMAX.TabIndex = 11; // // label43 // - this.label43.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label43.Location = new System.Drawing.Point(6, 66); + resources.ApplyResources(this.label43, "label43"); this.label43.Name = "label43"; - this.label43.Size = new System.Drawing.Size(65, 13); - this.label43.TabIndex = 12; - this.label43.Text = "IMAX"; // // STB_RLL_I // - this.STB_RLL_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.STB_RLL_I, "STB_RLL_I"); this.STB_RLL_I.Name = "STB_RLL_I"; - this.STB_RLL_I.Size = new System.Drawing.Size(78, 20); - this.STB_RLL_I.TabIndex = 7; // // label45 // - this.label45.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label45.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label45, "label45"); this.label45.Name = "label45"; - this.label45.Size = new System.Drawing.Size(10, 13); - this.label45.TabIndex = 14; - this.label45.Text = "I"; // // STB_RLL_P // - this.STB_RLL_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.STB_RLL_P, "STB_RLL_P"); this.STB_RLL_P.Name = "STB_RLL_P"; - this.STB_RLL_P.Size = new System.Drawing.Size(78, 20); - this.STB_RLL_P.TabIndex = 5; // // label46 // - this.label46.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label46.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label46, "label46"); this.label46.Name = "label46"; - this.label46.Size = new System.Drawing.Size(14, 13); - this.label46.TabIndex = 15; - this.label46.Text = "P"; // // groupBox23 // @@ -834,76 +633,49 @@ this.groupBox23.Controls.Add(this.label77); this.groupBox23.Controls.Add(this.RATE_YAW_P); this.groupBox23.Controls.Add(this.label82); - this.groupBox23.Location = new System.Drawing.Point(364, 133); + resources.ApplyResources(this.groupBox23, "groupBox23"); this.groupBox23.Name = "groupBox23"; - this.groupBox23.Size = new System.Drawing.Size(170, 108); - this.groupBox23.TabIndex = 31; this.groupBox23.TabStop = false; - this.groupBox23.Text = "Rate Yaw"; // // RATE_YAW_D // - this.RATE_YAW_D.Location = new System.Drawing.Point(80, 60); + resources.ApplyResources(this.RATE_YAW_D, "RATE_YAW_D"); this.RATE_YAW_D.Name = "RATE_YAW_D"; - this.RATE_YAW_D.Size = new System.Drawing.Size(78, 20); - this.RATE_YAW_D.TabIndex = 8; // // label10 // - this.label10.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label10.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; - this.label10.Size = new System.Drawing.Size(10, 13); - this.label10.TabIndex = 9; - this.label10.Text = "D"; // // RATE_YAW_IMAX // - this.RATE_YAW_IMAX.Location = new System.Drawing.Point(80, 84); + resources.ApplyResources(this.RATE_YAW_IMAX, "RATE_YAW_IMAX"); this.RATE_YAW_IMAX.Name = "RATE_YAW_IMAX"; - this.RATE_YAW_IMAX.Size = new System.Drawing.Size(78, 20); - this.RATE_YAW_IMAX.TabIndex = 0; // // label47 // - this.label47.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label47.Location = new System.Drawing.Point(6, 87); + resources.ApplyResources(this.label47, "label47"); this.label47.Name = "label47"; - this.label47.Size = new System.Drawing.Size(65, 13); - this.label47.TabIndex = 1; - this.label47.Text = "IMAX"; // // RATE_YAW_I // - this.RATE_YAW_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.RATE_YAW_I, "RATE_YAW_I"); this.RATE_YAW_I.Name = "RATE_YAW_I"; - this.RATE_YAW_I.Size = new System.Drawing.Size(78, 20); - this.RATE_YAW_I.TabIndex = 4; // // label77 // - this.label77.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label77.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label77, "label77"); this.label77.Name = "label77"; - this.label77.Size = new System.Drawing.Size(10, 13); - this.label77.TabIndex = 5; - this.label77.Text = "I"; // // RATE_YAW_P // - this.RATE_YAW_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.RATE_YAW_P, "RATE_YAW_P"); this.RATE_YAW_P.Name = "RATE_YAW_P"; - this.RATE_YAW_P.Size = new System.Drawing.Size(78, 20); - this.RATE_YAW_P.TabIndex = 6; // // label82 // - this.label82.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label82.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label82, "label82"); this.label82.Name = "label82"; - this.label82.Size = new System.Drawing.Size(14, 13); - this.label82.TabIndex = 7; - this.label82.Text = "P"; // // groupBox24 // @@ -915,76 +687,49 @@ this.groupBox24.Controls.Add(this.label86); this.groupBox24.Controls.Add(this.RATE_PIT_P); this.groupBox24.Controls.Add(this.label87); - this.groupBox24.Location = new System.Drawing.Point(188, 133); + resources.ApplyResources(this.groupBox24, "groupBox24"); this.groupBox24.Name = "groupBox24"; - this.groupBox24.Size = new System.Drawing.Size(170, 108); - this.groupBox24.TabIndex = 32; this.groupBox24.TabStop = false; - this.groupBox24.Text = "Rate Pitch"; // // RATE_PIT_D // - this.RATE_PIT_D.Location = new System.Drawing.Point(80, 60); + resources.ApplyResources(this.RATE_PIT_D, "RATE_PIT_D"); this.RATE_PIT_D.Name = "RATE_PIT_D"; - this.RATE_PIT_D.Size = new System.Drawing.Size(78, 20); - this.RATE_PIT_D.TabIndex = 10; // // label11 // - this.label11.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label11.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; - this.label11.Size = new System.Drawing.Size(10, 13); - this.label11.TabIndex = 11; - this.label11.Text = "D"; // // RATE_PIT_IMAX // - this.RATE_PIT_IMAX.Location = new System.Drawing.Point(80, 83); + resources.ApplyResources(this.RATE_PIT_IMAX, "RATE_PIT_IMAX"); this.RATE_PIT_IMAX.Name = "RATE_PIT_IMAX"; - this.RATE_PIT_IMAX.Size = new System.Drawing.Size(78, 20); - this.RATE_PIT_IMAX.TabIndex = 0; // // label84 // - this.label84.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label84.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label84, "label84"); this.label84.Name = "label84"; - this.label84.Size = new System.Drawing.Size(65, 13); - this.label84.TabIndex = 1; - this.label84.Text = "IMAX"; // // RATE_PIT_I // - this.RATE_PIT_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.RATE_PIT_I, "RATE_PIT_I"); this.RATE_PIT_I.Name = "RATE_PIT_I"; - this.RATE_PIT_I.Size = new System.Drawing.Size(78, 20); - this.RATE_PIT_I.TabIndex = 4; // // label86 // - this.label86.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label86.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label86, "label86"); this.label86.Name = "label86"; - this.label86.Size = new System.Drawing.Size(10, 13); - this.label86.TabIndex = 5; - this.label86.Text = "I"; // // RATE_PIT_P // - this.RATE_PIT_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.RATE_PIT_P, "RATE_PIT_P"); this.RATE_PIT_P.Name = "RATE_PIT_P"; - this.RATE_PIT_P.Size = new System.Drawing.Size(78, 20); - this.RATE_PIT_P.TabIndex = 6; // // label87 // - this.label87.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label87.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label87, "label87"); this.label87.Name = "label87"; - this.label87.Size = new System.Drawing.Size(14, 13); - this.label87.TabIndex = 7; - this.label87.Text = "P"; // // groupBox25 // @@ -996,82 +741,54 @@ this.groupBox25.Controls.Add(this.label90); this.groupBox25.Controls.Add(this.RATE_RLL_P); this.groupBox25.Controls.Add(this.label91); - this.groupBox25.Location = new System.Drawing.Point(12, 133); + resources.ApplyResources(this.groupBox25, "groupBox25"); this.groupBox25.Name = "groupBox25"; - this.groupBox25.Size = new System.Drawing.Size(170, 108); - this.groupBox25.TabIndex = 33; this.groupBox25.TabStop = false; - this.groupBox25.Text = "Rate Roll"; // // RATE_RLL_D // - this.RATE_RLL_D.Location = new System.Drawing.Point(80, 60); + resources.ApplyResources(this.RATE_RLL_D, "RATE_RLL_D"); this.RATE_RLL_D.Name = "RATE_RLL_D"; - this.RATE_RLL_D.Size = new System.Drawing.Size(78, 20); - this.RATE_RLL_D.TabIndex = 12; // // label17 // - this.label17.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label17.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; - this.label17.Size = new System.Drawing.Size(10, 13); - this.label17.TabIndex = 13; - this.label17.Text = "D"; // // RATE_RLL_IMAX // - this.RATE_RLL_IMAX.Location = new System.Drawing.Point(80, 83); + resources.ApplyResources(this.RATE_RLL_IMAX, "RATE_RLL_IMAX"); this.RATE_RLL_IMAX.Name = "RATE_RLL_IMAX"; - this.RATE_RLL_IMAX.Size = new System.Drawing.Size(78, 20); - this.RATE_RLL_IMAX.TabIndex = 0; // // label88 // - this.label88.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label88.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label88, "label88"); this.label88.Name = "label88"; - this.label88.Size = new System.Drawing.Size(68, 13); - this.label88.TabIndex = 1; - this.label88.Text = "IMAX"; // // RATE_RLL_I // - this.RATE_RLL_I.Location = new System.Drawing.Point(80, 37); + resources.ApplyResources(this.RATE_RLL_I, "RATE_RLL_I"); this.RATE_RLL_I.Name = "RATE_RLL_I"; - this.RATE_RLL_I.Size = new System.Drawing.Size(78, 20); - this.RATE_RLL_I.TabIndex = 4; // // label90 // - this.label90.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label90.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label90, "label90"); this.label90.Name = "label90"; - this.label90.Size = new System.Drawing.Size(10, 13); - this.label90.TabIndex = 5; - this.label90.Text = "I"; // // RATE_RLL_P // - this.RATE_RLL_P.Location = new System.Drawing.Point(80, 13); + resources.ApplyResources(this.RATE_RLL_P, "RATE_RLL_P"); this.RATE_RLL_P.Name = "RATE_RLL_P"; - this.RATE_RLL_P.Size = new System.Drawing.Size(78, 20); - this.RATE_RLL_P.TabIndex = 6; // // label91 // - this.label91.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label91.Location = new System.Drawing.Point(6, 16); + resources.ApplyResources(this.label91, "label91"); this.label91.Name = "label91"; - this.label91.Size = new System.Drawing.Size(14, 13); - this.label91.TabIndex = 7; - this.label91.Text = "P"; // // ConfigArducopter // - this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.AutoScroll = true; this.Controls.Add(this.myLabel3); this.Controls.Add(this.TUNE_LOW); this.Controls.Add(this.TUNE_HIGH); @@ -1092,7 +809,6 @@ this.Controls.Add(this.groupBox24); this.Controls.Add(this.groupBox25); this.Name = "ConfigArducopter"; - this.Size = new System.Drawing.Size(728, 529); this.Load += new System.EventHandler(this.ConfigArducopter_Load); ((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).EndInit(); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx index 271670364a..1be2fe2b20 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx @@ -117,7 +117,2398 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 540, 302 + + + 29, 23 + + + + 42 + + + Min + + + myLabel3 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + + + 575, 305 + + + 51, 20 + + + 41 + + + TUNE_LOW + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + 665, 305 + + + 46, 20 + + + 40 + + + TUNE_HIGH + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 540, 277 + + + 53, 23 + + + 39 + + + Ch6 Opt + + + myLabel2 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 3 + + + CH6_NONE + + + CH6_STABILIZE_KP + + + CH6_STABILIZE_KI + + + CH6_YAW_KP + + + CH6_RATE_KP + + + CH6_RATE_KI + + + CH6_YAW_RATE_KP + + + CH6_THROTTLE_KP + + + CH6_TOP_BOTTOM_RATIO + + + CH6_RELAY + + + CH6_TRAVERSE_SPEED + + + CH6_NAV_P + + + CH6_LOITER_P + + + CH6_HELI_EXTERNAL_GYRO + + + CH6_THR_HOLD_KP + + + CH6_Z_GAIN + + + CH6_DAMP + + + CH6_OPTFLOW_KP + + + CH6_OPTFLOW_KI + + + CH6_OPTFLOW_KD + + + CH6_NAV_I + + + CH6_RATE_KD + + + 599, 277 + + + 112, 21 + + + 38 + + + TUNE + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + 540, 329 + + + 53, 23 + + + 37 + + + Ch7 Opt + + + myLabel1 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 5 + + + Do Nothing + + + + + + + + + Simple Mode + + + RTL + + + + + + + + + Save WP + + + 599, 329 + + + 112, 21 + + + 36 + + + CH7_OPT + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + 80, 60 + + + 78, 20 + + + 14 + + + THR_RATE_D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + + NoControl + + + 6, 63 + + + 10, 13 + + + 15 + + + D + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 1 + + + NoControl + + + 6, 86 + + + 65, 13 + + + 16 + + + IMAX + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 2 + + + 80, 83 + + + 78, 20 + + + 11 + + + THR_RATE_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 3 + + + 80, 37 + + + 78, 20 + + + 7 + + + THR_RATE_I + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 4 + + + 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 + + + 5 + + + 80, 13 + + + 78, 20 + + + 5 + + + THR_RATE_P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 6 + + + 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 + + + 7 + + + 12, 267 + + + 170, 110 + + + 35 + + + Throttle Rate + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + True + + + NoControl + + + 9, 247 + + + 154, 17 + + + 34 + + + Lock Pitch and Roll Values + + + CHK_lockrollpitch + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 80, 60 + + + 78, 20 + + + 18 + + + NAV_LAT_D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 0 + + + NoControl + + + 6, 63 + + + 10, 13 + + + 19 + + + D + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 1 + + + 80, 107 + + + 78, 20 + + + 16 + + + WP_SPEED_MAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 2 + + + NoControl + + + 6, 110 + + + 54, 13 + + + 17 + + + m/s + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 3 + + + 80, 84 + + + 78, 20 + + + 11 + + + NAV_LAT_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 4 + + + NoControl + + + 6, 87 + + + 65, 13 + + + 12 + + + IMAX + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 5 + + + 80, 37 + + + 78, 20 + + + 7 + + + NAV_LAT_I + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 6 + + + 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 + + + 7 + + + 80, 13 + + + 78, 20 + + + 5 + + + NAV_LAT_P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 8 + + + 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 + + + 9 + + + 540, 133 + + + 170, 131 + + + 24 + + + Nav WP + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + 80, 13 + + + 78, 20 + + + 5 + + + XTRK_GAIN_SC1 + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 0 + + + NoControl + + + 6, 16 + + + 38, 13 + + + 15 + + + Gain + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox6 + + + 1 + + + 364, 267 + + + 170, 43 + + + 25 + + + Crosstrack Correction + + + groupBox6 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + 80, 63 + + + 78, 20 + + + 11 + + + THR_ALT_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 188, 267 + + + 170, 110 + + + 26 + + + Altitude Hold + + + groupBox7 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + 80, 61 + + + 78, 20 + + + 11 + + + HLD_LAT_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 537, 13 + + + 170, 95 + + + 27 + + + Loiter + + + groupBox19 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_YAW_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 364, 13 + + + 170, 95 + + + 28 + + + Stabilize Yaw + + + groupBox20 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + 80, 88 + + + 78, 20 + + + 16 + + + STAB_D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 0 + + + NoControl + + + 6, 91 + + + 65, 13 + + + 17 + + + Stabilize D + + + lblSTAB_D + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 1 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_PIT_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 2 + + + 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 + + + 3 + + + 80, 37 + + + 78, 20 + + + 7 + + + STB_PIT_I + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 4 + + + 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 + + + 5 + + + 80, 13 + + + 78, 20 + + + 5 + + + STB_PIT_P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox21 + + + 6 + + + 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 + + + 7 + + + 188, 13 + + + 170, 114 + + + 29 + + + Stabilize Pitch + + + groupBox21 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 80, 63 + + + 78, 20 + + + 11 + + + STB_RLL_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 12, 13 + + + 170, 95 + + + 30 + + + Stabilize Roll + + + groupBox22 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + 80, 60 + + + 78, 20 + + + 8 + + + RATE_YAW_D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 0 + + + NoControl + + + 6, 63 + + + 10, 13 + + + 9 + + + D + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 1 + + + 80, 84 + + + 78, 20 + + + 0 + + + RATE_YAW_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 2 + + + NoControl + + + 6, 87 + + + 65, 13 + + + 1 + + + IMAX + + + label47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 3 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_YAW_I + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 4 + + + 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 + + + 5 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_YAW_P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox23 + + + 6 + + + 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 + + + 7 + + + 364, 133 + + + 170, 108 + + + 31 + + + Rate Yaw + + + groupBox23 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + 80, 60 + + + 78, 20 + + + 10 + + + RATE_PIT_D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 0 + + + NoControl + + + 6, 63 + + + 10, 13 + + + 11 + + + D + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 1 + + + 80, 83 + + + 78, 20 + + + 0 + + + RATE_PIT_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 2 + + + NoControl + + + 6, 86 + + + 65, 13 + + + 1 + + + IMAX + + + label84 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 3 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_PIT_I + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 4 + + + 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 + + + 5 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_PIT_P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox24 + + + 6 + + + 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 + + + 7 + + + 188, 133 + + + 170, 108 + + + 32 + + + Rate Pitch + + + groupBox24 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + 80, 60 + + + 78, 20 + + + 12 + + + RATE_RLL_D + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 0 + + + NoControl + + + 6, 63 + + + 10, 13 + + + 13 + + + D + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 1 + + + 80, 83 + + + 78, 20 + + + 0 + + + RATE_RLL_IMAX + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 2 + + + NoControl + + + 6, 86 + + + 68, 13 + + + 1 + + + IMAX + + + label88 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 3 + + + 80, 37 + + + 78, 20 + + + 4 + + + RATE_RLL_I + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 4 + + + 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 + + + 5 + + + 80, 13 + + + 78, 20 + + + 6 + + + RATE_RLL_P + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox25 + + + 6 + + + 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 + + + 7 + + + 12, 133 + + + 170, 108 + + + 33 + + + Rate Roll + + + groupBox25 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 18 + 17, 17 + + True + + + 6, 13 + + + True + + + 728, 529 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigArducopter + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs index f30b039741..90e96df593 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs @@ -29,6 +29,7 @@ private void InitializeComponent() { this.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigArduplane)); this.groupBox3 = new System.Windows.Forms.GroupBox(); this.THR_FS_VALUE = new System.Windows.Forms.NumericUpDown(); this.label5 = new System.Windows.Forms.Label(); @@ -198,76 +199,49 @@ this.groupBox3.Controls.Add(this.label7); this.groupBox3.Controls.Add(this.TRIM_THROTTLE); this.groupBox3.Controls.Add(this.label8); - this.groupBox3.Location = new System.Drawing.Point(413, 231); + resources.ApplyResources(this.groupBox3, "groupBox3"); this.groupBox3.Name = "groupBox3"; - this.groupBox3.Size = new System.Drawing.Size(195, 108); - this.groupBox3.TabIndex = 12; this.groupBox3.TabStop = false; - this.groupBox3.Text = "Throttle 0-100%"; // // THR_FS_VALUE // - this.THR_FS_VALUE.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.THR_FS_VALUE, "THR_FS_VALUE"); this.THR_FS_VALUE.Name = "THR_FS_VALUE"; - this.THR_FS_VALUE.Size = new System.Drawing.Size(78, 20); - this.THR_FS_VALUE.TabIndex = 11; // // label5 // - this.label5.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label5.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; - this.label5.Size = new System.Drawing.Size(50, 13); - this.label5.TabIndex = 12; - this.label5.Text = "FS Value"; // // THR_MAX // - this.THR_MAX.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.THR_MAX, "THR_MAX"); this.THR_MAX.Name = "THR_MAX"; - this.THR_MAX.Size = new System.Drawing.Size(78, 20); - this.THR_MAX.TabIndex = 9; // // label6 // - this.label6.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label6.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; - this.label6.Size = new System.Drawing.Size(27, 13); - this.label6.TabIndex = 13; - this.label6.Text = "Max"; // // THR_MIN // - this.THR_MIN.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.THR_MIN, "THR_MIN"); this.THR_MIN.Name = "THR_MIN"; - this.THR_MIN.Size = new System.Drawing.Size(78, 20); - this.THR_MIN.TabIndex = 7; // // label7 // - this.label7.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label7.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; - this.label7.Size = new System.Drawing.Size(24, 13); - this.label7.TabIndex = 14; - this.label7.Text = "Min"; // // TRIM_THROTTLE // - this.TRIM_THROTTLE.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.TRIM_THROTTLE, "TRIM_THROTTLE"); this.TRIM_THROTTLE.Name = "TRIM_THROTTLE"; - this.TRIM_THROTTLE.Size = new System.Drawing.Size(78, 20); - this.TRIM_THROTTLE.TabIndex = 5; // // label8 // - this.label8.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label8.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; - this.label8.Size = new System.Drawing.Size(36, 13); - this.label8.TabIndex = 15; - this.label8.Text = "Cruise"; // // groupBox1 // @@ -279,76 +253,49 @@ this.groupBox1.Controls.Add(this.label3); this.groupBox1.Controls.Add(this.TRIM_ARSPD_CM); this.groupBox1.Controls.Add(this.label4); - this.groupBox1.Location = new System.Drawing.Point(414, 339); + resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Name = "groupBox1"; - this.groupBox1.Size = new System.Drawing.Size(195, 108); - this.groupBox1.TabIndex = 13; this.groupBox1.TabStop = false; - this.groupBox1.Text = "Airspeed m/s"; // // ARSPD_RATIO // - this.ARSPD_RATIO.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.ARSPD_RATIO, "ARSPD_RATIO"); this.ARSPD_RATIO.Name = "ARSPD_RATIO"; - this.ARSPD_RATIO.Size = new System.Drawing.Size(78, 20); - this.ARSPD_RATIO.TabIndex = 0; // // label1 // - this.label1.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label1.Location = new System.Drawing.Point(6, 87); + resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; - this.label1.Size = new System.Drawing.Size(32, 13); - this.label1.TabIndex = 1; - this.label1.Text = "Ratio"; // // ARSPD_FBW_MAX // - this.ARSPD_FBW_MAX.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.ARSPD_FBW_MAX, "ARSPD_FBW_MAX"); this.ARSPD_FBW_MAX.Name = "ARSPD_FBW_MAX"; - this.ARSPD_FBW_MAX.Size = new System.Drawing.Size(78, 20); - this.ARSPD_FBW_MAX.TabIndex = 2; // // label2 // - this.label2.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label2.Location = new System.Drawing.Point(6, 59); + resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; - this.label2.Size = new System.Drawing.Size(53, 13); - this.label2.TabIndex = 3; - this.label2.Text = "FBW max"; // // ARSPD_FBW_MIN // - this.ARSPD_FBW_MIN.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.ARSPD_FBW_MIN, "ARSPD_FBW_MIN"); this.ARSPD_FBW_MIN.Name = "ARSPD_FBW_MIN"; - this.ARSPD_FBW_MIN.Size = new System.Drawing.Size(78, 20); - this.ARSPD_FBW_MIN.TabIndex = 4; // // label3 // - this.label3.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label3.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; - this.label3.Size = new System.Drawing.Size(50, 13); - this.label3.TabIndex = 5; - this.label3.Text = "FBW min"; // // TRIM_ARSPD_CM // - this.TRIM_ARSPD_CM.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.TRIM_ARSPD_CM, "TRIM_ARSPD_CM"); this.TRIM_ARSPD_CM.Name = "TRIM_ARSPD_CM"; - this.TRIM_ARSPD_CM.Size = new System.Drawing.Size(78, 20); - this.TRIM_ARSPD_CM.TabIndex = 5; // // label4 // - this.label4.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label4.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; - this.label4.Size = new System.Drawing.Size(64, 13); - this.label4.TabIndex = 6; - this.label4.Text = "Cruise"; // // groupBox2 // @@ -358,60 +305,39 @@ this.groupBox2.Controls.Add(this.label38); this.groupBox2.Controls.Add(this.LIM_ROLL_CD); this.groupBox2.Controls.Add(this.label37); - this.groupBox2.Location = new System.Drawing.Point(213, 339); + resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Name = "groupBox2"; - this.groupBox2.Size = new System.Drawing.Size(195, 108); - this.groupBox2.TabIndex = 14; this.groupBox2.TabStop = false; - this.groupBox2.Text = "Navigation Angles"; // // LIM_PITCH_MIN // - this.LIM_PITCH_MIN.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.LIM_PITCH_MIN, "LIM_PITCH_MIN"); this.LIM_PITCH_MIN.Name = "LIM_PITCH_MIN"; - this.LIM_PITCH_MIN.Size = new System.Drawing.Size(78, 20); - this.LIM_PITCH_MIN.TabIndex = 9; // // label39 // - this.label39.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label39.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label39, "label39"); this.label39.Name = "label39"; - this.label39.Size = new System.Drawing.Size(51, 13); - this.label39.TabIndex = 10; - this.label39.Text = "Pitch Min"; // // LIM_PITCH_MAX // - this.LIM_PITCH_MAX.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.LIM_PITCH_MAX, "LIM_PITCH_MAX"); this.LIM_PITCH_MAX.Name = "LIM_PITCH_MAX"; - this.LIM_PITCH_MAX.Size = new System.Drawing.Size(78, 20); - this.LIM_PITCH_MAX.TabIndex = 7; // // label38 // - this.label38.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label38.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label38, "label38"); this.label38.Name = "label38"; - this.label38.Size = new System.Drawing.Size(54, 13); - this.label38.TabIndex = 11; - this.label38.Text = "Pitch Max"; // // LIM_ROLL_CD // - this.LIM_ROLL_CD.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.LIM_ROLL_CD, "LIM_ROLL_CD"); this.LIM_ROLL_CD.Name = "LIM_ROLL_CD"; - this.LIM_ROLL_CD.Size = new System.Drawing.Size(78, 20); - this.LIM_ROLL_CD.TabIndex = 5; // // label37 // - this.label37.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label37.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label37, "label37"); this.label37.Name = "label37"; - this.label37.Size = new System.Drawing.Size(55, 13); - this.label37.TabIndex = 12; - this.label37.Text = "Bank Max"; // // groupBox15 // @@ -419,44 +345,29 @@ this.groupBox15.Controls.Add(this.label79); this.groupBox15.Controls.Add(this.XTRK_GAIN_SC); this.groupBox15.Controls.Add(this.label80); - this.groupBox15.Location = new System.Drawing.Point(12, 339); + resources.ApplyResources(this.groupBox15, "groupBox15"); this.groupBox15.Name = "groupBox15"; - this.groupBox15.Size = new System.Drawing.Size(195, 108); - this.groupBox15.TabIndex = 15; this.groupBox15.TabStop = false; - this.groupBox15.Text = "Xtrack Pids"; // // XTRK_ANGLE_CD // - this.XTRK_ANGLE_CD.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.XTRK_ANGLE_CD, "XTRK_ANGLE_CD"); this.XTRK_ANGLE_CD.Name = "XTRK_ANGLE_CD"; - this.XTRK_ANGLE_CD.Size = new System.Drawing.Size(78, 20); - this.XTRK_ANGLE_CD.TabIndex = 7; // // label79 // - this.label79.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label79.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label79, "label79"); this.label79.Name = "label79"; - this.label79.Size = new System.Drawing.Size(61, 13); - this.label79.TabIndex = 8; - this.label79.Text = "Entry Angle"; // // XTRK_GAIN_SC // - this.XTRK_GAIN_SC.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.XTRK_GAIN_SC, "XTRK_GAIN_SC"); this.XTRK_GAIN_SC.Name = "XTRK_GAIN_SC"; - this.XTRK_GAIN_SC.Size = new System.Drawing.Size(78, 20); - this.XTRK_GAIN_SC.TabIndex = 5; // // label80 // - this.label80.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label80.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label80, "label80"); this.label80.Name = "label80"; - this.label80.Size = new System.Drawing.Size(52, 13); - this.label80.TabIndex = 9; - this.label80.Text = "Gain (cm)"; // // groupBox16 // @@ -466,60 +377,39 @@ this.groupBox16.Controls.Add(this.label78); this.groupBox16.Controls.Add(this.KFF_PTCHCOMP); this.groupBox16.Controls.Add(this.label81); - this.groupBox16.Location = new System.Drawing.Point(213, 231); + resources.ApplyResources(this.groupBox16, "groupBox16"); this.groupBox16.Name = "groupBox16"; - this.groupBox16.Size = new System.Drawing.Size(195, 108); - this.groupBox16.TabIndex = 16; this.groupBox16.TabStop = false; - this.groupBox16.Text = "Other Mix\'s"; // // KFF_PTCH2THR // - this.KFF_PTCH2THR.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.KFF_PTCH2THR, "KFF_PTCH2THR"); this.KFF_PTCH2THR.Name = "KFF_PTCH2THR"; - this.KFF_PTCH2THR.Size = new System.Drawing.Size(78, 20); - this.KFF_PTCH2THR.TabIndex = 13; // // label83 // - this.label83.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label83.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label83, "label83"); this.label83.Name = "label83"; - this.label83.Size = new System.Drawing.Size(36, 13); - this.label83.TabIndex = 14; - this.label83.Text = "P to T"; // // KFF_RDDRMIX // - this.KFF_RDDRMIX.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.KFF_RDDRMIX, "KFF_RDDRMIX"); this.KFF_RDDRMIX.Name = "KFF_RDDRMIX"; - this.KFF_RDDRMIX.Size = new System.Drawing.Size(78, 20); - this.KFF_RDDRMIX.TabIndex = 9; // // label78 // - this.label78.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label78.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label78, "label78"); this.label78.Name = "label78"; - this.label78.Size = new System.Drawing.Size(61, 13); - this.label78.TabIndex = 15; - this.label78.Text = "Rudder Mix"; // // KFF_PTCHCOMP // - this.KFF_PTCHCOMP.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.KFF_PTCHCOMP, "KFF_PTCHCOMP"); this.KFF_PTCHCOMP.Name = "KFF_PTCHCOMP"; - this.KFF_PTCHCOMP.Size = new System.Drawing.Size(78, 20); - this.KFF_PTCHCOMP.TabIndex = 7; // // label81 // - this.label81.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label81.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label81, "label81"); this.label81.Name = "label81"; - this.label81.Size = new System.Drawing.Size(61, 13); - this.label81.TabIndex = 16; - this.label81.Text = "Pitch Comp"; // // groupBox14 // @@ -531,76 +421,49 @@ this.groupBox14.Controls.Add(this.label75); this.groupBox14.Controls.Add(this.ENRGY2THR_P); this.groupBox14.Controls.Add(this.label76); - this.groupBox14.Location = new System.Drawing.Point(12, 231); + resources.ApplyResources(this.groupBox14, "groupBox14"); this.groupBox14.Name = "groupBox14"; - this.groupBox14.Size = new System.Drawing.Size(195, 108); - this.groupBox14.TabIndex = 17; this.groupBox14.TabStop = false; - this.groupBox14.Text = "Energy/Alt Pid"; // // ENRGY2THR_IMAX // - this.ENRGY2THR_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.ENRGY2THR_IMAX, "ENRGY2THR_IMAX"); this.ENRGY2THR_IMAX.Name = "ENRGY2THR_IMAX"; - this.ENRGY2THR_IMAX.Size = new System.Drawing.Size(78, 20); - this.ENRGY2THR_IMAX.TabIndex = 11; // // label73 // - this.label73.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label73.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label73, "label73"); this.label73.Name = "label73"; - this.label73.Size = new System.Drawing.Size(54, 13); - this.label73.TabIndex = 12; - this.label73.Text = "INT_MAX"; // // ENRGY2THR_D // - this.ENRGY2THR_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.ENRGY2THR_D, "ENRGY2THR_D"); this.ENRGY2THR_D.Name = "ENRGY2THR_D"; - this.ENRGY2THR_D.Size = new System.Drawing.Size(78, 20); - this.ENRGY2THR_D.TabIndex = 9; // // label74 // - this.label74.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label74.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label74, "label74"); this.label74.Name = "label74"; - this.label74.Size = new System.Drawing.Size(15, 13); - this.label74.TabIndex = 13; - this.label74.Text = "D"; // // ENRGY2THR_I // - this.ENRGY2THR_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.ENRGY2THR_I, "ENRGY2THR_I"); this.ENRGY2THR_I.Name = "ENRGY2THR_I"; - this.ENRGY2THR_I.Size = new System.Drawing.Size(78, 20); - this.ENRGY2THR_I.TabIndex = 7; // // label75 // - this.label75.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label75.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label75, "label75"); this.label75.Name = "label75"; - this.label75.Size = new System.Drawing.Size(10, 13); - this.label75.TabIndex = 14; - this.label75.Text = "I"; // // ENRGY2THR_P // - this.ENRGY2THR_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.ENRGY2THR_P, "ENRGY2THR_P"); this.ENRGY2THR_P.Name = "ENRGY2THR_P"; - this.ENRGY2THR_P.Size = new System.Drawing.Size(78, 20); - this.ENRGY2THR_P.TabIndex = 5; // // label76 // - this.label76.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label76.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label76, "label76"); this.label76.Name = "label76"; - this.label76.Size = new System.Drawing.Size(14, 13); - this.label76.TabIndex = 15; - this.label76.Text = "P"; // // groupBox13 // @@ -612,76 +475,49 @@ this.groupBox13.Controls.Add(this.label71); this.groupBox13.Controls.Add(this.ALT2PTCH_P); this.groupBox13.Controls.Add(this.label72); - this.groupBox13.Location = new System.Drawing.Point(414, 123); + resources.ApplyResources(this.groupBox13, "groupBox13"); this.groupBox13.Name = "groupBox13"; - this.groupBox13.Size = new System.Drawing.Size(195, 108); - this.groupBox13.TabIndex = 18; this.groupBox13.TabStop = false; - this.groupBox13.Text = "Nav Pitch Alt Pid"; // // ALT2PTCH_IMAX // - this.ALT2PTCH_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.ALT2PTCH_IMAX, "ALT2PTCH_IMAX"); this.ALT2PTCH_IMAX.Name = "ALT2PTCH_IMAX"; - this.ALT2PTCH_IMAX.Size = new System.Drawing.Size(78, 20); - this.ALT2PTCH_IMAX.TabIndex = 0; // // label69 // - this.label69.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label69.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label69, "label69"); this.label69.Name = "label69"; - this.label69.Size = new System.Drawing.Size(54, 13); - this.label69.TabIndex = 1; - this.label69.Text = "INT_MAX"; // // ALT2PTCH_D // - this.ALT2PTCH_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.ALT2PTCH_D, "ALT2PTCH_D"); this.ALT2PTCH_D.Name = "ALT2PTCH_D"; - this.ALT2PTCH_D.Size = new System.Drawing.Size(78, 20); - this.ALT2PTCH_D.TabIndex = 2; // // label70 // - this.label70.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label70.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label70, "label70"); this.label70.Name = "label70"; - this.label70.Size = new System.Drawing.Size(15, 13); - this.label70.TabIndex = 3; - this.label70.Text = "D"; // // ALT2PTCH_I // - this.ALT2PTCH_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.ALT2PTCH_I, "ALT2PTCH_I"); this.ALT2PTCH_I.Name = "ALT2PTCH_I"; - this.ALT2PTCH_I.Size = new System.Drawing.Size(78, 20); - this.ALT2PTCH_I.TabIndex = 4; // // label71 // - this.label71.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label71.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label71, "label71"); this.label71.Name = "label71"; - this.label71.Size = new System.Drawing.Size(10, 13); - this.label71.TabIndex = 5; - this.label71.Text = "I"; // // ALT2PTCH_P // - this.ALT2PTCH_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.ALT2PTCH_P, "ALT2PTCH_P"); this.ALT2PTCH_P.Name = "ALT2PTCH_P"; - this.ALT2PTCH_P.Size = new System.Drawing.Size(78, 20); - this.ALT2PTCH_P.TabIndex = 6; // // label72 // - this.label72.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label72.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label72, "label72"); this.label72.Name = "label72"; - this.label72.Size = new System.Drawing.Size(14, 13); - this.label72.TabIndex = 7; - this.label72.Text = "P"; // // groupBox12 // @@ -693,76 +529,49 @@ this.groupBox12.Controls.Add(this.label67); this.groupBox12.Controls.Add(this.ARSP2PTCH_P); this.groupBox12.Controls.Add(this.label68); - this.groupBox12.Location = new System.Drawing.Point(213, 123); + resources.ApplyResources(this.groupBox12, "groupBox12"); this.groupBox12.Name = "groupBox12"; - this.groupBox12.Size = new System.Drawing.Size(195, 108); - this.groupBox12.TabIndex = 19; this.groupBox12.TabStop = false; - this.groupBox12.Text = "Nav Pitch AS Pid"; // // ARSP2PTCH_IMAX // - this.ARSP2PTCH_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.ARSP2PTCH_IMAX, "ARSP2PTCH_IMAX"); this.ARSP2PTCH_IMAX.Name = "ARSP2PTCH_IMAX"; - this.ARSP2PTCH_IMAX.Size = new System.Drawing.Size(78, 20); - this.ARSP2PTCH_IMAX.TabIndex = 0; // // label65 // - this.label65.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label65.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label65, "label65"); this.label65.Name = "label65"; - this.label65.Size = new System.Drawing.Size(54, 13); - this.label65.TabIndex = 1; - this.label65.Text = "INT_MAX"; // // ARSP2PTCH_D // - this.ARSP2PTCH_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.ARSP2PTCH_D, "ARSP2PTCH_D"); this.ARSP2PTCH_D.Name = "ARSP2PTCH_D"; - this.ARSP2PTCH_D.Size = new System.Drawing.Size(78, 20); - this.ARSP2PTCH_D.TabIndex = 2; // // label66 // - this.label66.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label66.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label66, "label66"); this.label66.Name = "label66"; - this.label66.Size = new System.Drawing.Size(15, 13); - this.label66.TabIndex = 3; - this.label66.Text = "D"; // // ARSP2PTCH_I // - this.ARSP2PTCH_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.ARSP2PTCH_I, "ARSP2PTCH_I"); this.ARSP2PTCH_I.Name = "ARSP2PTCH_I"; - this.ARSP2PTCH_I.Size = new System.Drawing.Size(78, 20); - this.ARSP2PTCH_I.TabIndex = 4; // // label67 // - this.label67.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label67.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label67, "label67"); this.label67.Name = "label67"; - this.label67.Size = new System.Drawing.Size(10, 13); - this.label67.TabIndex = 5; - this.label67.Text = "I"; // // ARSP2PTCH_P // - this.ARSP2PTCH_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.ARSP2PTCH_P, "ARSP2PTCH_P"); this.ARSP2PTCH_P.Name = "ARSP2PTCH_P"; - this.ARSP2PTCH_P.Size = new System.Drawing.Size(78, 20); - this.ARSP2PTCH_P.TabIndex = 6; // // label68 // - this.label68.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label68.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label68, "label68"); this.label68.Name = "label68"; - this.label68.Size = new System.Drawing.Size(14, 13); - this.label68.TabIndex = 7; - this.label68.Text = "P"; // // groupBox11 // @@ -774,76 +583,49 @@ this.groupBox11.Controls.Add(this.label63); this.groupBox11.Controls.Add(this.HDNG2RLL_P); this.groupBox11.Controls.Add(this.label64); - this.groupBox11.Location = new System.Drawing.Point(12, 123); + resources.ApplyResources(this.groupBox11, "groupBox11"); this.groupBox11.Name = "groupBox11"; - this.groupBox11.Size = new System.Drawing.Size(195, 108); - this.groupBox11.TabIndex = 20; this.groupBox11.TabStop = false; - this.groupBox11.Text = "Nav Roll Pid"; // // HDNG2RLL_IMAX // - this.HDNG2RLL_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.HDNG2RLL_IMAX, "HDNG2RLL_IMAX"); this.HDNG2RLL_IMAX.Name = "HDNG2RLL_IMAX"; - this.HDNG2RLL_IMAX.Size = new System.Drawing.Size(78, 20); - this.HDNG2RLL_IMAX.TabIndex = 11; // // label61 // - this.label61.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label61.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label61, "label61"); this.label61.Name = "label61"; - this.label61.Size = new System.Drawing.Size(54, 13); - this.label61.TabIndex = 12; - this.label61.Text = "INT_MAX"; // // HDNG2RLL_D // - this.HDNG2RLL_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.HDNG2RLL_D, "HDNG2RLL_D"); this.HDNG2RLL_D.Name = "HDNG2RLL_D"; - this.HDNG2RLL_D.Size = new System.Drawing.Size(78, 20); - this.HDNG2RLL_D.TabIndex = 9; // // label62 // - this.label62.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label62.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label62, "label62"); this.label62.Name = "label62"; - this.label62.Size = new System.Drawing.Size(15, 13); - this.label62.TabIndex = 13; - this.label62.Text = "D"; // // HDNG2RLL_I // - this.HDNG2RLL_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.HDNG2RLL_I, "HDNG2RLL_I"); this.HDNG2RLL_I.Name = "HDNG2RLL_I"; - this.HDNG2RLL_I.Size = new System.Drawing.Size(78, 20); - this.HDNG2RLL_I.TabIndex = 7; // // label63 // - this.label63.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label63.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label63, "label63"); this.label63.Name = "label63"; - this.label63.Size = new System.Drawing.Size(10, 13); - this.label63.TabIndex = 14; - this.label63.Text = "I"; // // HDNG2RLL_P // - this.HDNG2RLL_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.HDNG2RLL_P, "HDNG2RLL_P"); this.HDNG2RLL_P.Name = "HDNG2RLL_P"; - this.HDNG2RLL_P.Size = new System.Drawing.Size(78, 20); - this.HDNG2RLL_P.TabIndex = 5; // // label64 // - this.label64.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label64.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label64, "label64"); this.label64.Name = "label64"; - this.label64.Size = new System.Drawing.Size(14, 13); - this.label64.TabIndex = 15; - this.label64.Text = "P"; // // groupBox10 // @@ -855,76 +637,49 @@ this.groupBox10.Controls.Add(this.label59); this.groupBox10.Controls.Add(this.YW2SRV_P); this.groupBox10.Controls.Add(this.label60); - this.groupBox10.Location = new System.Drawing.Point(414, 15); + resources.ApplyResources(this.groupBox10, "groupBox10"); this.groupBox10.Name = "groupBox10"; - this.groupBox10.Size = new System.Drawing.Size(195, 108); - this.groupBox10.TabIndex = 21; this.groupBox10.TabStop = false; - this.groupBox10.Text = "Servo Yaw Pid"; // // YW2SRV_IMAX // - this.YW2SRV_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.YW2SRV_IMAX, "YW2SRV_IMAX"); this.YW2SRV_IMAX.Name = "YW2SRV_IMAX"; - this.YW2SRV_IMAX.Size = new System.Drawing.Size(78, 20); - this.YW2SRV_IMAX.TabIndex = 11; // // label57 // - this.label57.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label57.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label57, "label57"); this.label57.Name = "label57"; - this.label57.Size = new System.Drawing.Size(54, 13); - this.label57.TabIndex = 12; - this.label57.Text = "INT_MAX"; // // YW2SRV_D // - this.YW2SRV_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.YW2SRV_D, "YW2SRV_D"); this.YW2SRV_D.Name = "YW2SRV_D"; - this.YW2SRV_D.Size = new System.Drawing.Size(78, 20); - this.YW2SRV_D.TabIndex = 9; // // label58 // - this.label58.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label58.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label58, "label58"); this.label58.Name = "label58"; - this.label58.Size = new System.Drawing.Size(15, 13); - this.label58.TabIndex = 13; - this.label58.Text = "D"; // // YW2SRV_I // - this.YW2SRV_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.YW2SRV_I, "YW2SRV_I"); this.YW2SRV_I.Name = "YW2SRV_I"; - this.YW2SRV_I.Size = new System.Drawing.Size(78, 20); - this.YW2SRV_I.TabIndex = 7; // // label59 // - this.label59.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label59.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label59, "label59"); this.label59.Name = "label59"; - this.label59.Size = new System.Drawing.Size(10, 13); - this.label59.TabIndex = 14; - this.label59.Text = "I"; // // YW2SRV_P // - this.YW2SRV_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.YW2SRV_P, "YW2SRV_P"); this.YW2SRV_P.Name = "YW2SRV_P"; - this.YW2SRV_P.Size = new System.Drawing.Size(78, 20); - this.YW2SRV_P.TabIndex = 5; // // label60 // - this.label60.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label60.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label60, "label60"); this.label60.Name = "label60"; - this.label60.Size = new System.Drawing.Size(14, 13); - this.label60.TabIndex = 15; - this.label60.Text = "P"; // // groupBox9 // @@ -936,76 +691,49 @@ this.groupBox9.Controls.Add(this.label55); this.groupBox9.Controls.Add(this.PTCH2SRV_P); this.groupBox9.Controls.Add(this.label56); - this.groupBox9.Location = new System.Drawing.Point(213, 15); + resources.ApplyResources(this.groupBox9, "groupBox9"); this.groupBox9.Name = "groupBox9"; - this.groupBox9.Size = new System.Drawing.Size(195, 108); - this.groupBox9.TabIndex = 22; this.groupBox9.TabStop = false; - this.groupBox9.Text = "Servo Pitch Pid"; // // PTCH2SRV_IMAX // - this.PTCH2SRV_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.PTCH2SRV_IMAX, "PTCH2SRV_IMAX"); this.PTCH2SRV_IMAX.Name = "PTCH2SRV_IMAX"; - this.PTCH2SRV_IMAX.Size = new System.Drawing.Size(78, 20); - this.PTCH2SRV_IMAX.TabIndex = 11; // // label53 // - this.label53.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label53.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label53, "label53"); this.label53.Name = "label53"; - this.label53.Size = new System.Drawing.Size(54, 13); - this.label53.TabIndex = 12; - this.label53.Text = "INT_MAX"; // // PTCH2SRV_D // - this.PTCH2SRV_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.PTCH2SRV_D, "PTCH2SRV_D"); this.PTCH2SRV_D.Name = "PTCH2SRV_D"; - this.PTCH2SRV_D.Size = new System.Drawing.Size(78, 20); - this.PTCH2SRV_D.TabIndex = 9; // // label54 // - this.label54.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label54.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label54, "label54"); this.label54.Name = "label54"; - this.label54.Size = new System.Drawing.Size(15, 13); - this.label54.TabIndex = 13; - this.label54.Text = "D"; // // PTCH2SRV_I // - this.PTCH2SRV_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.PTCH2SRV_I, "PTCH2SRV_I"); this.PTCH2SRV_I.Name = "PTCH2SRV_I"; - this.PTCH2SRV_I.Size = new System.Drawing.Size(78, 20); - this.PTCH2SRV_I.TabIndex = 7; // // label55 // - this.label55.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label55.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label55, "label55"); this.label55.Name = "label55"; - this.label55.Size = new System.Drawing.Size(10, 13); - this.label55.TabIndex = 14; - this.label55.Text = "I"; // // PTCH2SRV_P // - this.PTCH2SRV_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.PTCH2SRV_P, "PTCH2SRV_P"); this.PTCH2SRV_P.Name = "PTCH2SRV_P"; - this.PTCH2SRV_P.Size = new System.Drawing.Size(78, 20); - this.PTCH2SRV_P.TabIndex = 5; // // label56 // - this.label56.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label56.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label56, "label56"); this.label56.Name = "label56"; - this.label56.Size = new System.Drawing.Size(14, 13); - this.label56.TabIndex = 15; - this.label56.Text = "P"; // // groupBox8 // @@ -1017,80 +745,53 @@ this.groupBox8.Controls.Add(this.label51); this.groupBox8.Controls.Add(this.RLL2SRV_P); this.groupBox8.Controls.Add(this.label52); - this.groupBox8.Location = new System.Drawing.Point(12, 15); + resources.ApplyResources(this.groupBox8, "groupBox8"); this.groupBox8.Name = "groupBox8"; - this.groupBox8.Size = new System.Drawing.Size(195, 108); - this.groupBox8.TabIndex = 23; this.groupBox8.TabStop = false; - this.groupBox8.Text = "Servo Roll Pid"; // // RLL2SRV_IMAX // - this.RLL2SRV_IMAX.Location = new System.Drawing.Point(111, 82); + resources.ApplyResources(this.RLL2SRV_IMAX, "RLL2SRV_IMAX"); this.RLL2SRV_IMAX.Name = "RLL2SRV_IMAX"; - this.RLL2SRV_IMAX.Size = new System.Drawing.Size(78, 20); - this.RLL2SRV_IMAX.TabIndex = 11; // // label49 // - this.label49.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label49.Location = new System.Drawing.Point(6, 86); + resources.ApplyResources(this.label49, "label49"); this.label49.Name = "label49"; - this.label49.Size = new System.Drawing.Size(54, 13); - this.label49.TabIndex = 12; - this.label49.Text = "INT_MAX"; // // RLL2SRV_D // - this.RLL2SRV_D.Location = new System.Drawing.Point(111, 59); + resources.ApplyResources(this.RLL2SRV_D, "RLL2SRV_D"); this.RLL2SRV_D.Name = "RLL2SRV_D"; - this.RLL2SRV_D.Size = new System.Drawing.Size(78, 20); - this.RLL2SRV_D.TabIndex = 9; // // label50 // - this.label50.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label50.Location = new System.Drawing.Point(6, 63); + resources.ApplyResources(this.label50, "label50"); this.label50.Name = "label50"; - this.label50.Size = new System.Drawing.Size(15, 13); - this.label50.TabIndex = 13; - this.label50.Text = "D"; // // RLL2SRV_I // - this.RLL2SRV_I.Location = new System.Drawing.Point(111, 36); + resources.ApplyResources(this.RLL2SRV_I, "RLL2SRV_I"); this.RLL2SRV_I.Name = "RLL2SRV_I"; - this.RLL2SRV_I.Size = new System.Drawing.Size(78, 20); - this.RLL2SRV_I.TabIndex = 7; // // label51 // - this.label51.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label51.Location = new System.Drawing.Point(6, 40); + resources.ApplyResources(this.label51, "label51"); this.label51.Name = "label51"; - this.label51.Size = new System.Drawing.Size(10, 13); - this.label51.TabIndex = 14; - this.label51.Text = "I"; // // RLL2SRV_P // - this.RLL2SRV_P.Location = new System.Drawing.Point(111, 13); + resources.ApplyResources(this.RLL2SRV_P, "RLL2SRV_P"); this.RLL2SRV_P.Name = "RLL2SRV_P"; - this.RLL2SRV_P.Size = new System.Drawing.Size(78, 20); - this.RLL2SRV_P.TabIndex = 5; // // label52 // - this.label52.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label52.Location = new System.Drawing.Point(6, 17); + resources.ApplyResources(this.label52, "label52"); this.label52.Name = "label52"; - this.label52.Size = new System.Drawing.Size(14, 13); - this.label52.TabIndex = 15; - this.label52.Text = "P"; // // ConfigArduplane // - this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; this.Controls.Add(this.groupBox3); this.Controls.Add(this.groupBox1); @@ -1105,7 +806,6 @@ this.Controls.Add(this.groupBox9); this.Controls.Add(this.groupBox8); this.Name = "ConfigArduplane"; - this.Size = new System.Drawing.Size(621, 456); this.Load += new System.EventHandler(this.ConfigArduplane_Load); this.groupBox3.ResumeLayout(false); ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).EndInit(); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx index 271670364a..e78598b5a3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx @@ -117,7 +117,2431 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 111, 82 + + + 78, 20 + + + + 11 + + + THR_FS_VALUE + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 413, 231 + + + 195, 108 + + + 12 + + + Throttle 0-100% + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + 111, 82 + + + 78, 20 + + + 0 + + + ARSPD_RATIO + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 414, 339 + + + 195, 108 + + + 13 + + + Airspeed m/s + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + 111, 59 + + + 78, 20 + + + 9 + + + LIM_PITCH_MIN + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 213, 339 + + + 195, 108 + + + 14 + + + Navigation Angles + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 111, 36 + + + 78, 20 + + + 7 + + + XTRK_ANGLE_CD + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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 + + + 12, 339 + + + 195, 108 + + + 15 + + + Xtrack Pids + + + groupBox15 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + 111, 13 + + + 78, 20 + + + 13 + + + KFF_PTCH2THR + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 213, 231 + + + 195, 108 + + + 16 + + + Other Mix's + + + groupBox16 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + 111, 82 + + + 78, 20 + + + 11 + + + ENRGY2THR_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 12, 231 + + + 195, 108 + + + 17 + + + Energy/Alt Pid + + + groupBox14 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + 111, 82 + + + 78, 20 + + + 0 + + + ALT2PTCH_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 414, 123 + + + 195, 108 + + + 18 + + + Nav Pitch Alt Pid + + + groupBox13 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + 111, 82 + + + 78, 20 + + + 0 + + + ARSP2PTCH_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 213, 123 + + + 195, 108 + + + 19 + + + Nav Pitch AS Pid + + + groupBox12 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + 111, 82 + + + 78, 20 + + + 11 + + + HDNG2RLL_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 12, 123 + + + 195, 108 + + + 20 + + + Nav Roll Pid + + + groupBox11 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 111, 82 + + + 78, 20 + + + 11 + + + YW2SRV_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 414, 15 + + + 195, 108 + + + 21 + + + Servo Yaw Pid + + + groupBox10 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + 111, 82 + + + 78, 20 + + + 11 + + + PTCH2SRV_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 213, 15 + + + 195, 108 + + + 22 + + + Servo Pitch Pid + + + groupBox9 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + 111, 82 + + + 78, 20 + + + 11 + + + RLL2SRV_IMAX + + + System.Windows.Forms.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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.NumericUpDown, 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 + + + 12, 15 + + + 195, 108 + + + 23 + + + Servo Roll Pid + + + groupBox8 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + 17, 17 + + True + + + 6, 13 + + + 621, 456 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigArduplane + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs index 0c3c2c5a7b..93895d3e93 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs @@ -1,230 +1,230 @@ -namespace ArdupilotMega.GCSViews.ConfigurationView -{ - partial class ConfigBatteryMonitoring - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Component Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigBatteryMonitoring)); - this.groupBox4 = new System.Windows.Forms.GroupBox(); - this.label31 = new System.Windows.Forms.Label(); - this.label32 = new System.Windows.Forms.Label(); - this.label33 = new System.Windows.Forms.Label(); - this.TXT_ampspervolt = new System.Windows.Forms.TextBox(); - this.label34 = new System.Windows.Forms.Label(); - this.TXT_divider = new System.Windows.Forms.TextBox(); - this.label35 = new System.Windows.Forms.Label(); - this.TXT_voltage = new System.Windows.Forms.TextBox(); - this.TXT_inputvoltage = new System.Windows.Forms.TextBox(); - this.TXT_measuredvoltage = new System.Windows.Forms.TextBox(); - this.label47 = new System.Windows.Forms.Label(); - this.CMB_batmonsensortype = new System.Windows.Forms.ComboBox(); - this.textBox3 = new System.Windows.Forms.TextBox(); - this.label29 = new System.Windows.Forms.Label(); - this.label30 = new System.Windows.Forms.Label(); - this.TXT_battcapacity = new System.Windows.Forms.TextBox(); - this.CMB_batmontype = new System.Windows.Forms.ComboBox(); - this.pictureBox5 = new System.Windows.Forms.PictureBox(); - this.groupBox4.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit(); - this.SuspendLayout(); - // - // groupBox4 - // - this.groupBox4.Controls.Add(this.label31); - this.groupBox4.Controls.Add(this.label32); - this.groupBox4.Controls.Add(this.label33); - this.groupBox4.Controls.Add(this.TXT_ampspervolt); - this.groupBox4.Controls.Add(this.label34); - this.groupBox4.Controls.Add(this.TXT_divider); - this.groupBox4.Controls.Add(this.label35); - this.groupBox4.Controls.Add(this.TXT_voltage); - this.groupBox4.Controls.Add(this.TXT_inputvoltage); - this.groupBox4.Controls.Add(this.TXT_measuredvoltage); - resources.ApplyResources(this.groupBox4, "groupBox4"); - this.groupBox4.Name = "groupBox4"; - this.groupBox4.TabStop = false; - // - // label31 - // - resources.ApplyResources(this.label31, "label31"); - this.label31.Name = "label31"; - // - // label32 - // - resources.ApplyResources(this.label32, "label32"); - this.label32.Name = "label32"; - // - // label33 - // - resources.ApplyResources(this.label33, "label33"); - this.label33.Name = "label33"; - // - // TXT_ampspervolt - // - resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt"); - this.TXT_ampspervolt.Name = "TXT_ampspervolt"; - this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated); - // - // label34 - // - resources.ApplyResources(this.label34, "label34"); - this.label34.Name = "label34"; - // - // TXT_divider - // - resources.ApplyResources(this.TXT_divider, "TXT_divider"); - this.TXT_divider.Name = "TXT_divider"; - this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated); - // - // label35 - // - resources.ApplyResources(this.label35, "label35"); - this.label35.Name = "label35"; - // - // TXT_voltage - // - resources.ApplyResources(this.TXT_voltage, "TXT_voltage"); - this.TXT_voltage.Name = "TXT_voltage"; - this.TXT_voltage.ReadOnly = true; - // - // TXT_inputvoltage - // - resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage"); - this.TXT_inputvoltage.Name = "TXT_inputvoltage"; - this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated); - // - // TXT_measuredvoltage - // - resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage"); - this.TXT_measuredvoltage.Name = "TXT_measuredvoltage"; - this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated); - // - // label47 - // - resources.ApplyResources(this.label47, "label47"); - this.label47.Name = "label47"; - // - // CMB_batmonsensortype - // - this.CMB_batmonsensortype.FormattingEnabled = true; - this.CMB_batmonsensortype.Items.AddRange(new object[] { - resources.GetString("CMB_batmonsensortype.Items"), - resources.GetString("CMB_batmonsensortype.Items1"), - resources.GetString("CMB_batmonsensortype.Items2"), - resources.GetString("CMB_batmonsensortype.Items3")}); - resources.ApplyResources(this.CMB_batmonsensortype, "CMB_batmonsensortype"); - this.CMB_batmonsensortype.Name = "CMB_batmonsensortype"; - this.CMB_batmonsensortype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmonsensortype_SelectedIndexChanged); - // - // textBox3 - // - resources.ApplyResources(this.textBox3, "textBox3"); - this.textBox3.Name = "textBox3"; - this.textBox3.ReadOnly = true; - // - // label29 - // - resources.ApplyResources(this.label29, "label29"); - this.label29.Name = "label29"; - // - // label30 - // - resources.ApplyResources(this.label30, "label30"); - this.label30.Name = "label30"; - // - // TXT_battcapacity - // - resources.ApplyResources(this.TXT_battcapacity, "TXT_battcapacity"); - this.TXT_battcapacity.Name = "TXT_battcapacity"; - this.TXT_battcapacity.Validated += new System.EventHandler(this.TXT_battcapacity_Validated); - // - // CMB_batmontype - // - this.CMB_batmontype.FormattingEnabled = true; - this.CMB_batmontype.Items.AddRange(new object[] { - resources.GetString("CMB_batmontype.Items"), - resources.GetString("CMB_batmontype.Items1"), - resources.GetString("CMB_batmontype.Items2")}); - resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype"); - this.CMB_batmontype.Name = "CMB_batmontype"; - this.CMB_batmontype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmontype_SelectedIndexChanged); - // - // 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; - // - // ConfigBatteryMonitoring - // - resources.ApplyResources(this, "$this"); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.groupBox4); - this.Controls.Add(this.label47); - this.Controls.Add(this.CMB_batmonsensortype); - this.Controls.Add(this.textBox3); - this.Controls.Add(this.label29); - this.Controls.Add(this.label30); - this.Controls.Add(this.TXT_battcapacity); - this.Controls.Add(this.CMB_batmontype); - this.Controls.Add(this.pictureBox5); - this.Name = "ConfigBatteryMonitoring"; - this.Load += new System.EventHandler(this.ConfigBatteryMonitoring_Load); - this.groupBox4.ResumeLayout(false); - this.groupBox4.PerformLayout(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit(); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private System.Windows.Forms.GroupBox groupBox4; - private System.Windows.Forms.Label label31; - private System.Windows.Forms.Label label32; - private System.Windows.Forms.Label label33; - private System.Windows.Forms.TextBox TXT_ampspervolt; - private System.Windows.Forms.Label label34; - private System.Windows.Forms.TextBox TXT_divider; - private System.Windows.Forms.Label label35; - private System.Windows.Forms.TextBox TXT_voltage; - private System.Windows.Forms.TextBox TXT_inputvoltage; - private System.Windows.Forms.TextBox TXT_measuredvoltage; - private System.Windows.Forms.Label label47; - private System.Windows.Forms.ComboBox CMB_batmonsensortype; - private System.Windows.Forms.TextBox textBox3; - private System.Windows.Forms.Label label29; - private System.Windows.Forms.Label label30; - private System.Windows.Forms.TextBox TXT_battcapacity; - private System.Windows.Forms.ComboBox CMB_batmontype; - private System.Windows.Forms.PictureBox pictureBox5; - } -} +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class ConfigBatteryMonitoring + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Component Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigBatteryMonitoring)); + this.groupBox4 = new System.Windows.Forms.GroupBox(); + this.label31 = new System.Windows.Forms.Label(); + this.label32 = new System.Windows.Forms.Label(); + this.label33 = new System.Windows.Forms.Label(); + this.TXT_ampspervolt = new System.Windows.Forms.TextBox(); + this.label34 = new System.Windows.Forms.Label(); + this.TXT_divider = new System.Windows.Forms.TextBox(); + this.label35 = new System.Windows.Forms.Label(); + this.TXT_voltage = new System.Windows.Forms.TextBox(); + this.TXT_inputvoltage = new System.Windows.Forms.TextBox(); + this.TXT_measuredvoltage = new System.Windows.Forms.TextBox(); + this.label47 = new System.Windows.Forms.Label(); + this.CMB_batmonsensortype = new System.Windows.Forms.ComboBox(); + this.textBox3 = new System.Windows.Forms.TextBox(); + this.label29 = new System.Windows.Forms.Label(); + this.label30 = new System.Windows.Forms.Label(); + this.TXT_battcapacity = new System.Windows.Forms.TextBox(); + this.CMB_batmontype = new System.Windows.Forms.ComboBox(); + this.pictureBox5 = new System.Windows.Forms.PictureBox(); + this.groupBox4.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit(); + this.SuspendLayout(); + // + // groupBox4 + // + this.groupBox4.Controls.Add(this.label31); + this.groupBox4.Controls.Add(this.label32); + this.groupBox4.Controls.Add(this.label33); + this.groupBox4.Controls.Add(this.TXT_ampspervolt); + this.groupBox4.Controls.Add(this.label34); + this.groupBox4.Controls.Add(this.TXT_divider); + this.groupBox4.Controls.Add(this.label35); + this.groupBox4.Controls.Add(this.TXT_voltage); + this.groupBox4.Controls.Add(this.TXT_inputvoltage); + this.groupBox4.Controls.Add(this.TXT_measuredvoltage); + resources.ApplyResources(this.groupBox4, "groupBox4"); + this.groupBox4.Name = "groupBox4"; + this.groupBox4.TabStop = false; + // + // label31 + // + resources.ApplyResources(this.label31, "label31"); + this.label31.Name = "label31"; + // + // label32 + // + resources.ApplyResources(this.label32, "label32"); + this.label32.Name = "label32"; + // + // label33 + // + resources.ApplyResources(this.label33, "label33"); + this.label33.Name = "label33"; + // + // TXT_ampspervolt + // + resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt"); + this.TXT_ampspervolt.Name = "TXT_ampspervolt"; + this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated); + // + // label34 + // + resources.ApplyResources(this.label34, "label34"); + this.label34.Name = "label34"; + // + // TXT_divider + // + resources.ApplyResources(this.TXT_divider, "TXT_divider"); + this.TXT_divider.Name = "TXT_divider"; + this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated); + // + // label35 + // + resources.ApplyResources(this.label35, "label35"); + this.label35.Name = "label35"; + // + // TXT_voltage + // + resources.ApplyResources(this.TXT_voltage, "TXT_voltage"); + this.TXT_voltage.Name = "TXT_voltage"; + this.TXT_voltage.ReadOnly = true; + // + // TXT_inputvoltage + // + resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage"); + this.TXT_inputvoltage.Name = "TXT_inputvoltage"; + this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated); + // + // TXT_measuredvoltage + // + resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage"); + this.TXT_measuredvoltage.Name = "TXT_measuredvoltage"; + this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated); + // + // label47 + // + resources.ApplyResources(this.label47, "label47"); + this.label47.Name = "label47"; + // + // CMB_batmonsensortype + // + this.CMB_batmonsensortype.FormattingEnabled = true; + this.CMB_batmonsensortype.Items.AddRange(new object[] { + resources.GetString("CMB_batmonsensortype.Items"), + resources.GetString("CMB_batmonsensortype.Items1"), + resources.GetString("CMB_batmonsensortype.Items2"), + resources.GetString("CMB_batmonsensortype.Items3")}); + resources.ApplyResources(this.CMB_batmonsensortype, "CMB_batmonsensortype"); + this.CMB_batmonsensortype.Name = "CMB_batmonsensortype"; + this.CMB_batmonsensortype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmonsensortype_SelectedIndexChanged); + // + // textBox3 + // + resources.ApplyResources(this.textBox3, "textBox3"); + this.textBox3.Name = "textBox3"; + this.textBox3.ReadOnly = true; + // + // label29 + // + resources.ApplyResources(this.label29, "label29"); + this.label29.Name = "label29"; + // + // label30 + // + resources.ApplyResources(this.label30, "label30"); + this.label30.Name = "label30"; + // + // TXT_battcapacity + // + resources.ApplyResources(this.TXT_battcapacity, "TXT_battcapacity"); + this.TXT_battcapacity.Name = "TXT_battcapacity"; + this.TXT_battcapacity.Validated += new System.EventHandler(this.TXT_battcapacity_Validated); + // + // CMB_batmontype + // + this.CMB_batmontype.FormattingEnabled = true; + this.CMB_batmontype.Items.AddRange(new object[] { + resources.GetString("CMB_batmontype.Items"), + resources.GetString("CMB_batmontype.Items1"), + resources.GetString("CMB_batmontype.Items2")}); + resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype"); + this.CMB_batmontype.Name = "CMB_batmontype"; + this.CMB_batmontype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmontype_SelectedIndexChanged); + // + // 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; + // + // ConfigBatteryMonitoring + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.groupBox4); + this.Controls.Add(this.label47); + this.Controls.Add(this.CMB_batmonsensortype); + this.Controls.Add(this.textBox3); + this.Controls.Add(this.label29); + this.Controls.Add(this.label30); + this.Controls.Add(this.TXT_battcapacity); + this.Controls.Add(this.CMB_batmontype); + this.Controls.Add(this.pictureBox5); + this.Name = "ConfigBatteryMonitoring"; + this.Load += new System.EventHandler(this.ConfigBatteryMonitoring_Load); + this.groupBox4.ResumeLayout(false); + this.groupBox4.PerformLayout(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.GroupBox groupBox4; + private System.Windows.Forms.Label label31; + private System.Windows.Forms.Label label32; + private System.Windows.Forms.Label label33; + private System.Windows.Forms.TextBox TXT_ampspervolt; + private System.Windows.Forms.Label label34; + private System.Windows.Forms.TextBox TXT_divider; + private System.Windows.Forms.Label label35; + private System.Windows.Forms.TextBox TXT_voltage; + private System.Windows.Forms.TextBox TXT_inputvoltage; + private System.Windows.Forms.TextBox TXT_measuredvoltage; + private System.Windows.Forms.Label label47; + private System.Windows.Forms.ComboBox CMB_batmonsensortype; + private System.Windows.Forms.TextBox textBox3; + private System.Windows.Forms.Label label29; + private System.Windows.Forms.Label label30; + private System.Windows.Forms.TextBox TXT_battcapacity; + private System.Windows.Forms.ComboBox CMB_batmontype; + private System.Windows.Forms.PictureBox pictureBox5; + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx index 30ba0ba68e..8e44b5f462 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx @@ -1,678 +1,678 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - True - - - - NoControl - - - - 5, 16 - - - 2, 0, 2, 0 - - - 110, 13 - - - 29 - - - 1. APM Input voltage: - - - label31 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 0 - - - True - - - NoControl - - - 5, 38 - - - 2, 0, 2, 0 - - - 142, 13 - - - 30 - - - 2. Measured battery voltage: - - - label32 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 1 - - - True - - - NoControl - - - 5, 60 - - - 2, 0, 2, 0 - - - 135, 13 - - - 31 - - - 3. Battery voltage (Calced): - - - label33 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 2 - - - 149, 100 - - - 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 - - - groupBox4 - - - 3 - - - True - - - NoControl - - - 5, 81 - - - 2, 0, 2, 0 - - - 134, 13 - - - 32 - - - 4. Voltage divider (Calced): - - - label34 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 4 - - - 149, 78 - - - 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 - - - groupBox4 - - - 5 - - - True - - - NoControl - - - 6, 103 - - - 2, 0, 2, 0 - - - 101, 13 - - - 33 - - - 5. Amperes per volt: - - - label35 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 6 - - - 149, 57 - - - 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 - - - groupBox4 - - - 7 - - - 149, 13 - - - 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 - - - groupBox4 - - - 8 - - - 149, 35 - - - 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 - - - groupBox4 - - - 9 - - - 14, 172 - - - 238, 131 - - - 50 - - - Calibration - - - groupBox4 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - NoControl - - - 106, 71 - - - 42, 13 - - - 49 - - - Sensor - - - label47 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 1 - - - 0: Other - - - 1: AttoPilot 45A - - - 2: AttoPilot 90A - - - 3: AttoPilot 180A - - - 160, 68 - - - 121, 21 - - - 48 - - - CMB_batmonsensortype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - Microsoft Sans Serif, 8.25pt - - - 282, 172 - - - 2, 2, 2, 2 - - - True - - - 219, 131 - - - 47 - - - Voltage sensor calibration: -To calibrate your sensor, use a multimeter to measure the voltage coming out of your ESC's battery-elimination circuit (these are black and red wires in the three-wire cable that is powering your APM board). -Then subtract 0.3v from that value and enter it in field #1 at left. - - - - textBox3 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - - - True - - - NoControl - - - 288, 45 - - - 48, 13 - - - 43 - - - Capacity - - - label29 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 4 - - - NoControl - - - 106, 45 - - - 42, 13 - - - 44 - - - Monitor - - - label30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - 349, 42 - - - 83, 20 - - - 45 - - - TXT_battcapacity - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - 0: Disabled - - - 3: Battery Volts - - - 4: Volts & Current - - - 160, 41 - - - 121, 21 - - - 46 - - - CMB_batmontype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - Zoom - - - NoControl - - - 14, 16 - - - 75, 75 - - - 42 - - - pictureBox5 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 8 - - - True - - - 6, 13 - - - 518, 322 - - - ConfigBatteryMonitoring - - - System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + True + + + + NoControl + + + + 5, 16 + + + 2, 0, 2, 0 + + + 110, 13 + + + 29 + + + 1. APM Input voltage: + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 0 + + + True + + + NoControl + + + 5, 38 + + + 2, 0, 2, 0 + + + 142, 13 + + + 30 + + + 2. Measured battery voltage: + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 1 + + + True + + + NoControl + + + 5, 60 + + + 2, 0, 2, 0 + + + 135, 13 + + + 31 + + + 3. Battery voltage (Calced): + + + label33 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 2 + + + 149, 100 + + + 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 + + + groupBox4 + + + 3 + + + True + + + NoControl + + + 5, 81 + + + 2, 0, 2, 0 + + + 134, 13 + + + 32 + + + 4. Voltage divider (Calced): + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 4 + + + 149, 78 + + + 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 + + + groupBox4 + + + 5 + + + True + + + NoControl + + + 6, 103 + + + 2, 0, 2, 0 + + + 101, 13 + + + 33 + + + 5. Amperes per volt: + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 6 + + + 149, 57 + + + 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 + + + groupBox4 + + + 7 + + + 149, 13 + + + 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 + + + groupBox4 + + + 8 + + + 149, 35 + + + 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 + + + groupBox4 + + + 9 + + + 14, 172 + + + 238, 131 + + + 50 + + + Calibration + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + NoControl + + + 106, 71 + + + 42, 13 + + + 49 + + + Sensor + + + label47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + 0: Other + + + 1: AttoPilot 45A + + + 2: AttoPilot 90A + + + 3: AttoPilot 180A + + + 160, 68 + + + 121, 21 + + + 48 + + + CMB_batmonsensortype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + Microsoft Sans Serif, 8.25pt + + + 282, 172 + + + 2, 2, 2, 2 + + + True + + + 219, 131 + + + 47 + + + Voltage sensor calibration: +To calibrate your sensor, use a multimeter to measure the voltage coming out of your ESC's battery-elimination circuit (these are black and red wires in the three-wire cable that is powering your APM board). +Then subtract 0.3v from that value and enter it in field #1 at left. + + + + textBox3 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + True + + + NoControl + + + 288, 45 + + + 48, 13 + + + 43 + + + Capacity + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + NoControl + + + 106, 45 + + + 42, 13 + + + 44 + + + Monitor + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + 349, 42 + + + 83, 20 + + + 45 + + + TXT_battcapacity + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + 0: Disabled + + + 3: Battery Volts + + + 4: Volts & Current + + + 160, 41 + + + 121, 21 + + + 46 + + + CMB_batmontype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + Zoom + + + NoControl + + + 14, 16 + + + 75, 75 + + + 42 + + + pictureBox5 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + True + + + 6, 13 + + + 518, 322 + + + ConfigBatteryMonitoring + + + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx index f96892c423..8c530d8b9b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx @@ -1,496 +1,178 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 遥控输入 - - - 模式 - - - 硬件 - - - 电池 - - - AC2 直升机 - - - 上降副翼 (Elevon) 配置 - - - - 115, 17 - - - Elevons CH2 逆转 - - - 91, 17 - - - Elevons 逆转 - - - 115, 17 - - - Elevons CH1 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 校准遥控 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 64, 13 - - - 当前 PWM: - - - 58, 13 - - - 当前模式: - - - 64, 13 - - - 飞行模式 6 - - - 64, 13 - - - 飞行模式 5 - - - 64, 13 - - - 飞行模式 4 - - - 64, 13 - - - 飞行模式 3 - - - 64, 13 - - - 飞行模式 2 - - - 64, 13 - - - 飞行模式 1 - - - 保存模式 - - - 十进制, 2° 3' W 就是 -2.3 - - - 启用光流 - - - 67, 13 - - - 磁偏角网站 - - - 磁偏角 - - - 启用空速计 - - - 启用声纳 - - - 启用罗盘 - - - 58, 13 - - - 输入电压: - - - 94, 13 - - - 测量的电池电压: - - - 58, 13 - - - 电池电压: - - - 52, 13 - - - 分 压 比: - - - 63, 13 - - - 安培/伏特: - - - 48, 18 - - - 传感器 - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + 58, 13 + + + 输入电压: + + + 94, 13 + + + 测量的电池电压: + + + 58, 13 + + + 电池电压: + + + 52, 13 + + + 分 压 比: + + + 63, 13 + + + 安培/伏特: + + + 校准 + + + 48, 18 + + + 传感器 + + 电压传感器校准: 1. 测量APM输入电压,输入到下方的文本框中 2. 测量电池电压,输入到下方的文本框中 -3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中 - - - 31, 13 - - - 容量 - - - 48, 13 - - - 监控器 - - - 175, 13 - - - 设置水平面的默认加速度计偏移 - - - 261, 13 - - - 注: 图片只是用于展示,设置可以用于六轴等机架 - - - 93, 13 - - - 机架设置 (+ 或 x) - - - 找平 - - - 手动 - - - 手动 - - - 31, 13 - - - 感度 - - - 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 - - - 最大俯仰 - - - 55, 13 - - - 最大侧倾 - - - 55, 13 - - - 舵机行程 - - - 79, 13 - - - 斜盘水平微调 - - - 79, 13 - - - 斜盘舵机位置 - - - 重置 - - - 重置 APM 为默认设置 - - - APM设置 - +3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中 + + + 31, 13 + + + 容量 + + + 48, 13 + + + 监控器 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs index 6117c75a51..ed3be8b223 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs @@ -1,318 +1,318 @@ -namespace ArdupilotMega.GCSViews.ConfigurationView -{ - partial class ConfigFlightModes - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Component Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - this.components = new System.ComponentModel.Container(); - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigFlightModes)); - this.CB_simple6 = new System.Windows.Forms.CheckBox(); - this.CB_simple5 = new System.Windows.Forms.CheckBox(); - this.CB_simple4 = new System.Windows.Forms.CheckBox(); - this.CB_simple3 = new System.Windows.Forms.CheckBox(); - this.CB_simple2 = new System.Windows.Forms.CheckBox(); - this.CB_simple1 = new System.Windows.Forms.CheckBox(); - this.label14 = new System.Windows.Forms.Label(); - this.LBL_flightmodepwm = new System.Windows.Forms.Label(); - this.label13 = new System.Windows.Forms.Label(); - this.lbl_currentmode = new System.Windows.Forms.Label(); - this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); - this.label12 = new System.Windows.Forms.Label(); - this.label11 = new System.Windows.Forms.Label(); - this.label10 = new System.Windows.Forms.Label(); - this.label9 = new System.Windows.Forms.Label(); - this.label8 = new System.Windows.Forms.Label(); - this.label7 = new System.Windows.Forms.Label(); - this.label6 = new System.Windows.Forms.Label(); - this.CMB_fmode6 = new System.Windows.Forms.ComboBox(); - this.label5 = new System.Windows.Forms.Label(); - this.CMB_fmode5 = new System.Windows.Forms.ComboBox(); - this.label4 = new System.Windows.Forms.Label(); - this.CMB_fmode4 = new System.Windows.Forms.ComboBox(); - this.label3 = new System.Windows.Forms.Label(); - this.CMB_fmode3 = new System.Windows.Forms.ComboBox(); - this.label2 = new System.Windows.Forms.Label(); - this.CMB_fmode2 = new System.Windows.Forms.ComboBox(); - this.label1 = new System.Windows.Forms.Label(); - this.CMB_fmode1 = new System.Windows.Forms.ComboBox(); - this.BUT_SaveModes = new ArdupilotMega.MyButton(); - ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); - this.SuspendLayout(); - // - // CB_simple6 - // - resources.ApplyResources(this.CB_simple6, "CB_simple6"); - this.CB_simple6.Name = "CB_simple6"; - this.CB_simple6.UseVisualStyleBackColor = true; - // - // CB_simple5 - // - resources.ApplyResources(this.CB_simple5, "CB_simple5"); - this.CB_simple5.Name = "CB_simple5"; - this.CB_simple5.UseVisualStyleBackColor = true; - // - // CB_simple4 - // - resources.ApplyResources(this.CB_simple4, "CB_simple4"); - this.CB_simple4.Name = "CB_simple4"; - this.CB_simple4.UseVisualStyleBackColor = true; - // - // CB_simple3 - // - resources.ApplyResources(this.CB_simple3, "CB_simple3"); - this.CB_simple3.Name = "CB_simple3"; - this.CB_simple3.UseVisualStyleBackColor = true; - // - // CB_simple2 - // - resources.ApplyResources(this.CB_simple2, "CB_simple2"); - this.CB_simple2.Name = "CB_simple2"; - this.CB_simple2.UseVisualStyleBackColor = true; - // - // CB_simple1 - // - resources.ApplyResources(this.CB_simple1, "CB_simple1"); - this.CB_simple1.Name = "CB_simple1"; - this.CB_simple1.UseVisualStyleBackColor = true; - // - // label14 - // - resources.ApplyResources(this.label14, "label14"); - this.label14.Name = "label14"; - // - // LBL_flightmodepwm - // - resources.ApplyResources(this.LBL_flightmodepwm, "LBL_flightmodepwm"); - this.LBL_flightmodepwm.Name = "LBL_flightmodepwm"; - // - // label13 - // - resources.ApplyResources(this.label13, "label13"); - this.label13.Name = "label13"; - // - // 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"; - // - // label12 - // - resources.ApplyResources(this.label12, "label12"); - this.label12.Name = "label12"; - // - // label11 - // - resources.ApplyResources(this.label11, "label11"); - this.label11.Name = "label11"; - // - // label10 - // - resources.ApplyResources(this.label10, "label10"); - this.label10.Name = "label10"; - // - // label9 - // - resources.ApplyResources(this.label9, "label9"); - this.label9.Name = "label9"; - // - // label8 - // - resources.ApplyResources(this.label8, "label8"); - this.label8.Name = "label8"; - // - // label7 - // - resources.ApplyResources(this.label7, "label7"); - this.label7.Name = "label7"; - // - // label6 - // - resources.ApplyResources(this.label6, "label6"); - this.label6.Name = "label6"; - // - // 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"; - // - // label5 - // - resources.ApplyResources(this.label5, "label5"); - this.label5.Name = "label5"; - // - // 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"; - // - // label4 - // - resources.ApplyResources(this.label4, "label4"); - this.label4.Name = "label4"; - // - // 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"; - // - // label3 - // - resources.ApplyResources(this.label3, "label3"); - this.label3.Name = "label3"; - // - // 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"; - // - // label2 - // - resources.ApplyResources(this.label2, "label2"); - this.label2.Name = "label2"; - // - // 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"; - // - // label1 - // - resources.ApplyResources(this.label1, "label1"); - this.label1.Name = "label1"; - // - // 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"; - // - // BUT_SaveModes - // - resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes"); - this.BUT_SaveModes.Name = "BUT_SaveModes"; - this.BUT_SaveModes.UseVisualStyleBackColor = true; - this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click); - // - // ConfigFlightModes - // - resources.ApplyResources(this, "$this"); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.CB_simple6); - this.Controls.Add(this.CB_simple5); - this.Controls.Add(this.CB_simple4); - this.Controls.Add(this.CB_simple3); - this.Controls.Add(this.CB_simple2); - this.Controls.Add(this.CB_simple1); - this.Controls.Add(this.label14); - this.Controls.Add(this.LBL_flightmodepwm); - this.Controls.Add(this.label13); - this.Controls.Add(this.lbl_currentmode); - this.Controls.Add(this.label12); - this.Controls.Add(this.label11); - this.Controls.Add(this.label10); - this.Controls.Add(this.label9); - this.Controls.Add(this.label8); - this.Controls.Add(this.label7); - this.Controls.Add(this.label6); - this.Controls.Add(this.CMB_fmode6); - this.Controls.Add(this.label5); - this.Controls.Add(this.CMB_fmode5); - this.Controls.Add(this.label4); - this.Controls.Add(this.CMB_fmode4); - this.Controls.Add(this.label3); - this.Controls.Add(this.CMB_fmode3); - this.Controls.Add(this.label2); - this.Controls.Add(this.CMB_fmode2); - this.Controls.Add(this.label1); - this.Controls.Add(this.CMB_fmode1); - this.Controls.Add(this.BUT_SaveModes); - this.Name = "ConfigFlightModes"; - this.Load += new System.EventHandler(this.ConfigFlightModes_Load); - ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private System.Windows.Forms.CheckBox CB_simple6; - private System.Windows.Forms.CheckBox CB_simple5; - private System.Windows.Forms.CheckBox CB_simple4; - private System.Windows.Forms.CheckBox CB_simple3; - private System.Windows.Forms.CheckBox CB_simple2; - private System.Windows.Forms.CheckBox CB_simple1; - private System.Windows.Forms.Label label14; - private System.Windows.Forms.Label LBL_flightmodepwm; - private System.Windows.Forms.Label label13; - private System.Windows.Forms.Label lbl_currentmode; - private System.Windows.Forms.Label label12; - private System.Windows.Forms.Label label11; - private System.Windows.Forms.Label label10; - private System.Windows.Forms.Label label9; - private System.Windows.Forms.Label label8; - private System.Windows.Forms.Label label7; - private System.Windows.Forms.Label label6; - private System.Windows.Forms.ComboBox CMB_fmode6; - private System.Windows.Forms.Label label5; - private System.Windows.Forms.ComboBox CMB_fmode5; - private System.Windows.Forms.Label label4; - private System.Windows.Forms.ComboBox CMB_fmode4; - private System.Windows.Forms.Label label3; - private System.Windows.Forms.ComboBox CMB_fmode3; - private System.Windows.Forms.Label label2; - private System.Windows.Forms.ComboBox CMB_fmode2; - private System.Windows.Forms.Label label1; - private System.Windows.Forms.ComboBox CMB_fmode1; - private MyButton BUT_SaveModes; - private System.Windows.Forms.BindingSource currentStateBindingSource; - } -} +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class ConfigFlightModes + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Component Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + this.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigFlightModes)); + this.CB_simple6 = new System.Windows.Forms.CheckBox(); + this.CB_simple5 = new System.Windows.Forms.CheckBox(); + this.CB_simple4 = new System.Windows.Forms.CheckBox(); + this.CB_simple3 = new System.Windows.Forms.CheckBox(); + this.CB_simple2 = new System.Windows.Forms.CheckBox(); + this.CB_simple1 = new System.Windows.Forms.CheckBox(); + this.label14 = new System.Windows.Forms.Label(); + this.LBL_flightmodepwm = new System.Windows.Forms.Label(); + this.label13 = new System.Windows.Forms.Label(); + this.lbl_currentmode = new System.Windows.Forms.Label(); + this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); + this.label12 = new System.Windows.Forms.Label(); + this.label11 = new System.Windows.Forms.Label(); + this.label10 = new System.Windows.Forms.Label(); + this.label9 = new System.Windows.Forms.Label(); + this.label8 = new System.Windows.Forms.Label(); + this.label7 = new System.Windows.Forms.Label(); + this.label6 = new System.Windows.Forms.Label(); + this.CMB_fmode6 = new System.Windows.Forms.ComboBox(); + this.label5 = new System.Windows.Forms.Label(); + this.CMB_fmode5 = new System.Windows.Forms.ComboBox(); + this.label4 = new System.Windows.Forms.Label(); + this.CMB_fmode4 = new System.Windows.Forms.ComboBox(); + this.label3 = new System.Windows.Forms.Label(); + this.CMB_fmode3 = new System.Windows.Forms.ComboBox(); + this.label2 = new System.Windows.Forms.Label(); + this.CMB_fmode2 = new System.Windows.Forms.ComboBox(); + this.label1 = new System.Windows.Forms.Label(); + this.CMB_fmode1 = new System.Windows.Forms.ComboBox(); + this.BUT_SaveModes = new ArdupilotMega.MyButton(); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); + this.SuspendLayout(); + // + // CB_simple6 + // + resources.ApplyResources(this.CB_simple6, "CB_simple6"); + this.CB_simple6.Name = "CB_simple6"; + this.CB_simple6.UseVisualStyleBackColor = true; + // + // CB_simple5 + // + resources.ApplyResources(this.CB_simple5, "CB_simple5"); + this.CB_simple5.Name = "CB_simple5"; + this.CB_simple5.UseVisualStyleBackColor = true; + // + // CB_simple4 + // + resources.ApplyResources(this.CB_simple4, "CB_simple4"); + this.CB_simple4.Name = "CB_simple4"; + this.CB_simple4.UseVisualStyleBackColor = true; + // + // CB_simple3 + // + resources.ApplyResources(this.CB_simple3, "CB_simple3"); + this.CB_simple3.Name = "CB_simple3"; + this.CB_simple3.UseVisualStyleBackColor = true; + // + // CB_simple2 + // + resources.ApplyResources(this.CB_simple2, "CB_simple2"); + this.CB_simple2.Name = "CB_simple2"; + this.CB_simple2.UseVisualStyleBackColor = true; + // + // CB_simple1 + // + resources.ApplyResources(this.CB_simple1, "CB_simple1"); + this.CB_simple1.Name = "CB_simple1"; + this.CB_simple1.UseVisualStyleBackColor = true; + // + // label14 + // + resources.ApplyResources(this.label14, "label14"); + this.label14.Name = "label14"; + // + // LBL_flightmodepwm + // + resources.ApplyResources(this.LBL_flightmodepwm, "LBL_flightmodepwm"); + this.LBL_flightmodepwm.Name = "LBL_flightmodepwm"; + // + // label13 + // + resources.ApplyResources(this.label13, "label13"); + this.label13.Name = "label13"; + // + // 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"; + // + // label12 + // + resources.ApplyResources(this.label12, "label12"); + this.label12.Name = "label12"; + // + // label11 + // + resources.ApplyResources(this.label11, "label11"); + this.label11.Name = "label11"; + // + // label10 + // + resources.ApplyResources(this.label10, "label10"); + this.label10.Name = "label10"; + // + // label9 + // + resources.ApplyResources(this.label9, "label9"); + this.label9.Name = "label9"; + // + // label8 + // + resources.ApplyResources(this.label8, "label8"); + this.label8.Name = "label8"; + // + // label7 + // + resources.ApplyResources(this.label7, "label7"); + this.label7.Name = "label7"; + // + // label6 + // + resources.ApplyResources(this.label6, "label6"); + this.label6.Name = "label6"; + // + // 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"; + // + // label5 + // + resources.ApplyResources(this.label5, "label5"); + this.label5.Name = "label5"; + // + // 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"; + // + // label4 + // + resources.ApplyResources(this.label4, "label4"); + this.label4.Name = "label4"; + // + // 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"; + // + // label3 + // + resources.ApplyResources(this.label3, "label3"); + this.label3.Name = "label3"; + // + // 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"; + // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // + // 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"; + // + // label1 + // + resources.ApplyResources(this.label1, "label1"); + this.label1.Name = "label1"; + // + // 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"; + // + // BUT_SaveModes + // + resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes"); + this.BUT_SaveModes.Name = "BUT_SaveModes"; + this.BUT_SaveModes.UseVisualStyleBackColor = true; + this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click); + // + // ConfigFlightModes + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.CB_simple6); + this.Controls.Add(this.CB_simple5); + this.Controls.Add(this.CB_simple4); + this.Controls.Add(this.CB_simple3); + this.Controls.Add(this.CB_simple2); + this.Controls.Add(this.CB_simple1); + this.Controls.Add(this.label14); + this.Controls.Add(this.LBL_flightmodepwm); + this.Controls.Add(this.label13); + this.Controls.Add(this.lbl_currentmode); + this.Controls.Add(this.label12); + this.Controls.Add(this.label11); + this.Controls.Add(this.label10); + this.Controls.Add(this.label9); + this.Controls.Add(this.label8); + this.Controls.Add(this.label7); + this.Controls.Add(this.label6); + this.Controls.Add(this.CMB_fmode6); + this.Controls.Add(this.label5); + this.Controls.Add(this.CMB_fmode5); + this.Controls.Add(this.label4); + this.Controls.Add(this.CMB_fmode4); + this.Controls.Add(this.label3); + this.Controls.Add(this.CMB_fmode3); + this.Controls.Add(this.label2); + this.Controls.Add(this.CMB_fmode2); + this.Controls.Add(this.label1); + this.Controls.Add(this.CMB_fmode1); + this.Controls.Add(this.BUT_SaveModes); + this.Name = "ConfigFlightModes"; + this.Load += new System.EventHandler(this.ConfigFlightModes_Load); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.CheckBox CB_simple6; + private System.Windows.Forms.CheckBox CB_simple5; + private System.Windows.Forms.CheckBox CB_simple4; + private System.Windows.Forms.CheckBox CB_simple3; + private System.Windows.Forms.CheckBox CB_simple2; + private System.Windows.Forms.CheckBox CB_simple1; + private System.Windows.Forms.Label label14; + private System.Windows.Forms.Label LBL_flightmodepwm; + private System.Windows.Forms.Label label13; + private System.Windows.Forms.Label lbl_currentmode; + private System.Windows.Forms.Label label12; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label8; + private System.Windows.Forms.Label label7; + private System.Windows.Forms.Label label6; + private System.Windows.Forms.ComboBox CMB_fmode6; + private System.Windows.Forms.Label label5; + private System.Windows.Forms.ComboBox CMB_fmode5; + private System.Windows.Forms.Label label4; + private System.Windows.Forms.ComboBox CMB_fmode4; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.ComboBox CMB_fmode3; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.ComboBox CMB_fmode2; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.ComboBox CMB_fmode1; + private MyButton BUT_SaveModes; + private System.Windows.Forms.BindingSource currentStateBindingSource; + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx index a4992dbe3e..7f2a0fb988 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx @@ -1,978 +1,978 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - True - - - - NoControl - - - - 232, 200 - - - 2, 2, 2, 2 - - - 87, 17 - - - 148 - - - Simple Mode - - - CB_simple6 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - True - - - NoControl - - - 232, 173 - - - 2, 2, 2, 2 - - - 87, 17 - - - 147 - - - Simple Mode - - - CB_simple5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 1 - - - True - - - NoControl - - - 232, 146 - - - 2, 2, 2, 2 - - - 87, 17 - - - 146 - - - Simple Mode - - - CB_simple4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - True - - - NoControl - - - 232, 119 - - - 2, 2, 2, 2 - - - 87, 17 - - - 145 - - - Simple Mode - - - CB_simple3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - - - True - - - NoControl - - - 232, 92 - - - 2, 2, 2, 2 - - - 87, 17 - - - 144 - - - Simple Mode - - - CB_simple2 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 4 - - - True - - - NoControl - - - 232, 65 - - - 2, 2, 2, 2 - - - 87, 17 - - - 143 - - - Simple Mode - - - CB_simple1 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - True - - - NoControl - - - 94, 32 - - - 74, 13 - - - 142 - - - Current PWM: - - - label14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - True - - - NoControl - - - 174, 32 - - - 13, 13 - - - 141 - - - 0 - - - LBL_flightmodepwm - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - True - - - NoControl - - - 94, 15 - - - 74, 13 - - - 140 - - - Current Mode: - - - label13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 8 - - - True - - - 17, 17 - - - NoControl - - - 174, 15 - - - 42, 13 - - - 139 - - - Manual - - - lbl_currentmode - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 9 - - - True - - - NoControl - - - 358, 66 - - - 76, 13 - - - 138 - - - PWM 0 - 1230 - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - - True - - - NoControl - - - 358, 201 - - - 70, 13 - - - 137 - - - PWM 1750 + - - - label11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 11 - - - True - - - NoControl - - - 358, 174 - - - 94, 13 - - - 136 - - - PWM 1621 - 1749 - - - label10 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 12 - - - True - - - NoControl - - - 358, 147 - - - 94, 13 - - - 135 - - - PWM 1491 - 1620 - - - label9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 13 - - - True - - - NoControl - - - 358, 120 - - - 94, 13 - - - 134 - - - PWM 1361 - 1490 - - - label8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 14 - - - True - - - NoControl - - - 358, 93 - - - 94, 13 - - - 133 - - - PWM 1231 - 1360 - - - label7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 15 - - - True - - - NoControl - - - 20, 201 - - - 71, 13 - - - 131 - - - Flight Mode 6 - - - label6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 16 - - - 97, 198 - - - 121, 21 - - - 130 - - - CMB_fmode6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 17 - - - True - - - NoControl - - - 20, 174 - - - 71, 13 - - - 129 - - - Flight Mode 5 - - - label5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 18 - - - 97, 171 - - - 121, 21 - - - 128 - - - CMB_fmode5 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 19 - - - True - - - NoControl - - - 20, 147 - - - 71, 13 - - - 127 - - - Flight Mode 4 - - - label4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 20 - - - 97, 144 - - - 121, 21 - - - 126 - - - CMB_fmode4 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 21 - - - True - - - NoControl - - - 20, 120 - - - 71, 13 - - - 125 - - - Flight Mode 3 - - - label3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 22 - - - 97, 117 - - - 121, 21 - - - 124 - - - CMB_fmode3 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 23 - - - True - - - NoControl - - - 20, 93 - - - 71, 13 - - - 123 - - - Flight Mode 2 - - - label2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 24 - - - 97, 90 - - - 121, 21 - - - 122 - - - CMB_fmode2 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 25 - - - True - - - NoControl - - - 20, 66 - - - 71, 13 - - - 121 - - - Flight Mode 1 - - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 26 - - - 97, 63 - - - 121, 21 - - - 120 - - - CMB_fmode1 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 27 - - - NoControl - - - 97, 225 - - - 121, 23 - - - 132 - - - Save Modes - - - BUT_SaveModes - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 28 - - - True - - - 6, 13 - - - 500, 270 - - - currentStateBindingSource - - - System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ConfigFlightModes - - - System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + True + + + + NoControl + + + + 232, 200 + + + 2, 2, 2, 2 + + + 87, 17 + + + 148 + + + Simple Mode + + + CB_simple6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + True + + + NoControl + + + 232, 173 + + + 2, 2, 2, 2 + + + 87, 17 + + + 147 + + + Simple Mode + + + CB_simple5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + NoControl + + + 232, 146 + + + 2, 2, 2, 2 + + + 87, 17 + + + 146 + + + Simple Mode + + + CB_simple4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + True + + + NoControl + + + 232, 119 + + + 2, 2, 2, 2 + + + 87, 17 + + + 145 + + + Simple Mode + + + CB_simple3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + True + + + NoControl + + + 232, 92 + + + 2, 2, 2, 2 + + + 87, 17 + + + 144 + + + Simple Mode + + + CB_simple2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + True + + + NoControl + + + 232, 65 + + + 2, 2, 2, 2 + + + 87, 17 + + + 143 + + + Simple Mode + + + CB_simple1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + True + + + NoControl + + + 94, 32 + + + 74, 13 + + + 142 + + + Current PWM: + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + True + + + NoControl + + + 174, 32 + + + 13, 13 + + + 141 + + + 0 + + + LBL_flightmodepwm + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + True + + + NoControl + + + 94, 15 + + + 74, 13 + + + 140 + + + Current Mode: + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + True + + + 17, 17 + + + NoControl + + + 174, 15 + + + 42, 13 + + + 139 + + + Manual + + + lbl_currentmode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + True + + + NoControl + + + 358, 66 + + + 76, 13 + + + 138 + + + PWM 0 - 1230 + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + True + + + NoControl + + + 358, 201 + + + 70, 13 + + + 137 + + + PWM 1750 + + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + True + + + NoControl + + + 358, 174 + + + 94, 13 + + + 136 + + + PWM 1621 - 1749 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + True + + + NoControl + + + 358, 147 + + + 94, 13 + + + 135 + + + PWM 1491 - 1620 + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + True + + + NoControl + + + 358, 120 + + + 94, 13 + + + 134 + + + PWM 1361 - 1490 + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + True + + + NoControl + + + 358, 93 + + + 94, 13 + + + 133 + + + PWM 1231 - 1360 + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + True + + + NoControl + + + 20, 201 + + + 71, 13 + + + 131 + + + Flight Mode 6 + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + 97, 198 + + + 121, 21 + + + 130 + + + CMB_fmode6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + True + + + NoControl + + + 20, 174 + + + 71, 13 + + + 129 + + + Flight Mode 5 + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 18 + + + 97, 171 + + + 121, 21 + + + 128 + + + CMB_fmode5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + True + + + NoControl + + + 20, 147 + + + 71, 13 + + + 127 + + + Flight Mode 4 + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 97, 144 + + + 121, 21 + + + 126 + + + CMB_fmode4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + True + + + NoControl + + + 20, 120 + + + 71, 13 + + + 125 + + + Flight Mode 3 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + 97, 117 + + + 121, 21 + + + 124 + + + CMB_fmode3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + True + + + NoControl + + + 20, 93 + + + 71, 13 + + + 123 + + + Flight Mode 2 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + 97, 90 + + + 121, 21 + + + 122 + + + CMB_fmode2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 25 + + + True + + + NoControl + + + 20, 66 + + + 71, 13 + + + 121 + + + Flight Mode 1 + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 26 + + + 97, 63 + + + 121, 21 + + + 120 + + + CMB_fmode1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 27 + + + NoControl + + + 97, 225 + + + 121, 23 + + + 132 + + + Save Modes + + + BUT_SaveModes + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + $this + + + 28 + + + True + + + 6, 13 + + + 500, 270 + + + currentStateBindingSource + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigFlightModes + + + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx index f96892c423..88d1f411b6 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx @@ -1,496 +1,208 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 遥控输入 - - - 模式 - - - 硬件 - - - 电池 - - - AC2 直升机 - - - 上降副翼 (Elevon) 配置 - - - - 115, 17 - - - Elevons CH2 逆转 - - - 91, 17 - - - Elevons 逆转 - - - 115, 17 - - - Elevons CH1 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 校准遥控 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 64, 13 - - - 当前 PWM: - - - 58, 13 - - - 当前模式: - - - 64, 13 - - - 飞行模式 6 - - - 64, 13 - - - 飞行模式 5 - - - 64, 13 - - - 飞行模式 4 - - - 64, 13 - - - 飞行模式 3 - - - 64, 13 - - - 飞行模式 2 - - - 64, 13 - - - 飞行模式 1 - - - 保存模式 - - - 十进制, 2° 3' W 就是 -2.3 - - - 启用光流 - - - 67, 13 - - - 磁偏角网站 - - - 磁偏角 - - - 启用空速计 - - - 启用声纳 - - - 启用罗盘 - - - 58, 13 - - - 输入电压: - - - 94, 13 - - - 测量的电池电压: - - - 58, 13 - - - 电池电压: - - - 52, 13 - - - 分 压 比: - - - 63, 13 - - - 安培/伏特: - - - 48, 18 - - - 传感器 - - - 电压传感器校准: -1. 测量APM输入电压,输入到下方的文本框中 -2. 测量电池电压,输入到下方的文本框中 -3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中 - - - 31, 13 - - - 容量 - - - 48, 13 - - - 监控器 - - - 175, 13 - - - 设置水平面的默认加速度计偏移 - - - 261, 13 - - - 注: 图片只是用于展示,设置可以用于六轴等机架 - - - 93, 13 - - - 机架设置 (+ 或 x) - - - 找平 - - - 手动 - - - 手动 - - - 31, 13 - - - 感度 - - - 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 - - - 最大俯仰 - - - 55, 13 - - - 最大侧倾 - - - 55, 13 - - - 舵机行程 - - - 79, 13 - - - 斜盘水平微调 - - - 79, 13 - - - 斜盘舵机位置 - - - 重置 - - - 重置 APM 为默认设置 - - - APM设置 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 74, 17 + + + 简单模式 + + + 64, 13 + + + 当前 PWM: + + + 58, 13 + + + 当前模式: + + + 64, 13 + + + 飞行模式 6 + + + 64, 13 + + + 飞行模式 5 + + + 64, 13 + + + 飞行模式 4 + + + 64, 13 + + + 飞行模式 3 + + + 64, 13 + + + 飞行模式 2 + + + 64, 13 + + + 飞行模式 1 + + + 保存模式 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs index fcdef62936..e5a2e07eae 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs @@ -1,212 +1,222 @@ -namespace ArdupilotMega.GCSViews.ConfigurationView -{ - partial class ConfigHardwareOptions - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Component Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigHardwareOptions)); - this.BUT_MagCalibrationLive = new ArdupilotMega.MyButton(); - this.label27 = new System.Windows.Forms.Label(); - this.CMB_sonartype = new System.Windows.Forms.ComboBox(); - this.CHK_enableoptflow = new System.Windows.Forms.CheckBox(); - this.pictureBox2 = new System.Windows.Forms.PictureBox(); - this.linkLabelmagdec = new System.Windows.Forms.LinkLabel(); - this.label100 = new System.Windows.Forms.Label(); - this.TXT_declination = new System.Windows.Forms.TextBox(); - this.CHK_enableairspeed = new System.Windows.Forms.CheckBox(); - this.CHK_enablesonar = new System.Windows.Forms.CheckBox(); - this.CHK_enablecompass = new System.Windows.Forms.CheckBox(); - this.pictureBox4 = new System.Windows.Forms.PictureBox(); - this.pictureBox3 = new System.Windows.Forms.PictureBox(); - this.pictureBox1 = new System.Windows.Forms.PictureBox(); - this.BUT_MagCalibrationLog = new ArdupilotMega.MyButton(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit(); - this.SuspendLayout(); - // - // BUT_MagCalibrationLive - // - resources.ApplyResources(this.BUT_MagCalibrationLive, "BUT_MagCalibrationLive"); - this.BUT_MagCalibrationLive.Name = "BUT_MagCalibrationLive"; - this.BUT_MagCalibrationLive.UseVisualStyleBackColor = true; - this.BUT_MagCalibrationLive.Click += new System.EventHandler(this.BUT_MagCalibration_Click); - // - // label27 - // - resources.ApplyResources(this.label27, "label27"); - this.label27.Name = "label27"; - // - // CMB_sonartype - // - this.CMB_sonartype.FormattingEnabled = true; - this.CMB_sonartype.Items.AddRange(new object[] { - resources.GetString("CMB_sonartype.Items"), - resources.GetString("CMB_sonartype.Items1"), - resources.GetString("CMB_sonartype.Items2")}); - resources.ApplyResources(this.CMB_sonartype, "CMB_sonartype"); - this.CMB_sonartype.Name = "CMB_sonartype"; - this.CMB_sonartype.SelectedIndexChanged += new System.EventHandler(this.CMB_sonartype_SelectedIndexChanged); - // - // CHK_enableoptflow - // - resources.ApplyResources(this.CHK_enableoptflow, "CHK_enableoptflow"); - this.CHK_enableoptflow.Name = "CHK_enableoptflow"; - this.CHK_enableoptflow.UseVisualStyleBackColor = true; - this.CHK_enableoptflow.CheckedChanged += new System.EventHandler(this.CHK_enableoptflow_CheckedChanged); - // - // pictureBox2 - // - this.pictureBox2.BackColor = System.Drawing.Color.White; - this.pictureBox2.BackgroundImage = global::ArdupilotMega.Properties.Resources.opticalflow; - resources.ApplyResources(this.pictureBox2, "pictureBox2"); - this.pictureBox2.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; - this.pictureBox2.Name = "pictureBox2"; - this.pictureBox2.TabStop = false; - // - // linkLabelmagdec - // - resources.ApplyResources(this.linkLabelmagdec, "linkLabelmagdec"); - this.linkLabelmagdec.Name = "linkLabelmagdec"; - this.linkLabelmagdec.TabStop = true; - this.linkLabelmagdec.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked); - // - // label100 - // - resources.ApplyResources(this.label100, "label100"); - this.label100.Name = "label100"; - // - // TXT_declination - // - resources.ApplyResources(this.TXT_declination, "TXT_declination"); - this.TXT_declination.Name = "TXT_declination"; - this.TXT_declination.Validated += new System.EventHandler(this.TXT_declination_Validated); - // - // CHK_enableairspeed - // - resources.ApplyResources(this.CHK_enableairspeed, "CHK_enableairspeed"); - this.CHK_enableairspeed.Name = "CHK_enableairspeed"; - this.CHK_enableairspeed.UseVisualStyleBackColor = true; - this.CHK_enableairspeed.CheckedChanged += new System.EventHandler(this.CHK_enableairspeed_CheckedChanged); - // - // CHK_enablesonar - // - resources.ApplyResources(this.CHK_enablesonar, "CHK_enablesonar"); - this.CHK_enablesonar.Name = "CHK_enablesonar"; - this.CHK_enablesonar.UseVisualStyleBackColor = true; - this.CHK_enablesonar.CheckedChanged += new System.EventHandler(this.CHK_enablesonar_CheckedChanged); - // - // CHK_enablecompass - // - resources.ApplyResources(this.CHK_enablecompass, "CHK_enablecompass"); - this.CHK_enablecompass.Name = "CHK_enablecompass"; - this.CHK_enablecompass.UseVisualStyleBackColor = true; - this.CHK_enablecompass.CheckedChanged += new System.EventHandler(this.CHK_enablecompass_CheckedChanged); - // - // 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; - // - // 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; - // - // 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; - // - // BUT_MagCalibrationLog - // - resources.ApplyResources(this.BUT_MagCalibrationLog, "BUT_MagCalibrationLog"); - this.BUT_MagCalibrationLog.Name = "BUT_MagCalibrationLog"; - this.BUT_MagCalibrationLog.UseVisualStyleBackColor = true; - this.BUT_MagCalibrationLog.Click += new System.EventHandler(this.BUT_MagCalibrationLog_Click); - // - // ConfigHardwareOptions - // - resources.ApplyResources(this, "$this"); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.BUT_MagCalibrationLog); - this.Controls.Add(this.BUT_MagCalibrationLive); - this.Controls.Add(this.label27); - this.Controls.Add(this.CMB_sonartype); - this.Controls.Add(this.CHK_enableoptflow); - this.Controls.Add(this.pictureBox2); - this.Controls.Add(this.linkLabelmagdec); - this.Controls.Add(this.label100); - this.Controls.Add(this.TXT_declination); - this.Controls.Add(this.CHK_enableairspeed); - this.Controls.Add(this.CHK_enablesonar); - this.Controls.Add(this.CHK_enablecompass); - this.Controls.Add(this.pictureBox4); - this.Controls.Add(this.pictureBox3); - this.Controls.Add(this.pictureBox1); - this.Name = "ConfigHardwareOptions"; - this.Load += new System.EventHandler(this.ConfigHardwareOptions_Load); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit(); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private MyButton BUT_MagCalibrationLive; - private System.Windows.Forms.Label label27; - private System.Windows.Forms.ComboBox CMB_sonartype; - private System.Windows.Forms.CheckBox CHK_enableoptflow; - private System.Windows.Forms.PictureBox pictureBox2; - private System.Windows.Forms.LinkLabel linkLabelmagdec; - private System.Windows.Forms.Label label100; - private System.Windows.Forms.TextBox TXT_declination; - private System.Windows.Forms.CheckBox CHK_enableairspeed; - private System.Windows.Forms.CheckBox CHK_enablesonar; - private System.Windows.Forms.CheckBox CHK_enablecompass; - private System.Windows.Forms.PictureBox pictureBox4; - private System.Windows.Forms.PictureBox pictureBox3; - private System.Windows.Forms.PictureBox pictureBox1; - private MyButton BUT_MagCalibrationLog; - } -} +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class ConfigHardwareOptions + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Component Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigHardwareOptions)); + this.BUT_MagCalibrationLive = new ArdupilotMega.MyButton(); + this.label27 = new System.Windows.Forms.Label(); + this.CMB_sonartype = new System.Windows.Forms.ComboBox(); + this.CHK_enableoptflow = new System.Windows.Forms.CheckBox(); + this.pictureBox2 = new System.Windows.Forms.PictureBox(); + this.linkLabelmagdec = new System.Windows.Forms.LinkLabel(); + this.label100 = new System.Windows.Forms.Label(); + this.TXT_declination = new System.Windows.Forms.TextBox(); + this.CHK_enableairspeed = new System.Windows.Forms.CheckBox(); + this.CHK_enablesonar = new System.Windows.Forms.CheckBox(); + this.CHK_enablecompass = new System.Windows.Forms.CheckBox(); + this.pictureBox4 = new System.Windows.Forms.PictureBox(); + this.pictureBox3 = new System.Windows.Forms.PictureBox(); + this.pictureBox1 = new System.Windows.Forms.PictureBox(); + this.BUT_MagCalibrationLog = new ArdupilotMega.MyButton(); + this.CHK_autodec = new System.Windows.Forms.CheckBox(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit(); + this.SuspendLayout(); + // + // BUT_MagCalibrationLive + // + resources.ApplyResources(this.BUT_MagCalibrationLive, "BUT_MagCalibrationLive"); + this.BUT_MagCalibrationLive.Name = "BUT_MagCalibrationLive"; + this.BUT_MagCalibrationLive.UseVisualStyleBackColor = true; + this.BUT_MagCalibrationLive.Click += new System.EventHandler(this.BUT_MagCalibration_Click); + // + // label27 + // + resources.ApplyResources(this.label27, "label27"); + this.label27.Name = "label27"; + // + // CMB_sonartype + // + this.CMB_sonartype.FormattingEnabled = true; + this.CMB_sonartype.Items.AddRange(new object[] { + resources.GetString("CMB_sonartype.Items"), + resources.GetString("CMB_sonartype.Items1"), + resources.GetString("CMB_sonartype.Items2")}); + resources.ApplyResources(this.CMB_sonartype, "CMB_sonartype"); + this.CMB_sonartype.Name = "CMB_sonartype"; + this.CMB_sonartype.SelectedIndexChanged += new System.EventHandler(this.CMB_sonartype_SelectedIndexChanged); + // + // CHK_enableoptflow + // + resources.ApplyResources(this.CHK_enableoptflow, "CHK_enableoptflow"); + this.CHK_enableoptflow.Name = "CHK_enableoptflow"; + this.CHK_enableoptflow.UseVisualStyleBackColor = true; + this.CHK_enableoptflow.CheckedChanged += new System.EventHandler(this.CHK_enableoptflow_CheckedChanged); + // + // pictureBox2 + // + this.pictureBox2.BackColor = System.Drawing.Color.White; + this.pictureBox2.BackgroundImage = global::ArdupilotMega.Properties.Resources.opticalflow; + resources.ApplyResources(this.pictureBox2, "pictureBox2"); + this.pictureBox2.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; + this.pictureBox2.Name = "pictureBox2"; + this.pictureBox2.TabStop = false; + // + // linkLabelmagdec + // + resources.ApplyResources(this.linkLabelmagdec, "linkLabelmagdec"); + this.linkLabelmagdec.Name = "linkLabelmagdec"; + this.linkLabelmagdec.TabStop = true; + this.linkLabelmagdec.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked); + // + // label100 + // + resources.ApplyResources(this.label100, "label100"); + this.label100.Name = "label100"; + // + // TXT_declination + // + resources.ApplyResources(this.TXT_declination, "TXT_declination"); + this.TXT_declination.Name = "TXT_declination"; + this.TXT_declination.Validated += new System.EventHandler(this.TXT_declination_Validated); + // + // CHK_enableairspeed + // + resources.ApplyResources(this.CHK_enableairspeed, "CHK_enableairspeed"); + this.CHK_enableairspeed.Name = "CHK_enableairspeed"; + this.CHK_enableairspeed.UseVisualStyleBackColor = true; + this.CHK_enableairspeed.CheckedChanged += new System.EventHandler(this.CHK_enableairspeed_CheckedChanged); + // + // CHK_enablesonar + // + resources.ApplyResources(this.CHK_enablesonar, "CHK_enablesonar"); + this.CHK_enablesonar.Name = "CHK_enablesonar"; + this.CHK_enablesonar.UseVisualStyleBackColor = true; + this.CHK_enablesonar.CheckedChanged += new System.EventHandler(this.CHK_enablesonar_CheckedChanged); + // + // CHK_enablecompass + // + resources.ApplyResources(this.CHK_enablecompass, "CHK_enablecompass"); + this.CHK_enablecompass.Name = "CHK_enablecompass"; + this.CHK_enablecompass.UseVisualStyleBackColor = true; + this.CHK_enablecompass.CheckedChanged += new System.EventHandler(this.CHK_enablecompass_CheckedChanged); + // + // 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; + // + // 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; + // + // 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; + // + // BUT_MagCalibrationLog + // + resources.ApplyResources(this.BUT_MagCalibrationLog, "BUT_MagCalibrationLog"); + this.BUT_MagCalibrationLog.Name = "BUT_MagCalibrationLog"; + this.BUT_MagCalibrationLog.UseVisualStyleBackColor = true; + this.BUT_MagCalibrationLog.Click += new System.EventHandler(this.BUT_MagCalibrationLog_Click); + // + // CHK_autodec + // + resources.ApplyResources(this.CHK_autodec, "CHK_autodec"); + this.CHK_autodec.Name = "CHK_autodec"; + this.CHK_autodec.UseVisualStyleBackColor = true; + this.CHK_autodec.CheckedChanged += new System.EventHandler(this.CHK_autodec_CheckedChanged); + // + // ConfigHardwareOptions + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.CHK_autodec); + this.Controls.Add(this.BUT_MagCalibrationLog); + this.Controls.Add(this.BUT_MagCalibrationLive); + this.Controls.Add(this.label27); + this.Controls.Add(this.CMB_sonartype); + this.Controls.Add(this.CHK_enableoptflow); + this.Controls.Add(this.pictureBox2); + this.Controls.Add(this.linkLabelmagdec); + this.Controls.Add(this.label100); + this.Controls.Add(this.TXT_declination); + this.Controls.Add(this.CHK_enableairspeed); + this.Controls.Add(this.CHK_enablesonar); + this.Controls.Add(this.CHK_enablecompass); + this.Controls.Add(this.pictureBox4); + this.Controls.Add(this.pictureBox3); + this.Controls.Add(this.pictureBox1); + this.Name = "ConfigHardwareOptions"; + this.Load += new System.EventHandler(this.ConfigHardwareOptions_Load); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private MyButton BUT_MagCalibrationLive; + private System.Windows.Forms.Label label27; + private System.Windows.Forms.ComboBox CMB_sonartype; + private System.Windows.Forms.CheckBox CHK_enableoptflow; + private System.Windows.Forms.PictureBox pictureBox2; + private System.Windows.Forms.LinkLabel linkLabelmagdec; + private System.Windows.Forms.Label label100; + private System.Windows.Forms.TextBox TXT_declination; + private System.Windows.Forms.CheckBox CHK_enableairspeed; + private System.Windows.Forms.CheckBox CHK_enablesonar; + private System.Windows.Forms.CheckBox CHK_enablecompass; + private System.Windows.Forms.PictureBox pictureBox4; + private System.Windows.Forms.PictureBox pictureBox3; + private System.Windows.Forms.PictureBox pictureBox1; + private MyButton BUT_MagCalibrationLog; + private System.Windows.Forms.CheckBox CHK_autodec; + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs index fbae833da6..e804b80529 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs @@ -129,6 +129,17 @@ namespace ArdupilotMega.GCSViews.ConfigurationView private void CHK_enablecompass_CheckedChanged(object sender, EventArgs e) { + if (((CheckBox)sender).Checked == true) + { + CHK_autodec.Enabled = true; + TXT_declination.Enabled = true; + } + else + { + CHK_autodec.Enabled = false; + TXT_declination.Enabled = false; + } + if (startup) return; try @@ -250,6 +261,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView if (MainV2.comPort.param["FLOW_ENABLE"] != null) CHK_enableoptflow.Checked = MainV2.comPort.param["FLOW_ENABLE"].ToString() == "1" ? true : false; + if (MainV2.comPort.param["COMPASS_AUTODEC"] != null) + CHK_autodec.Checked = MainV2.comPort.param["COMPASS_AUTODEC"].ToString() == "1" ? true : false; + startup = false; } @@ -264,5 +278,32 @@ namespace ArdupilotMega.GCSViews.ConfigurationView MagCalib.ProcessLog(ans); } + + private void CHK_autodec_CheckedChanged(object sender, EventArgs e) + { + if (((CheckBox)sender).Checked == true) + { + TXT_declination.Enabled = false; + } + else + { + TXT_declination.Enabled = true; + } + + if (startup) + return; + try + { + if (MainV2.comPort.param["COMPASS_AUTODEC"] == null) + { + CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString()); + } + else + { + MainV2.comPort.setParam("COMPASS_AUTODEC", ((CheckBox)sender).Checked == true ? 1 : 0); + } + } + catch { CustomMessageBox.Show("Set COMPASS_AUTODEC Failed"); } + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx index 158f11af30..b15fe2836a 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx @@ -1,549 +1,582 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - NoControl - - - - 318, 13 - - - 60, 23 - - - - 47 - - - Live Calibration - - - BUT_MagCalibrationLive - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4487.21319, Culture=neutral, PublicKeyToken=null - - - $this - - - 1 - - - NoControl - - - 445, 45 - - - 150, 20 - - - 46 - - - in Degrees eg 2° 3' W is -2.3 - - - label27 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - XL-EZ0 - - - LV-EZ0 - - - XL-EZL0 - - - 243, 122 - - - 121, 21 - - - 45 - - - CMB_sonartype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - - - NoControl - - - 97, 285 - - - 134, 19 - - - 44 - - - Enable Optical Flow - - - CHK_enableoptflow - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 4 - - - Zoom - - - NoControl - - - 13, 259 - - - 75, 75 - - - 43 - - - pictureBox2 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - True - - - NoControl - - - 325, 68 - - - 104, 13 - - - 42 - - - Declination WebSite - - - linkLabelmagdec - - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - NoControl - - - 240, 45 - - - 72, 16 - - - 38 - - - Declination - - - label100 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - 318, 45 - - - 121, 20 - - - 37 - - - TXT_declination - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 8 - - - NoControl - - - 97, 202 - - - 103, 17 - - - 39 - - - Enable Airspeed - - - CHK_enableairspeed - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 9 - - - NoControl - - - 94, 124 - - - 90, 17 - - - 40 - - - Enable Sonar - - - CHK_enablesonar - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - - NoControl - - - 97, 44 - - - 105, 17 - - - 41 - - - Enable Compass - - - CHK_enablecompass - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 11 - - - Zoom - - - NoControl - - - 13, 176 - - - 75, 75 - - - 36 - - - pictureBox4 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 12 - - - Zoom - - - NoControl - - - 13, 94 - - - 75, 75 - - - 35 - - - pictureBox3 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 13 - - - Zoom - - - - - - NoControl - - - - - - 13, 13 - - - 75, 75 - - - 34 - - - pictureBox1 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 14 - - - NoControl - - - 379, 13 - - - 60, 23 - - - 48 - - - Log Calibration - - - BUT_MagCalibrationLog - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4487.21319, Culture=neutral, PublicKeyToken=null - - - $this - - - 0 - - - True - - - 6, 13 - - - 602, 351 - - - ConfigHardwareOptions - - - ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4487.21319, Culture=neutral, PublicKeyToken=null - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + NoControl + + + + 331, 13 + + + 60, 23 + + + + 47 + + + Live Calibration + + + BUT_MagCalibrationLive + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null + + + $this + + + 2 + + + NoControl + + + 455, 45 + + + 145, 20 + + + 46 + + + in Degrees eg 2° 3' W is -2.3 + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + XL-EZ0 + + + LV-EZ0 + + + XL-EZL0 + + + 243, 122 + + + 121, 21 + + + 45 + + + CMB_sonartype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + NoControl + + + 97, 285 + + + 134, 19 + + + 44 + + + Enable Optical Flow + + + CHK_enableoptflow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + Zoom + + + NoControl + + + 13, 259 + + + 75, 75 + + + 43 + + + pictureBox2 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + True + + + NoControl + + + 338, 68 + + + 104, 13 + + + 42 + + + Declination WebSite + + + linkLabelmagdec + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + NoControl + + + 240, 45 + + + 72, 16 + + + 38 + + + Declination + + + label100 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + False + + + 331, 45 + + + 121, 20 + + + 37 + + + TXT_declination + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + NoControl + + + 97, 202 + + + 103, 17 + + + 39 + + + Enable Airspeed + + + CHK_enableairspeed + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + NoControl + + + 94, 124 + + + 90, 17 + + + 40 + + + Enable Sonar + + + CHK_enablesonar + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + NoControl + + + 97, 44 + + + 105, 17 + + + 41 + + + Enable Compass + + + CHK_enablecompass + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + Zoom + + + NoControl + + + 13, 176 + + + 75, 75 + + + 36 + + + pictureBox4 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + Zoom + + + NoControl + + + 13, 94 + + + 75, 75 + + + 35 + + + pictureBox3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + Zoom + + + + + + NoControl + + + + + + 13, 13 + + + 75, 75 + + + 34 + + + pictureBox1 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + NoControl + + + 392, 13 + + + 60, 23 + + + 48 + + + Log Calibration + + + BUT_MagCalibrationLog + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 + + + False + + + NoControl + + + 243, 25 + + + 82, 17 + + + 49 + + + Auto Dec + + + CHK_autodec + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + True + + + 6, 13 + + + 602, 351 + + + ConfigHardwareOptions + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx index f96892c423..182e965324 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx @@ -1,496 +1,151 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 遥控输入 - - - 模式 - - - 硬件 - - - 电池 - - - AC2 直升机 - - - 上降副翼 (Elevon) 配置 - - - - 115, 17 - - - Elevons CH2 逆转 - - - 91, 17 - - - Elevons 逆转 - - - 115, 17 - - - Elevons CH1 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 校准遥控 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 64, 13 - - - 当前 PWM: - - - 58, 13 - - - 当前模式: - - - 64, 13 - - - 飞行模式 6 - - - 64, 13 - - - 飞行模式 5 - - - 64, 13 - - - 飞行模式 4 - - - 64, 13 - - - 飞行模式 3 - - - 64, 13 - - - 飞行模式 2 - - - 64, 13 - - - 飞行模式 1 - - - 保存模式 - - - 十进制, 2° 3' W 就是 -2.3 - - - 启用光流 - - - 67, 13 - - - 磁偏角网站 - - - 磁偏角 - - - 启用空速计 - - - 启用声纳 - - - 启用罗盘 - - - 58, 13 - - - 输入电压: - - - 94, 13 - - - 测量的电池电压: - - - 58, 13 - - - 电池电压: - - - 52, 13 - - - 分 压 比: - - - 63, 13 - - - 安培/伏特: - - - 48, 18 - - - 传感器 - - - 电压传感器校准: -1. 测量APM输入电压,输入到下方的文本框中 -2. 测量电池电压,输入到下方的文本框中 -3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中 - - - 31, 13 - - - 容量 - - - 48, 13 - - - 监控器 - - - 175, 13 - - - 设置水平面的默认加速度计偏移 - - - 261, 13 - - - 注: 图片只是用于展示,设置可以用于六轴等机架 - - - 93, 13 - - - 机架设置 (+ 或 x) - - - 找平 - - - 手动 - - - 手动 - - - 31, 13 - - - 感度 - - - 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 - - - 最大俯仰 - - - 55, 13 - - - 最大侧倾 - - - 55, 13 - - - 舵机行程 - - - 79, 13 - - - 斜盘水平微调 - - - 79, 13 - - - 斜盘舵机位置 - - - 重置 - - - 重置 APM 为默认设置 - - - APM设置 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 现场校准 + + + 十进制, 2° 3' W 就是 -2.3 + + + 启用光流 + + + + 67, 13 + + + 磁偏角网站 + + + 磁偏角 + + + 启用空速计 + + + 启用声纳 + + + 启用罗盘 + + + 日志校准 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs index ec5a15499e..3b6108454f 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs @@ -28,6 +28,7 @@ /// private void InitializeComponent() { + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigPlanner)); this.label33 = new System.Windows.Forms.Label(); this.CMB_ratesensors = new System.Windows.Forms.ComboBox(); this.label26 = new System.Windows.Forms.Label(); @@ -78,94 +79,62 @@ // // label33 // - this.label33.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label33.Location = new System.Drawing.Point(517, 246); + resources.ApplyResources(this.label33, "label33"); this.label33.Name = "label33"; - this.label33.Size = new System.Drawing.Size(43, 13); - this.label33.TabIndex = 87; - this.label33.Text = "Sensor"; // // CMB_ratesensors // this.CMB_ratesensors.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_ratesensors.FormattingEnabled = true; this.CMB_ratesensors.Items.AddRange(new object[] { - "0", - "1", - "3", - "10", - "50"}); - this.CMB_ratesensors.Location = new System.Drawing.Point(564, 243); + resources.GetString("CMB_ratesensors.Items"), + resources.GetString("CMB_ratesensors.Items1"), + resources.GetString("CMB_ratesensors.Items2"), + resources.GetString("CMB_ratesensors.Items3"), + resources.GetString("CMB_ratesensors.Items4")}); + resources.ApplyResources(this.CMB_ratesensors, "CMB_ratesensors"); this.CMB_ratesensors.Name = "CMB_ratesensors"; - this.CMB_ratesensors.Size = new System.Drawing.Size(40, 21); - this.CMB_ratesensors.TabIndex = 88; // // label26 // - this.label26.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label26.Location = new System.Drawing.Point(15, 52); + resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; - this.label26.Size = new System.Drawing.Size(100, 23); - this.label26.TabIndex = 86; - this.label26.Text = "Video Format"; // // CMB_videoresolutions // this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videoresolutions.FormattingEnabled = true; - this.CMB_videoresolutions.Location = new System.Drawing.Point(124, 49); + resources.ApplyResources(this.CMB_videoresolutions, "CMB_videoresolutions"); this.CMB_videoresolutions.Name = "CMB_videoresolutions"; - this.CMB_videoresolutions.Size = new System.Drawing.Size(408, 21); - this.CMB_videoresolutions.TabIndex = 44; // // label12 // - this.label12.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label12.Location = new System.Drawing.Point(15, 342); + resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; - this.label12.Size = new System.Drawing.Size(61, 13); - this.label12.TabIndex = 84; - this.label12.Text = "HUD"; // // CHK_GDIPlus // - this.CHK_GDIPlus.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_GDIPlus.Location = new System.Drawing.Point(124, 342); + resources.ApplyResources(this.CHK_GDIPlus, "CHK_GDIPlus"); this.CHK_GDIPlus.Name = "CHK_GDIPlus"; - this.CHK_GDIPlus.Size = new System.Drawing.Size(177, 17); - this.CHK_GDIPlus.TabIndex = 85; - this.CHK_GDIPlus.Text = "GDI+ (old type)"; this.CHK_GDIPlus.UseVisualStyleBackColor = true; this.CHK_GDIPlus.CheckedChanged += new System.EventHandler(this.CHK_GDIPlus_CheckedChanged); // // label24 // - this.label24.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label24.Location = new System.Drawing.Point(15, 320); + resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; - this.label24.Size = new System.Drawing.Size(61, 13); - this.label24.TabIndex = 82; - this.label24.Text = "Waypoints"; // // CHK_loadwponconnect // - this.CHK_loadwponconnect.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_loadwponconnect.Location = new System.Drawing.Point(124, 319); + resources.ApplyResources(this.CHK_loadwponconnect, "CHK_loadwponconnect"); this.CHK_loadwponconnect.Name = "CHK_loadwponconnect"; - this.CHK_loadwponconnect.Size = new System.Drawing.Size(177, 17); - this.CHK_loadwponconnect.TabIndex = 83; - this.CHK_loadwponconnect.Text = "Load Waypoints on connect?"; this.CHK_loadwponconnect.UseVisualStyleBackColor = true; this.CHK_loadwponconnect.CheckedChanged += new System.EventHandler(this.CHK_loadwponconnect_CheckedChanged); // // label23 // - this.label23.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label23.Location = new System.Drawing.Point(15, 294); + resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; - this.label23.Size = new System.Drawing.Size(103, 18); - this.label23.TabIndex = 81; - this.label23.Text = "Track Length"; // // NUM_tracklength // @@ -174,7 +143,7 @@ 0, 0, 0}); - this.NUM_tracklength.Location = new System.Drawing.Point(124, 293); + resources.ApplyResources(this.NUM_tracklength, "NUM_tracklength"); this.NUM_tracklength.Maximum = new decimal(new int[] { 2000, 0, @@ -186,8 +155,6 @@ 0, 0}); this.NUM_tracklength.Name = "NUM_tracklength"; - this.NUM_tracklength.Size = new System.Drawing.Size(67, 20); - this.NUM_tracklength.TabIndex = 80; this.NUM_tracklength.Value = new decimal(new int[] { 200, 0, @@ -197,122 +164,81 @@ // // CHK_speechaltwarning // - this.CHK_speechaltwarning.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_speechaltwarning.Location = new System.Drawing.Point(564, 109); + resources.ApplyResources(this.CHK_speechaltwarning, "CHK_speechaltwarning"); this.CHK_speechaltwarning.Name = "CHK_speechaltwarning"; - this.CHK_speechaltwarning.Size = new System.Drawing.Size(102, 17); - this.CHK_speechaltwarning.TabIndex = 79; - this.CHK_speechaltwarning.Text = "Alt Warning"; this.CHK_speechaltwarning.UseVisualStyleBackColor = true; this.CHK_speechaltwarning.CheckedChanged += new System.EventHandler(this.CHK_speechaltwarning_CheckedChanged); // // label108 // - this.label108.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label108.Location = new System.Drawing.Point(15, 271); + resources.ApplyResources(this.label108, "label108"); this.label108.Name = "label108"; - this.label108.Size = new System.Drawing.Size(61, 13); - this.label108.TabIndex = 45; - this.label108.Text = "APM Reset"; // // CHK_resetapmonconnect // this.CHK_resetapmonconnect.Checked = true; this.CHK_resetapmonconnect.CheckState = System.Windows.Forms.CheckState.Checked; - this.CHK_resetapmonconnect.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_resetapmonconnect.Location = new System.Drawing.Point(124, 269); + resources.ApplyResources(this.CHK_resetapmonconnect, "CHK_resetapmonconnect"); this.CHK_resetapmonconnect.Name = "CHK_resetapmonconnect"; - this.CHK_resetapmonconnect.Size = new System.Drawing.Size(163, 17); - this.CHK_resetapmonconnect.TabIndex = 46; - this.CHK_resetapmonconnect.Text = "Reset APM on USB Connect"; this.CHK_resetapmonconnect.UseVisualStyleBackColor = true; this.CHK_resetapmonconnect.CheckedChanged += new System.EventHandler(this.CHK_resetapmonconnect_CheckedChanged); // // CHK_mavdebug // - this.CHK_mavdebug.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left))); - this.CHK_mavdebug.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_mavdebug.Location = new System.Drawing.Point(15, 378); + resources.ApplyResources(this.CHK_mavdebug, "CHK_mavdebug"); this.CHK_mavdebug.Name = "CHK_mavdebug"; - this.CHK_mavdebug.Size = new System.Drawing.Size(144, 17); - this.CHK_mavdebug.TabIndex = 47; - this.CHK_mavdebug.Text = "Mavlink Message Debug"; this.CHK_mavdebug.UseVisualStyleBackColor = true; this.CHK_mavdebug.CheckedChanged += new System.EventHandler(this.CHK_mavdebug_CheckedChanged); // // label107 // - this.label107.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label107.Location = new System.Drawing.Point(439, 246); + resources.ApplyResources(this.label107, "label107"); this.label107.Name = "label107"; - this.label107.Size = new System.Drawing.Size(22, 13); - this.label107.TabIndex = 48; - this.label107.Text = "RC"; // // CMB_raterc // this.CMB_raterc.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_raterc.FormattingEnabled = true; this.CMB_raterc.Items.AddRange(new object[] { - "0", - "1", - "3", - "10"}); - this.CMB_raterc.Location = new System.Drawing.Point(470, 242); + resources.GetString("CMB_raterc.Items"), + 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.CMB_raterc.Size = new System.Drawing.Size(40, 21); - this.CMB_raterc.TabIndex = 49; this.CMB_raterc.SelectedIndexChanged += new System.EventHandler(this.CMB_raterc_SelectedIndexChanged); // // label104 // - this.label104.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label104.Location = new System.Drawing.Point(319, 246); + resources.ApplyResources(this.label104, "label104"); this.label104.Name = "label104"; - this.label104.Size = new System.Drawing.Size(69, 13); - this.label104.TabIndex = 50; - this.label104.Text = "Mode/Status"; // // label103 // - this.label103.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label103.Location = new System.Drawing.Point(219, 246); + resources.ApplyResources(this.label103, "label103"); this.label103.Name = "label103"; - this.label103.Size = new System.Drawing.Size(44, 13); - this.label103.TabIndex = 51; - this.label103.Text = "Position"; // // label102 // - this.label102.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label102.Location = new System.Drawing.Point(121, 246); + resources.ApplyResources(this.label102, "label102"); this.label102.Name = "label102"; - this.label102.Size = new System.Drawing.Size(43, 13); - this.label102.TabIndex = 52; - this.label102.Text = "Attitude"; // // label101 // - this.label101.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label101.Location = new System.Drawing.Point(12, 246); + resources.ApplyResources(this.label101, "label101"); this.label101.Name = "label101"; - this.label101.Size = new System.Drawing.Size(84, 13); - this.label101.TabIndex = 53; - this.label101.Text = "Telemetry Rates"; // // CMB_ratestatus // this.CMB_ratestatus.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_ratestatus.FormattingEnabled = true; this.CMB_ratestatus.Items.AddRange(new object[] { - "0", - "1", - "3", - "10"}); - this.CMB_ratestatus.Location = new System.Drawing.Point(393, 242); + resources.GetString("CMB_ratestatus.Items"), + 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.CMB_ratestatus.Size = new System.Drawing.Size(40, 21); - this.CMB_ratestatus.TabIndex = 54; this.CMB_ratestatus.SelectedIndexChanged += new System.EventHandler(this.CMB_ratestatus_SelectedIndexChanged); // // CMB_rateposition @@ -320,14 +246,12 @@ this.CMB_rateposition.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_rateposition.FormattingEnabled = true; this.CMB_rateposition.Items.AddRange(new object[] { - "0", - "1", - "3", - "10"}); - this.CMB_rateposition.Location = new System.Drawing.Point(273, 242); + resources.GetString("CMB_rateposition.Items"), + 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.CMB_rateposition.Size = new System.Drawing.Size(40, 21); - this.CMB_rateposition.TabIndex = 55; this.CMB_rateposition.SelectedIndexChanged += new System.EventHandler(this.CMB_rateposition_SelectedIndexChanged); // // CMB_rateattitude @@ -335,173 +259,114 @@ this.CMB_rateattitude.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_rateattitude.FormattingEnabled = true; this.CMB_rateattitude.Items.AddRange(new object[] { - "0", - "1", - "3", - "10"}); - this.CMB_rateattitude.Location = new System.Drawing.Point(173, 242); + resources.GetString("CMB_rateattitude.Items"), + 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.CMB_rateattitude.Size = new System.Drawing.Size(40, 21); - this.CMB_rateattitude.TabIndex = 56; this.CMB_rateattitude.SelectedIndexChanged += new System.EventHandler(this.CMB_rateattitude_SelectedIndexChanged); // // label99 // - this.label99.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label99.Location = new System.Drawing.Point(268, 211); + resources.ApplyResources(this.label99, "label99"); this.label99.Name = "label99"; - this.label99.Size = new System.Drawing.Size(402, 13); - this.label99.TabIndex = 57; - this.label99.Text = "NOTE: The Configuration Tab will NOT display these units, as those are raw values" + - ".\r\n"; // // label98 // - this.label98.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label98.Location = new System.Drawing.Point(15, 219); + resources.ApplyResources(this.label98, "label98"); this.label98.Name = "label98"; - this.label98.Size = new System.Drawing.Size(65, 13); - this.label98.TabIndex = 58; - this.label98.Text = "Speed Units"; // // label97 // - this.label97.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label97.Location = new System.Drawing.Point(15, 191); + resources.ApplyResources(this.label97, "label97"); this.label97.Name = "label97"; - this.label97.Size = new System.Drawing.Size(52, 13); - this.label97.TabIndex = 59; - this.label97.Text = "Dist Units"; // // CMB_speedunits // this.CMB_speedunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_speedunits.FormattingEnabled = true; - this.CMB_speedunits.Location = new System.Drawing.Point(124, 216); + resources.ApplyResources(this.CMB_speedunits, "CMB_speedunits"); this.CMB_speedunits.Name = "CMB_speedunits"; - this.CMB_speedunits.Size = new System.Drawing.Size(138, 21); - this.CMB_speedunits.TabIndex = 60; this.CMB_speedunits.SelectedIndexChanged += new System.EventHandler(this.CMB_speedunits_SelectedIndexChanged); // // CMB_distunits // this.CMB_distunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_distunits.FormattingEnabled = true; - this.CMB_distunits.Location = new System.Drawing.Point(124, 189); + resources.ApplyResources(this.CMB_distunits, "CMB_distunits"); this.CMB_distunits.Name = "CMB_distunits"; - this.CMB_distunits.Size = new System.Drawing.Size(138, 21); - this.CMB_distunits.TabIndex = 61; this.CMB_distunits.SelectedIndexChanged += new System.EventHandler(this.CMB_distunits_SelectedIndexChanged); // // label96 // - this.label96.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label96.Location = new System.Drawing.Point(15, 164); + resources.ApplyResources(this.label96, "label96"); this.label96.Name = "label96"; - this.label96.Size = new System.Drawing.Size(45, 13); - this.label96.TabIndex = 62; - this.label96.Text = "Joystick"; // // label95 // - this.label95.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label95.Location = new System.Drawing.Point(15, 113); + resources.ApplyResources(this.label95, "label95"); this.label95.Name = "label95"; - this.label95.Size = new System.Drawing.Size(44, 13); - this.label95.TabIndex = 63; - this.label95.Text = "Speech"; // // CHK_speechbattery // - this.CHK_speechbattery.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_speechbattery.Location = new System.Drawing.Point(456, 109); + resources.ApplyResources(this.CHK_speechbattery, "CHK_speechbattery"); this.CHK_speechbattery.Name = "CHK_speechbattery"; - this.CHK_speechbattery.Size = new System.Drawing.Size(102, 17); - this.CHK_speechbattery.TabIndex = 64; - this.CHK_speechbattery.Text = "Battery Warning"; this.CHK_speechbattery.UseVisualStyleBackColor = true; this.CHK_speechbattery.CheckedChanged += new System.EventHandler(this.CHK_speechbattery_CheckedChanged); // // CHK_speechcustom // - this.CHK_speechcustom.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_speechcustom.Location = new System.Drawing.Point(363, 109); + resources.ApplyResources(this.CHK_speechcustom, "CHK_speechcustom"); this.CHK_speechcustom.Name = "CHK_speechcustom"; - this.CHK_speechcustom.Size = new System.Drawing.Size(87, 17); - this.CHK_speechcustom.TabIndex = 65; - this.CHK_speechcustom.Text = "Time Interval"; this.CHK_speechcustom.UseVisualStyleBackColor = true; this.CHK_speechcustom.CheckedChanged += new System.EventHandler(this.CHK_speechcustom_CheckedChanged); // // CHK_speechmode // - this.CHK_speechmode.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_speechmode.Location = new System.Drawing.Point(307, 109); + resources.ApplyResources(this.CHK_speechmode, "CHK_speechmode"); this.CHK_speechmode.Name = "CHK_speechmode"; - this.CHK_speechmode.Size = new System.Drawing.Size(56, 17); - this.CHK_speechmode.TabIndex = 66; - this.CHK_speechmode.Text = "Mode "; this.CHK_speechmode.UseVisualStyleBackColor = true; this.CHK_speechmode.CheckedChanged += new System.EventHandler(this.CHK_speechmode_CheckedChanged); // // CHK_speechwaypoint // - this.CHK_speechwaypoint.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_speechwaypoint.Location = new System.Drawing.Point(230, 109); + resources.ApplyResources(this.CHK_speechwaypoint, "CHK_speechwaypoint"); this.CHK_speechwaypoint.Name = "CHK_speechwaypoint"; - this.CHK_speechwaypoint.Size = new System.Drawing.Size(71, 17); - this.CHK_speechwaypoint.TabIndex = 67; - this.CHK_speechwaypoint.Text = "Waypoint"; this.CHK_speechwaypoint.UseVisualStyleBackColor = true; this.CHK_speechwaypoint.CheckedChanged += new System.EventHandler(this.CHK_speechwaypoint_CheckedChanged); // // label94 // - this.label94.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label94.Location = new System.Drawing.Point(15, 85); + resources.ApplyResources(this.label94, "label94"); this.label94.Name = "label94"; - this.label94.Size = new System.Drawing.Size(57, 13); - this.label94.TabIndex = 68; - this.label94.Text = "OSD Color"; // // 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; - this.CMB_osdcolor.Location = new System.Drawing.Point(124, 82); + resources.ApplyResources(this.CMB_osdcolor, "CMB_osdcolor"); this.CMB_osdcolor.Name = "CMB_osdcolor"; - this.CMB_osdcolor.Size = new System.Drawing.Size(138, 21); - this.CMB_osdcolor.TabIndex = 69; this.CMB_osdcolor.SelectedIndexChanged += new System.EventHandler(this.CMB_osdcolor_SelectedIndexChanged); // // CMB_language // this.CMB_language.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_language.FormattingEnabled = true; - this.CMB_language.Location = new System.Drawing.Point(124, 133); + resources.ApplyResources(this.CMB_language, "CMB_language"); this.CMB_language.Name = "CMB_language"; - this.CMB_language.Size = new System.Drawing.Size(138, 21); - this.CMB_language.TabIndex = 70; this.CMB_language.SelectedIndexChanged += new System.EventHandler(this.CMB_language_SelectedIndexChanged); // // label93 // - this.label93.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label93.Location = new System.Drawing.Point(15, 137); + resources.ApplyResources(this.label93, "label93"); this.label93.Name = "label93"; - this.label93.Size = new System.Drawing.Size(69, 13); - this.label93.TabIndex = 71; - this.label93.Text = "UI Language"; // // CHK_enablespeech // - this.CHK_enablespeech.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_enablespeech.Location = new System.Drawing.Point(124, 109); + resources.ApplyResources(this.CHK_enablespeech, "CHK_enablespeech"); this.CHK_enablespeech.Name = "CHK_enablespeech"; - this.CHK_enablespeech.Size = new System.Drawing.Size(99, 17); - this.CHK_enablespeech.TabIndex = 72; - this.CHK_enablespeech.Text = "Enable Speech"; this.CHK_enablespeech.UseVisualStyleBackColor = true; this.CHK_enablespeech.CheckedChanged += new System.EventHandler(this.CHK_enablespeech_CheckedChanged); // @@ -509,70 +374,48 @@ // this.CHK_hudshow.Checked = true; this.CHK_hudshow.CheckState = System.Windows.Forms.CheckState.Checked; - this.CHK_hudshow.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.CHK_hudshow.Location = new System.Drawing.Point(537, 17); + resources.ApplyResources(this.CHK_hudshow, "CHK_hudshow"); this.CHK_hudshow.Name = "CHK_hudshow"; - this.CHK_hudshow.Size = new System.Drawing.Size(125, 17); - this.CHK_hudshow.TabIndex = 73; - this.CHK_hudshow.Text = "Enable HUD Overlay"; this.CHK_hudshow.UseVisualStyleBackColor = true; this.CHK_hudshow.Click += new System.EventHandler(this.CHK_hudshow_CheckedChanged); // // label92 // - this.label92.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.label92.Location = new System.Drawing.Point(15, 18); + resources.ApplyResources(this.label92, "label92"); this.label92.Name = "label92"; - this.label92.Size = new System.Drawing.Size(100, 23); - this.label92.TabIndex = 74; - this.label92.Text = "Video Device"; // // CMB_videosources // this.CMB_videosources.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videosources.FormattingEnabled = true; - this.CMB_videosources.Location = new System.Drawing.Point(124, 15); + resources.ApplyResources(this.CMB_videosources, "CMB_videosources"); this.CMB_videosources.Name = "CMB_videosources"; - this.CMB_videosources.Size = new System.Drawing.Size(245, 21); - this.CMB_videosources.TabIndex = 75; this.CMB_videosources.SelectedIndexChanged += new System.EventHandler(this.CMB_videosources_SelectedIndexChanged); // // BUT_Joystick // - this.BUT_Joystick.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_Joystick.Location = new System.Drawing.Point(124, 160); + resources.ApplyResources(this.BUT_Joystick, "BUT_Joystick"); this.BUT_Joystick.Name = "BUT_Joystick"; - this.BUT_Joystick.Size = new System.Drawing.Size(99, 23); - this.BUT_Joystick.TabIndex = 76; - this.BUT_Joystick.Text = "Joystick Setup"; this.BUT_Joystick.UseVisualStyleBackColor = true; this.BUT_Joystick.Click += new System.EventHandler(this.BUT_Joystick_Click); // // BUT_videostop // - this.BUT_videostop.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_videostop.Location = new System.Drawing.Point(456, 13); + resources.ApplyResources(this.BUT_videostop, "BUT_videostop"); this.BUT_videostop.Name = "BUT_videostop"; - this.BUT_videostop.Size = new System.Drawing.Size(75, 23); - this.BUT_videostop.TabIndex = 77; - this.BUT_videostop.Text = "Stop"; this.BUT_videostop.UseVisualStyleBackColor = true; this.BUT_videostop.Click += new System.EventHandler(this.BUT_videostop_Click); // // BUT_videostart // - this.BUT_videostart.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_videostart.Location = new System.Drawing.Point(375, 13); + resources.ApplyResources(this.BUT_videostart, "BUT_videostart"); this.BUT_videostart.Name = "BUT_videostart"; - this.BUT_videostart.Size = new System.Drawing.Size(75, 23); - this.BUT_videostart.TabIndex = 78; - this.BUT_videostart.Text = "Start"; this.BUT_videostart.UseVisualStyleBackColor = true; this.BUT_videostart.Click += new System.EventHandler(this.BUT_videostart_Click); // // ConfigPlanner // - this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; this.Controls.Add(this.label33); this.Controls.Add(this.CMB_ratesensors); @@ -620,7 +463,6 @@ this.Controls.Add(this.BUT_videostop); this.Controls.Add(this.BUT_videostart); this.Name = "ConfigPlanner"; - this.Size = new System.Drawing.Size(682, 398); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit(); this.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx index 7080a7d118..6e75804078 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx @@ -117,4 +117,1232 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl + + + + 517, 246 + + + 43, 13 + + + + 87 + + + Sensor + + + label33 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + 0 + + + 1 + + + 3 + + + 10 + + + 50 + + + 564, 243 + + + 40, 21 + + + 88 + + + CMB_ratesensors + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + NoControl + + + 15, 52 + + + 100, 23 + + + 86 + + + Video Format + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 124, 49 + + + 408, 21 + + + 44 + + + CMB_videoresolutions + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + NoControl + + + 15, 342 + + + 61, 13 + + + 84 + + + HUD + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + NoControl + + + 124, 342 + + + 177, 17 + + + 85 + + + GDI+ (old type) + + + CHK_GDIPlus + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + NoControl + + + 15, 320 + + + 61, 13 + + + 82 + + + Waypoints + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + NoControl + + + 124, 319 + + + 177, 17 + + + 83 + + + Load Waypoints on connect? + + + CHK_loadwponconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + NoControl + + + 15, 294 + + + 103, 18 + + + 81 + + + Track Length + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 124, 293 + + + 67, 20 + + + 80 + + + NUM_tracklength + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + NoControl + + + 564, 109 + + + 102, 17 + + + 79 + + + Alt Warning + + + CHK_speechaltwarning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + NoControl + + + 15, 271 + + + 61, 13 + + + 45 + + + APM Reset + + + label108 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + NoControl + + + 124, 269 + + + 163, 17 + + + 46 + + + Reset APM on USB Connect + + + CHK_resetapmonconnect + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + Bottom, Left + + + NoControl + + + 15, 378 + + + 144, 17 + + + 47 + + + Mavlink Message Debug + + + CHK_mavdebug + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + NoControl + + + 439, 246 + + + 22, 13 + + + 48 + + + RC + + + label107 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 0 + + + 1 + + + 3 + + + 10 + + + 470, 242 + + + 40, 21 + + + 49 + + + CMB_raterc + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + NoControl + + + 319, 246 + + + 69, 13 + + + 50 + + + Mode/Status + + + label104 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + NoControl + + + 219, 246 + + + 44, 13 + + + 51 + + + Position + + + label103 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + NoControl + + + 121, 246 + + + 43, 13 + + + 52 + + + Attitude + + + label102 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 18 + + + NoControl + + + 12, 246 + + + 84, 13 + + + 53 + + + Telemetry Rates + + + label101 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + 0 + + + 1 + + + 3 + + + 10 + + + 393, 242 + + + 40, 21 + + + 54 + + + CMB_ratestatus + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 0 + + + 1 + + + 3 + + + 10 + + + 273, 242 + + + 40, 21 + + + 55 + + + CMB_rateposition + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + 0 + + + 1 + + + 3 + + + 10 + + + 173, 242 + + + 40, 21 + + + 56 + + + CMB_rateattitude + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + NoControl + + + 268, 211 + + + 402, 13 + + + 57 + + + 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 + + + $this + + + 23 + + + NoControl + + + 15, 219 + + + 65, 13 + + + 58 + + + Speed Units + + + label98 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + NoControl + + + 15, 191 + + + 52, 13 + + + 59 + + + Dist Units + + + label97 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 25 + + + 124, 216 + + + 138, 21 + + + 60 + + + CMB_speedunits + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 26 + + + 124, 189 + + + 138, 21 + + + 61 + + + CMB_distunits + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 27 + + + NoControl + + + 15, 164 + + + 45, 13 + + + 62 + + + Joystick + + + label96 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 28 + + + NoControl + + + 15, 113 + + + 44, 13 + + + 63 + + + Speech + + + label95 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 29 + + + NoControl + + + 456, 109 + + + 102, 17 + + + 64 + + + Battery Warning + + + CHK_speechbattery + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 30 + + + NoControl + + + 363, 109 + + + 87, 17 + + + 65 + + + Time Interval + + + CHK_speechcustom + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 31 + + + NoControl + + + 307, 109 + + + 56, 17 + + + 66 + + + Mode + + + CHK_speechmode + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 32 + + + NoControl + + + 230, 109 + + + 71, 17 + + + 67 + + + Waypoint + + + CHK_speechwaypoint + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 33 + + + NoControl + + + 15, 85 + + + 57, 13 + + + 68 + + + OSD Color + + + label94 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 34 + + + 124, 82 + + + 138, 21 + + + 69 + + + CMB_osdcolor + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 35 + + + 124, 133 + + + 138, 21 + + + 70 + + + CMB_language + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 36 + + + NoControl + + + 15, 137 + + + 69, 13 + + + 71 + + + UI Language + + + label93 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 37 + + + NoControl + + + 124, 109 + + + 99, 17 + + + 72 + + + Enable Speech + + + CHK_enablespeech + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 38 + + + NoControl + + + 537, 17 + + + 125, 17 + + + 73 + + + Enable HUD Overlay + + + CHK_hudshow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 39 + + + NoControl + + + 15, 18 + + + 100, 23 + + + 74 + + + Video Device + + + label92 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 40 + + + 124, 15 + + + 245, 21 + + + 75 + + + CMB_videosources + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 41 + + + NoControl + + + 124, 160 + + + 99, 23 + + + 76 + + + Joystick Setup + + + BUT_Joystick + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 42 + + + NoControl + + + 456, 13 + + + 75, 23 + + + 77 + + + Stop + + + BUT_videostop + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 43 + + + NoControl + + + 375, 13 + + + 75, 23 + + + 78 + + + Start + + + BUT_videostart + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 44 + + + True + + + 6, 13 + + + 682, 398 + + + ConfigPlanner + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs index 8ef9695b92..389ce857b8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs @@ -29,6 +29,7 @@ private void InitializeComponent() { this.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigRawParams)); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle(); this.BUT_compare = new ArdupilotMega.MyButton(); @@ -48,63 +49,36 @@ // // BUT_compare // - this.BUT_compare.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right))); - this.BUT_compare.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_compare.Location = new System.Drawing.Point(341, 119); + resources.ApplyResources(this.BUT_compare, "BUT_compare"); this.BUT_compare.Name = "BUT_compare"; - this.BUT_compare.Size = new System.Drawing.Size(103, 19); - this.BUT_compare.TabIndex = 72; - this.BUT_compare.Text = "Compare Params"; this.BUT_compare.UseVisualStyleBackColor = true; this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click); // // BUT_rerequestparams // - this.BUT_rerequestparams.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right))); - this.BUT_rerequestparams.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_rerequestparams.Location = new System.Drawing.Point(341, 94); + resources.ApplyResources(this.BUT_rerequestparams, "BUT_rerequestparams"); this.BUT_rerequestparams.Name = "BUT_rerequestparams"; - this.BUT_rerequestparams.Size = new System.Drawing.Size(103, 19); - this.BUT_rerequestparams.TabIndex = 67; - this.BUT_rerequestparams.Text = "Refresh Params"; this.BUT_rerequestparams.UseVisualStyleBackColor = true; this.BUT_rerequestparams.Click += new System.EventHandler(this.BUT_rerequestparams_Click); // // BUT_writePIDS // - this.BUT_writePIDS.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right))); - this.BUT_writePIDS.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_writePIDS.Location = new System.Drawing.Point(341, 69); + resources.ApplyResources(this.BUT_writePIDS, "BUT_writePIDS"); this.BUT_writePIDS.Name = "BUT_writePIDS"; - this.BUT_writePIDS.Size = new System.Drawing.Size(103, 19); - this.BUT_writePIDS.TabIndex = 69; - this.BUT_writePIDS.Text = "Write Params"; this.BUT_writePIDS.UseVisualStyleBackColor = true; this.BUT_writePIDS.Click += new System.EventHandler(this.BUT_writePIDS_Click); // // BUT_save // - this.BUT_save.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right))); - this.BUT_save.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_save.Location = new System.Drawing.Point(341, 35); - this.BUT_save.Margin = new System.Windows.Forms.Padding(0); + resources.ApplyResources(this.BUT_save, "BUT_save"); this.BUT_save.Name = "BUT_save"; - this.BUT_save.Size = new System.Drawing.Size(104, 19); - this.BUT_save.TabIndex = 70; - this.BUT_save.Text = "Save"; this.BUT_save.UseVisualStyleBackColor = true; this.BUT_save.Click += new System.EventHandler(this.BUT_save_Click); // // BUT_load // - this.BUT_load.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right))); - this.BUT_load.ImeMode = System.Windows.Forms.ImeMode.NoControl; - this.BUT_load.Location = new System.Drawing.Point(341, 7); - this.BUT_load.Margin = new System.Windows.Forms.Padding(0); + resources.ApplyResources(this.BUT_load, "BUT_load"); this.BUT_load.Name = "BUT_load"; - this.BUT_load.Size = new System.Drawing.Size(104, 19); - this.BUT_load.TabIndex = 71; - this.BUT_load.Text = "Load"; this.BUT_load.UseVisualStyleBackColor = true; this.BUT_load.Click += new System.EventHandler(this.BUT_load_Click); // @@ -112,9 +86,7 @@ // this.Params.AllowUserToAddRows = false; this.Params.AllowUserToDeleteRows = false; - this.Params.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom) - | System.Windows.Forms.AnchorStyles.Left) - | System.Windows.Forms.AnchorStyles.Right))); + 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))); @@ -130,7 +102,6 @@ this.Default, this.mavScale, this.RawValue}); - this.Params.Location = new System.Drawing.Point(14, 3); this.Params.Name = "Params"; dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption; @@ -141,45 +112,37 @@ dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True; this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2; this.Params.RowHeadersVisible = false; - this.Params.RowHeadersWidth = 150; - this.Params.Size = new System.Drawing.Size(321, 302); - this.Params.TabIndex = 68; this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged); // // Command // - this.Command.HeaderText = "Command"; + resources.ApplyResources(this.Command, "Command"); this.Command.Name = "Command"; this.Command.ReadOnly = true; - this.Command.Width = 150; // // Value // - this.Value.HeaderText = "Value"; + resources.ApplyResources(this.Value, "Value"); this.Value.Name = "Value"; - this.Value.Width = 80; // // Default // - this.Default.HeaderText = "Default"; + resources.ApplyResources(this.Default, "Default"); this.Default.Name = "Default"; - this.Default.Visible = false; // // mavScale // - this.mavScale.HeaderText = "mavScale"; + resources.ApplyResources(this.mavScale, "mavScale"); this.mavScale.Name = "mavScale"; - this.mavScale.Visible = false; // // RawValue // - this.RawValue.HeaderText = "RawValue"; + resources.ApplyResources(this.RawValue, "RawValue"); this.RawValue.Name = "RawValue"; - this.RawValue.Visible = false; // // ConfigRawParams // - this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; this.Controls.Add(this.BUT_compare); this.Controls.Add(this.BUT_rerequestparams); @@ -188,7 +151,6 @@ this.Controls.Add(this.BUT_load); this.Controls.Add(this.Params); this.Name = "ConfigRawParams"; - this.Size = new System.Drawing.Size(460, 305); this.Load += new System.EventHandler(this.ConfigRawParams_Load); ((System.ComponentModel.ISupportInitialize)(this.Params)).EndInit(); this.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx index a5480f3926..3a3f70f565 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx @@ -117,19 +117,286 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Top, Right + + + NoControl + + + + 341, 119 + + + 103, 19 + + + + 72 + + + Compare Params + + + BUT_compare + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + + + Top, Right + + + NoControl + + + 341, 94 + + + 103, 19 + + + 67 + + + Refresh Params + + + BUT_rerequestparams + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 + + + Top, Right + + + NoControl + + + 341, 69 + + + 103, 19 + + + 69 + + + Write Params + + + BUT_writePIDS + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 2 + + + Top, Right + + + NoControl + + + 341, 35 + + + 0, 0, 0, 0 + + + 104, 19 + + + 70 + + + Save + + + BUT_save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 3 + + + Top, Right + + + NoControl + + + 341, 7 + + + 0, 0, 0, 0 + + + 104, 19 + + + 71 + + + Load + + + BUT_load + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 4 + + + Top, Bottom, Left, Right + True + + Command + + + 150 + True + + Value + + + 80 + True + + Default + + + False + + + mavScale + + + False + True + + RawValue + + + False + + + 14, 3 + + + 150 + + + 321, 302 + + + 68 + + + Params + + + System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + 17, 17 + + True + + + 6, 13 + + + 460, 305 + + + Command + + + 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 + + + ConfigRawParams + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs index b31c7ebd80..ca8b57a6bf 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs @@ -1,764 +1,764 @@ -namespace ArdupilotMega.GCSViews.ConfigurationView -{ - partial class ConfigTradHeli - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Component Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - this.components = new System.ComponentModel.Container(); - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigTradHeli)); - this.groupBox5 = new System.Windows.Forms.GroupBox(); - this.H1_ENABLE = new System.Windows.Forms.RadioButton(); - this.CCPM = new System.Windows.Forms.RadioButton(); - this.BUT_swash_manual = new ArdupilotMega.MyButton(); - this.label41 = new System.Windows.Forms.Label(); - this.groupBox3 = new System.Windows.Forms.GroupBox(); - this.label46 = new System.Windows.Forms.Label(); - this.label45 = new System.Windows.Forms.Label(); - this.GYR_ENABLE = new System.Windows.Forms.CheckBox(); - this.GYR_GAIN = new System.Windows.Forms.TextBox(); - this.BUT_HS4save = new ArdupilotMega.MyButton(); - this.label21 = new System.Windows.Forms.Label(); - this.COL_MIN = new System.Windows.Forms.TextBox(); - this.groupBox1 = new System.Windows.Forms.GroupBox(); - this.COL_MID = new System.Windows.Forms.TextBox(); - this.COL_MAX = new System.Windows.Forms.TextBox(); - this.BUT_0collective = new ArdupilotMega.MyButton(); - this.groupBox2 = new System.Windows.Forms.GroupBox(); - this.label24 = new System.Windows.Forms.Label(); - this.HS4_MIN = new System.Windows.Forms.TextBox(); - this.HS4_MAX = new System.Windows.Forms.TextBox(); - this.label40 = new System.Windows.Forms.Label(); - this.HS3_TRIM = new System.Windows.Forms.NumericUpDown(); - this.HS2_TRIM = new System.Windows.Forms.NumericUpDown(); - this.HS1_TRIM = new System.Windows.Forms.NumericUpDown(); - this.label39 = new System.Windows.Forms.Label(); - this.label38 = new System.Windows.Forms.Label(); - this.label37 = new System.Windows.Forms.Label(); - this.label36 = new System.Windows.Forms.Label(); - this.label26 = new System.Windows.Forms.Label(); - this.PIT_MAX = new System.Windows.Forms.TextBox(); - this.label25 = new System.Windows.Forms.Label(); - this.ROL_MAX = new System.Windows.Forms.TextBox(); - this.label23 = new System.Windows.Forms.Label(); - this.label22 = new System.Windows.Forms.Label(); - this.label20 = new System.Windows.Forms.Label(); - this.label19 = new System.Windows.Forms.Label(); - this.label18 = new System.Windows.Forms.Label(); - this.SV3_POS = new System.Windows.Forms.TextBox(); - this.SV2_POS = new System.Windows.Forms.TextBox(); - this.SV1_POS = new System.Windows.Forms.TextBox(); - this.HS3_REV = new System.Windows.Forms.CheckBox(); - this.HS2_REV = new System.Windows.Forms.CheckBox(); - this.HS1_REV = new System.Windows.Forms.CheckBox(); - this.label17 = new System.Windows.Forms.Label(); - this.HS4 = new ArdupilotMega.HorizontalProgressBar2(); - this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); - this.HS3 = new ArdupilotMega.VerticalProgressBar2(); - this.Gservoloc = new AGaugeApp.AGauge(); - this.label44 = new System.Windows.Forms.Label(); - this.label43 = new System.Windows.Forms.Label(); - this.label42 = new System.Windows.Forms.Label(); - this.HS4_TRIM = new System.Windows.Forms.NumericUpDown(); - this.HS4_REV = new System.Windows.Forms.CheckBox(); - this.groupBox5.SuspendLayout(); - this.groupBox3.SuspendLayout(); - this.groupBox1.SuspendLayout(); - this.groupBox2.SuspendLayout(); - ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit(); - this.SuspendLayout(); - // - // groupBox5 - // - this.groupBox5.Controls.Add(this.H1_ENABLE); - this.groupBox5.Controls.Add(this.CCPM); - resources.ApplyResources(this.groupBox5, "groupBox5"); - this.groupBox5.Name = "groupBox5"; - this.groupBox5.TabStop = false; - // - // H1_ENABLE - // - resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE"); - this.H1_ENABLE.Name = "H1_ENABLE"; - this.H1_ENABLE.TabStop = true; - this.H1_ENABLE.UseVisualStyleBackColor = true; - this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged); - // - // CCPM - // - resources.ApplyResources(this.CCPM, "CCPM"); - this.CCPM.Name = "CCPM"; - this.CCPM.TabStop = true; - this.CCPM.UseVisualStyleBackColor = true; - // - // BUT_swash_manual - // - resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual"); - this.BUT_swash_manual.Name = "BUT_swash_manual"; - this.BUT_swash_manual.UseVisualStyleBackColor = true; - this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click); - // - // label41 - // - resources.ApplyResources(this.label41, "label41"); - this.label41.Name = "label41"; - // - // 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; - // - // label46 - // - resources.ApplyResources(this.label46, "label46"); - this.label46.Name = "label46"; - // - // label45 - // - resources.ApplyResources(this.label45, "label45"); - this.label45.Name = "label45"; - // - // GYR_ENABLE - // - resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE"); - this.GYR_ENABLE.Name = "GYR_ENABLE"; - this.GYR_ENABLE.UseVisualStyleBackColor = true; - this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged); - // - // GYR_GAIN - // - resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN"); - this.GYR_GAIN.Name = "GYR_GAIN"; - this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating); - // - // BUT_HS4save - // - resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save"); - this.BUT_HS4save.Name = "BUT_HS4save"; - this.BUT_HS4save.UseVisualStyleBackColor = true; - this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click); - // - // label21 - // - resources.ApplyResources(this.label21, "label21"); - this.label21.Name = "label21"; - // - // COL_MIN - // - resources.ApplyResources(this.COL_MIN, "COL_MIN"); - this.COL_MIN.Name = "COL_MIN"; - // - // 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; - // - // COL_MID - // - resources.ApplyResources(this.COL_MID, "COL_MID"); - this.COL_MID.Name = "COL_MID"; - 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.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); - // - // BUT_0collective - // - resources.ApplyResources(this.BUT_0collective, "BUT_0collective"); - this.BUT_0collective.Name = "BUT_0collective"; - this.BUT_0collective.UseVisualStyleBackColor = true; - this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click); - // - // 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; - // - // label24 - // - resources.ApplyResources(this.label24, "label24"); - this.label24.Name = "label24"; - // - // HS4_MIN - // - resources.ApplyResources(this.HS4_MIN, "HS4_MIN"); - this.HS4_MIN.Name = "HS4_MIN"; - // - // HS4_MAX - // - resources.ApplyResources(this.HS4_MAX, "HS4_MAX"); - this.HS4_MAX.Name = "HS4_MAX"; - 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); - // - // label40 - // - resources.ApplyResources(this.label40, "label40"); - this.label40.Name = "label40"; - // - // HS3_TRIM - // - resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM"); - this.HS3_TRIM.Maximum = new decimal(new int[] { - 2000, - 0, - 0, - 0}); - this.HS3_TRIM.Minimum = new decimal(new int[] { - 1000, - 0, - 0, - 0}); - this.HS3_TRIM.Name = "HS3_TRIM"; - this.HS3_TRIM.Value = new decimal(new int[] { - 1500, - 0, - 0, - 0}); - this.HS3_TRIM.ValueChanged += new System.EventHandler(this.HS3_TRIM_ValueChanged); - // - // HS2_TRIM - // - resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM"); - this.HS2_TRIM.Maximum = new decimal(new int[] { - 2000, - 0, - 0, - 0}); - this.HS2_TRIM.Minimum = new decimal(new int[] { - 1000, - 0, - 0, - 0}); - this.HS2_TRIM.Name = "HS2_TRIM"; - this.HS2_TRIM.Value = new decimal(new int[] { - 1500, - 0, - 0, - 0}); - this.HS2_TRIM.ValueChanged += new System.EventHandler(this.HS2_TRIM_ValueChanged); - // - // HS1_TRIM - // - resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM"); - this.HS1_TRIM.Maximum = new decimal(new int[] { - 2000, - 0, - 0, - 0}); - this.HS1_TRIM.Minimum = new decimal(new int[] { - 1000, - 0, - 0, - 0}); - this.HS1_TRIM.Name = "HS1_TRIM"; - this.HS1_TRIM.Value = new decimal(new int[] { - 1500, - 0, - 0, - 0}); - this.HS1_TRIM.ValueChanged += new System.EventHandler(this.HS1_TRIM_ValueChanged); - // - // label39 - // - resources.ApplyResources(this.label39, "label39"); - this.label39.Name = "label39"; - // - // label38 - // - resources.ApplyResources(this.label38, "label38"); - this.label38.Name = "label38"; - // - // label37 - // - resources.ApplyResources(this.label37, "label37"); - this.label37.Name = "label37"; - // - // label36 - // - resources.ApplyResources(this.label36, "label36"); - this.label36.Name = "label36"; - // - // label26 - // - resources.ApplyResources(this.label26, "label26"); - this.label26.Name = "label26"; - // - // PIT_MAX - // - resources.ApplyResources(this.PIT_MAX, "PIT_MAX"); - this.PIT_MAX.Name = "PIT_MAX"; - this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating); - // - // label25 - // - resources.ApplyResources(this.label25, "label25"); - this.label25.Name = "label25"; - // - // ROL_MAX - // - resources.ApplyResources(this.ROL_MAX, "ROL_MAX"); - this.ROL_MAX.Name = "ROL_MAX"; - this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating); - // - // label23 - // - resources.ApplyResources(this.label23, "label23"); - this.label23.Name = "label23"; - // - // label22 - // - resources.ApplyResources(this.label22, "label22"); - this.label22.Name = "label22"; - // - // label20 - // - resources.ApplyResources(this.label20, "label20"); - this.label20.Name = "label20"; - // - // label19 - // - resources.ApplyResources(this.label19, "label19"); - this.label19.Name = "label19"; - // - // label18 - // - resources.ApplyResources(this.label18, "label18"); - this.label18.Name = "label18"; - // - // SV3_POS - // - resources.ApplyResources(this.SV3_POS, "SV3_POS"); - this.SV3_POS.Name = "SV3_POS"; - 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.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.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.HS3_REV.UseVisualStyleBackColor = true; - this.HS3_REV.CheckedChanged += new System.EventHandler(this.HS3_REV_CheckedChanged); - // - // HS2_REV - // - resources.ApplyResources(this.HS2_REV, "HS2_REV"); - this.HS2_REV.Name = "HS2_REV"; - this.HS2_REV.UseVisualStyleBackColor = true; - this.HS2_REV.CheckedChanged += new System.EventHandler(this.HS2_REV_CheckedChanged); - // - // HS1_REV - // - resources.ApplyResources(this.HS1_REV, "HS1_REV"); - this.HS1_REV.Name = "HS1_REV"; - this.HS1_REV.UseVisualStyleBackColor = true; - this.HS1_REV.CheckedChanged += new System.EventHandler(this.HS1_REV_CheckedChanged); - // - // label17 - // - resources.ApplyResources(this.label17, "label17"); - this.label17.Name = "label17"; - // - // 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.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); - // - // currentStateBindingSource - // - this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState); - // - // 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.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 - // - 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; - this.Gservoloc.BaseArcSweep = 360; - this.Gservoloc.BaseArcWidth = 2; - this.Gservoloc.basesize = new System.Drawing.Size(150, 150); - this.Gservoloc.Cap_Idx = ((byte)(0)); - this.Gservoloc.CapColor = System.Drawing.Color.White; - this.Gservoloc.CapColors = new System.Drawing.Color[] { - System.Drawing.Color.White, - System.Drawing.Color.Black, - System.Drawing.Color.Black, - System.Drawing.Color.Black, - System.Drawing.Color.Black}; - this.Gservoloc.CapPosition = new System.Drawing.Point(55, 85); - this.Gservoloc.CapsPosition = new System.Drawing.Point[] { - new System.Drawing.Point(55, 85), - new System.Drawing.Point(40, 67), - new System.Drawing.Point(10, 10), - new System.Drawing.Point(10, 10), - new System.Drawing.Point(10, 10)}; - this.Gservoloc.CapsText = new string[] { - "Position", - "", - "", - "", - ""}; - this.Gservoloc.CapText = "Position"; - this.Gservoloc.Center = new System.Drawing.Point(75, 75); - this.Gservoloc.MaxValue = 180F; - this.Gservoloc.MinValue = -180F; - this.Gservoloc.Name = "Gservoloc"; - this.Gservoloc.Need_Idx = ((byte)(3)); - this.Gservoloc.NeedleColor1 = AGaugeApp.AGauge.NeedleColorEnum.Gray; - this.Gservoloc.NeedleColor2 = System.Drawing.Color.White; - this.Gservoloc.NeedleEnabled = false; - this.Gservoloc.NeedleRadius = 80; - this.Gservoloc.NeedlesColor1 = new AGaugeApp.AGauge.NeedleColorEnum[] { - AGaugeApp.AGauge.NeedleColorEnum.Gray, - AGaugeApp.AGauge.NeedleColorEnum.Red, - AGaugeApp.AGauge.NeedleColorEnum.Green, - AGaugeApp.AGauge.NeedleColorEnum.Gray}; - this.Gservoloc.NeedlesColor2 = new System.Drawing.Color[] { - System.Drawing.Color.White, - System.Drawing.Color.White, - System.Drawing.Color.White, - System.Drawing.Color.White}; - this.Gservoloc.NeedlesEnabled = new bool[] { - true, - true, - true, - false}; - this.Gservoloc.NeedlesRadius = new int[] { - 60, - 60, - 60, - 80}; - this.Gservoloc.NeedlesType = new int[] { - 0, - 0, - 0, - 0}; - this.Gservoloc.NeedlesWidth = new int[] { - 2, - 2, - 2, - 2}; - this.Gservoloc.NeedleType = 0; - this.Gservoloc.NeedleWidth = 2; - this.Gservoloc.Range_Idx = ((byte)(0)); - this.Gservoloc.RangeColor = System.Drawing.Color.LightGreen; - this.Gservoloc.RangeEnabled = false; - this.Gservoloc.RangeEndValue = 360F; - this.Gservoloc.RangeInnerRadius = 1; - this.Gservoloc.RangeOuterRadius = 60; - this.Gservoloc.RangesColor = new System.Drawing.Color[] { - System.Drawing.Color.LightGreen, - System.Drawing.Color.Red, - System.Drawing.Color.Orange, - System.Drawing.SystemColors.Control, - System.Drawing.SystemColors.Control}; - this.Gservoloc.RangesEnabled = new bool[] { - false, - false, - false, - false, - false}; - this.Gservoloc.RangesEndValue = new float[] { - 360F, - 200F, - 150F, - 0F, - 0F}; - this.Gservoloc.RangesInnerRadius = new int[] { - 1, - 1, - 1, - 70, - 70}; - this.Gservoloc.RangesOuterRadius = new int[] { - 60, - 60, - 60, - 80, - 80}; - this.Gservoloc.RangesStartValue = new float[] { - 0F, - 150F, - 75F, - 0F, - 0F}; - this.Gservoloc.RangeStartValue = 0F; - this.Gservoloc.ScaleLinesInterColor = System.Drawing.Color.White; - this.Gservoloc.ScaleLinesInterInnerRadius = 52; - this.Gservoloc.ScaleLinesInterOuterRadius = 60; - this.Gservoloc.ScaleLinesInterWidth = 1; - this.Gservoloc.ScaleLinesMajorColor = System.Drawing.Color.White; - this.Gservoloc.ScaleLinesMajorInnerRadius = 50; - this.Gservoloc.ScaleLinesMajorOuterRadius = 60; - this.Gservoloc.ScaleLinesMajorStepValue = 30F; - this.Gservoloc.ScaleLinesMajorWidth = 2; - this.Gservoloc.ScaleLinesMinorColor = System.Drawing.Color.White; - this.Gservoloc.ScaleLinesMinorInnerRadius = 55; - this.Gservoloc.ScaleLinesMinorNumOf = 2; - this.Gservoloc.ScaleLinesMinorOuterRadius = 60; - this.Gservoloc.ScaleLinesMinorWidth = 1; - this.Gservoloc.ScaleNumbersColor = System.Drawing.Color.White; - this.Gservoloc.ScaleNumbersFormat = null; - this.Gservoloc.ScaleNumbersRadius = 44; - this.Gservoloc.ScaleNumbersRotation = 45; - this.Gservoloc.ScaleNumbersStartScaleLine = 2; - this.Gservoloc.ScaleNumbersStepScaleLines = 1; - this.Gservoloc.Value = 0F; - this.Gservoloc.Value0 = -60F; - this.Gservoloc.Value1 = 60F; - this.Gservoloc.Value2 = 180F; - this.Gservoloc.Value3 = 0F; - // - // label44 - // - resources.ApplyResources(this.label44, "label44"); - this.label44.Name = "label44"; - // - // label43 - // - resources.ApplyResources(this.label43, "label43"); - this.label43.Name = "label43"; - // - // label42 - // - resources.ApplyResources(this.label42, "label42"); - this.label42.Name = "label42"; - // - // HS4_TRIM - // - resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM"); - this.HS4_TRIM.Maximum = new decimal(new int[] { - 2000, - 0, - 0, - 0}); - this.HS4_TRIM.Minimum = new decimal(new int[] { - 1000, - 0, - 0, - 0}); - this.HS4_TRIM.Name = "HS4_TRIM"; - this.HS4_TRIM.Value = new decimal(new int[] { - 1500, - 0, - 0, - 0}); - this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged); - // - // HS4_REV - // - resources.ApplyResources(this.HS4_REV, "HS4_REV"); - this.HS4_REV.Name = "HS4_REV"; - this.HS4_REV.UseVisualStyleBackColor = true; - this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged); - // - // ConfigTradHeli - // - resources.ApplyResources(this, "$this"); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.label44); - this.Controls.Add(this.label43); - this.Controls.Add(this.label42); - this.Controls.Add(this.HS4_TRIM); - this.Controls.Add(this.HS4_REV); - this.Controls.Add(this.groupBox5); - this.Controls.Add(this.BUT_swash_manual); - this.Controls.Add(this.groupBox3); - this.Controls.Add(this.BUT_HS4save); - this.Controls.Add(this.groupBox1); - this.Controls.Add(this.groupBox2); - this.Controls.Add(this.HS3_TRIM); - this.Controls.Add(this.HS2_TRIM); - this.Controls.Add(this.HS1_TRIM); - this.Controls.Add(this.label39); - this.Controls.Add(this.label38); - this.Controls.Add(this.label37); - this.Controls.Add(this.label36); - this.Controls.Add(this.label26); - this.Controls.Add(this.PIT_MAX); - this.Controls.Add(this.label25); - this.Controls.Add(this.ROL_MAX); - this.Controls.Add(this.label23); - this.Controls.Add(this.label22); - this.Controls.Add(this.label20); - this.Controls.Add(this.label19); - this.Controls.Add(this.label18); - this.Controls.Add(this.SV3_POS); - this.Controls.Add(this.SV2_POS); - this.Controls.Add(this.SV1_POS); - this.Controls.Add(this.HS3_REV); - this.Controls.Add(this.HS2_REV); - this.Controls.Add(this.HS1_REV); - this.Controls.Add(this.label17); - this.Controls.Add(this.HS4); - this.Controls.Add(this.HS3); - this.Controls.Add(this.Gservoloc); - this.Name = "ConfigTradHeli"; - this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.ConfigTradHeli_FormClosing); - this.Load += new System.EventHandler(this.ConfigTradHeli_Load); - this.groupBox5.ResumeLayout(false); - this.groupBox5.PerformLayout(); - this.groupBox3.ResumeLayout(false); - this.groupBox3.PerformLayout(); - this.groupBox1.ResumeLayout(false); - this.groupBox1.PerformLayout(); - this.groupBox2.ResumeLayout(false); - this.groupBox2.PerformLayout(); - ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit(); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private System.Windows.Forms.GroupBox groupBox5; - private System.Windows.Forms.RadioButton H1_ENABLE; - private System.Windows.Forms.RadioButton CCPM; - private MyButton BUT_swash_manual; - private System.Windows.Forms.Label label41; - private System.Windows.Forms.GroupBox groupBox3; - private System.Windows.Forms.Label label46; - private System.Windows.Forms.Label label45; - private System.Windows.Forms.CheckBox GYR_ENABLE; - private System.Windows.Forms.TextBox GYR_GAIN; - private MyButton BUT_HS4save; - private System.Windows.Forms.Label label21; - private System.Windows.Forms.TextBox COL_MIN; - private System.Windows.Forms.GroupBox groupBox1; - private System.Windows.Forms.TextBox COL_MID; - private System.Windows.Forms.TextBox COL_MAX; - private MyButton BUT_0collective; - private System.Windows.Forms.GroupBox groupBox2; - private System.Windows.Forms.Label label24; - private System.Windows.Forms.TextBox HS4_MIN; - private System.Windows.Forms.TextBox HS4_MAX; - private System.Windows.Forms.Label label40; - private System.Windows.Forms.NumericUpDown HS3_TRIM; - private System.Windows.Forms.NumericUpDown HS2_TRIM; - private System.Windows.Forms.NumericUpDown HS1_TRIM; - private System.Windows.Forms.Label label39; - private System.Windows.Forms.Label label38; - private System.Windows.Forms.Label label37; - private System.Windows.Forms.Label label36; - private System.Windows.Forms.Label label26; - private System.Windows.Forms.TextBox PIT_MAX; - private System.Windows.Forms.Label label25; - private System.Windows.Forms.TextBox ROL_MAX; - private System.Windows.Forms.Label label23; - private System.Windows.Forms.Label label22; - private System.Windows.Forms.Label label20; - private System.Windows.Forms.Label label19; - private System.Windows.Forms.Label label18; - private System.Windows.Forms.TextBox SV3_POS; - private System.Windows.Forms.TextBox SV2_POS; - private System.Windows.Forms.TextBox SV1_POS; - private System.Windows.Forms.CheckBox HS3_REV; - private System.Windows.Forms.CheckBox HS2_REV; - private System.Windows.Forms.CheckBox HS1_REV; - private System.Windows.Forms.Label label17; - private HorizontalProgressBar2 HS4; - private VerticalProgressBar2 HS3; - private AGaugeApp.AGauge Gservoloc; - private System.Windows.Forms.BindingSource currentStateBindingSource; - private System.Windows.Forms.Label label44; - private System.Windows.Forms.Label label43; - private System.Windows.Forms.Label label42; - private System.Windows.Forms.NumericUpDown HS4_TRIM; - private System.Windows.Forms.CheckBox HS4_REV; - } -} +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class ConfigTradHeli + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Component Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + this.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigTradHeli)); + this.groupBox5 = new System.Windows.Forms.GroupBox(); + this.H1_ENABLE = new System.Windows.Forms.RadioButton(); + this.CCPM = new System.Windows.Forms.RadioButton(); + this.BUT_swash_manual = new ArdupilotMega.MyButton(); + this.label41 = new System.Windows.Forms.Label(); + this.groupBox3 = new System.Windows.Forms.GroupBox(); + this.label46 = new System.Windows.Forms.Label(); + this.label45 = new System.Windows.Forms.Label(); + this.GYR_ENABLE = new System.Windows.Forms.CheckBox(); + this.GYR_GAIN = new System.Windows.Forms.TextBox(); + this.BUT_HS4save = new ArdupilotMega.MyButton(); + this.label21 = new System.Windows.Forms.Label(); + this.COL_MIN = new System.Windows.Forms.TextBox(); + this.groupBox1 = new System.Windows.Forms.GroupBox(); + this.COL_MID = new System.Windows.Forms.TextBox(); + this.COL_MAX = new System.Windows.Forms.TextBox(); + this.BUT_0collective = new ArdupilotMega.MyButton(); + this.groupBox2 = new System.Windows.Forms.GroupBox(); + this.label24 = new System.Windows.Forms.Label(); + this.HS4_MIN = new System.Windows.Forms.TextBox(); + this.HS4_MAX = new System.Windows.Forms.TextBox(); + this.label40 = new System.Windows.Forms.Label(); + this.HS3_TRIM = new System.Windows.Forms.NumericUpDown(); + this.HS2_TRIM = new System.Windows.Forms.NumericUpDown(); + this.HS1_TRIM = new System.Windows.Forms.NumericUpDown(); + this.label39 = new System.Windows.Forms.Label(); + this.label38 = new System.Windows.Forms.Label(); + this.label37 = new System.Windows.Forms.Label(); + this.label36 = new System.Windows.Forms.Label(); + this.label26 = new System.Windows.Forms.Label(); + this.PIT_MAX = new System.Windows.Forms.TextBox(); + this.label25 = new System.Windows.Forms.Label(); + this.ROL_MAX = new System.Windows.Forms.TextBox(); + this.label23 = new System.Windows.Forms.Label(); + this.label22 = new System.Windows.Forms.Label(); + this.label20 = new System.Windows.Forms.Label(); + this.label19 = new System.Windows.Forms.Label(); + this.label18 = new System.Windows.Forms.Label(); + this.SV3_POS = new System.Windows.Forms.TextBox(); + this.SV2_POS = new System.Windows.Forms.TextBox(); + this.SV1_POS = new System.Windows.Forms.TextBox(); + this.HS3_REV = new System.Windows.Forms.CheckBox(); + this.HS2_REV = new System.Windows.Forms.CheckBox(); + this.HS1_REV = new System.Windows.Forms.CheckBox(); + this.label17 = new System.Windows.Forms.Label(); + this.HS4 = new ArdupilotMega.HorizontalProgressBar2(); + this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); + this.HS3 = new ArdupilotMega.VerticalProgressBar2(); + this.Gservoloc = new AGaugeApp.AGauge(); + this.label44 = new System.Windows.Forms.Label(); + this.label43 = new System.Windows.Forms.Label(); + this.label42 = new System.Windows.Forms.Label(); + this.HS4_TRIM = new System.Windows.Forms.NumericUpDown(); + this.HS4_REV = new System.Windows.Forms.CheckBox(); + this.groupBox5.SuspendLayout(); + this.groupBox3.SuspendLayout(); + this.groupBox1.SuspendLayout(); + this.groupBox2.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit(); + this.SuspendLayout(); + // + // groupBox5 + // + this.groupBox5.Controls.Add(this.H1_ENABLE); + this.groupBox5.Controls.Add(this.CCPM); + resources.ApplyResources(this.groupBox5, "groupBox5"); + this.groupBox5.Name = "groupBox5"; + this.groupBox5.TabStop = false; + // + // H1_ENABLE + // + resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE"); + this.H1_ENABLE.Name = "H1_ENABLE"; + this.H1_ENABLE.TabStop = true; + this.H1_ENABLE.UseVisualStyleBackColor = true; + this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged); + // + // CCPM + // + resources.ApplyResources(this.CCPM, "CCPM"); + this.CCPM.Name = "CCPM"; + this.CCPM.TabStop = true; + this.CCPM.UseVisualStyleBackColor = true; + // + // BUT_swash_manual + // + resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual"); + this.BUT_swash_manual.Name = "BUT_swash_manual"; + this.BUT_swash_manual.UseVisualStyleBackColor = true; + this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click); + // + // label41 + // + resources.ApplyResources(this.label41, "label41"); + this.label41.Name = "label41"; + // + // 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; + // + // label46 + // + resources.ApplyResources(this.label46, "label46"); + this.label46.Name = "label46"; + // + // label45 + // + resources.ApplyResources(this.label45, "label45"); + this.label45.Name = "label45"; + // + // GYR_ENABLE + // + resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE"); + this.GYR_ENABLE.Name = "GYR_ENABLE"; + this.GYR_ENABLE.UseVisualStyleBackColor = true; + this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged); + // + // GYR_GAIN + // + resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN"); + this.GYR_GAIN.Name = "GYR_GAIN"; + this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating); + // + // BUT_HS4save + // + resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save"); + this.BUT_HS4save.Name = "BUT_HS4save"; + this.BUT_HS4save.UseVisualStyleBackColor = true; + this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click); + // + // label21 + // + resources.ApplyResources(this.label21, "label21"); + this.label21.Name = "label21"; + // + // COL_MIN + // + resources.ApplyResources(this.COL_MIN, "COL_MIN"); + this.COL_MIN.Name = "COL_MIN"; + // + // 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; + // + // COL_MID + // + resources.ApplyResources(this.COL_MID, "COL_MID"); + this.COL_MID.Name = "COL_MID"; + 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.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); + // + // BUT_0collective + // + resources.ApplyResources(this.BUT_0collective, "BUT_0collective"); + this.BUT_0collective.Name = "BUT_0collective"; + this.BUT_0collective.UseVisualStyleBackColor = true; + this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click); + // + // 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; + // + // label24 + // + resources.ApplyResources(this.label24, "label24"); + this.label24.Name = "label24"; + // + // HS4_MIN + // + resources.ApplyResources(this.HS4_MIN, "HS4_MIN"); + this.HS4_MIN.Name = "HS4_MIN"; + // + // HS4_MAX + // + resources.ApplyResources(this.HS4_MAX, "HS4_MAX"); + this.HS4_MAX.Name = "HS4_MAX"; + 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); + // + // label40 + // + resources.ApplyResources(this.label40, "label40"); + this.label40.Name = "label40"; + // + // HS3_TRIM + // + resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM"); + this.HS3_TRIM.Maximum = new decimal(new int[] { + 2000, + 0, + 0, + 0}); + this.HS3_TRIM.Minimum = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.HS3_TRIM.Name = "HS3_TRIM"; + this.HS3_TRIM.Value = new decimal(new int[] { + 1500, + 0, + 0, + 0}); + this.HS3_TRIM.ValueChanged += new System.EventHandler(this.HS3_TRIM_ValueChanged); + // + // HS2_TRIM + // + resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM"); + this.HS2_TRIM.Maximum = new decimal(new int[] { + 2000, + 0, + 0, + 0}); + this.HS2_TRIM.Minimum = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.HS2_TRIM.Name = "HS2_TRIM"; + this.HS2_TRIM.Value = new decimal(new int[] { + 1500, + 0, + 0, + 0}); + this.HS2_TRIM.ValueChanged += new System.EventHandler(this.HS2_TRIM_ValueChanged); + // + // HS1_TRIM + // + resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM"); + this.HS1_TRIM.Maximum = new decimal(new int[] { + 2000, + 0, + 0, + 0}); + this.HS1_TRIM.Minimum = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.HS1_TRIM.Name = "HS1_TRIM"; + this.HS1_TRIM.Value = new decimal(new int[] { + 1500, + 0, + 0, + 0}); + this.HS1_TRIM.ValueChanged += new System.EventHandler(this.HS1_TRIM_ValueChanged); + // + // label39 + // + resources.ApplyResources(this.label39, "label39"); + this.label39.Name = "label39"; + // + // label38 + // + resources.ApplyResources(this.label38, "label38"); + this.label38.Name = "label38"; + // + // label37 + // + resources.ApplyResources(this.label37, "label37"); + this.label37.Name = "label37"; + // + // label36 + // + resources.ApplyResources(this.label36, "label36"); + this.label36.Name = "label36"; + // + // label26 + // + resources.ApplyResources(this.label26, "label26"); + this.label26.Name = "label26"; + // + // PIT_MAX + // + resources.ApplyResources(this.PIT_MAX, "PIT_MAX"); + this.PIT_MAX.Name = "PIT_MAX"; + this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating); + // + // label25 + // + resources.ApplyResources(this.label25, "label25"); + this.label25.Name = "label25"; + // + // ROL_MAX + // + resources.ApplyResources(this.ROL_MAX, "ROL_MAX"); + this.ROL_MAX.Name = "ROL_MAX"; + this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating); + // + // label23 + // + resources.ApplyResources(this.label23, "label23"); + this.label23.Name = "label23"; + // + // label22 + // + resources.ApplyResources(this.label22, "label22"); + this.label22.Name = "label22"; + // + // label20 + // + resources.ApplyResources(this.label20, "label20"); + this.label20.Name = "label20"; + // + // label19 + // + resources.ApplyResources(this.label19, "label19"); + this.label19.Name = "label19"; + // + // label18 + // + resources.ApplyResources(this.label18, "label18"); + this.label18.Name = "label18"; + // + // SV3_POS + // + resources.ApplyResources(this.SV3_POS, "SV3_POS"); + this.SV3_POS.Name = "SV3_POS"; + 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.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.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.HS3_REV.UseVisualStyleBackColor = true; + this.HS3_REV.CheckedChanged += new System.EventHandler(this.HS3_REV_CheckedChanged); + // + // HS2_REV + // + resources.ApplyResources(this.HS2_REV, "HS2_REV"); + this.HS2_REV.Name = "HS2_REV"; + this.HS2_REV.UseVisualStyleBackColor = true; + this.HS2_REV.CheckedChanged += new System.EventHandler(this.HS2_REV_CheckedChanged); + // + // HS1_REV + // + resources.ApplyResources(this.HS1_REV, "HS1_REV"); + this.HS1_REV.Name = "HS1_REV"; + this.HS1_REV.UseVisualStyleBackColor = true; + this.HS1_REV.CheckedChanged += new System.EventHandler(this.HS1_REV_CheckedChanged); + // + // label17 + // + resources.ApplyResources(this.label17, "label17"); + this.label17.Name = "label17"; + // + // 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.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); + // + // currentStateBindingSource + // + this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState); + // + // 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.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 + // + 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; + this.Gservoloc.BaseArcSweep = 360; + this.Gservoloc.BaseArcWidth = 2; + this.Gservoloc.basesize = new System.Drawing.Size(150, 150); + this.Gservoloc.Cap_Idx = ((byte)(0)); + this.Gservoloc.CapColor = System.Drawing.Color.White; + this.Gservoloc.CapColors = new System.Drawing.Color[] { + System.Drawing.Color.White, + System.Drawing.Color.Black, + System.Drawing.Color.Black, + System.Drawing.Color.Black, + System.Drawing.Color.Black}; + this.Gservoloc.CapPosition = new System.Drawing.Point(55, 85); + this.Gservoloc.CapsPosition = new System.Drawing.Point[] { + new System.Drawing.Point(55, 85), + new System.Drawing.Point(40, 67), + new System.Drawing.Point(10, 10), + new System.Drawing.Point(10, 10), + new System.Drawing.Point(10, 10)}; + this.Gservoloc.CapsText = new string[] { + "Position", + "", + "", + "", + ""}; + this.Gservoloc.CapText = "Position"; + this.Gservoloc.Center = new System.Drawing.Point(75, 75); + this.Gservoloc.MaxValue = 180F; + this.Gservoloc.MinValue = -180F; + this.Gservoloc.Name = "Gservoloc"; + this.Gservoloc.Need_Idx = ((byte)(3)); + this.Gservoloc.NeedleColor1 = AGaugeApp.AGauge.NeedleColorEnum.Gray; + this.Gservoloc.NeedleColor2 = System.Drawing.Color.White; + this.Gservoloc.NeedleEnabled = false; + this.Gservoloc.NeedleRadius = 80; + this.Gservoloc.NeedlesColor1 = new AGaugeApp.AGauge.NeedleColorEnum[] { + AGaugeApp.AGauge.NeedleColorEnum.Gray, + AGaugeApp.AGauge.NeedleColorEnum.Red, + AGaugeApp.AGauge.NeedleColorEnum.Green, + AGaugeApp.AGauge.NeedleColorEnum.Gray}; + this.Gservoloc.NeedlesColor2 = new System.Drawing.Color[] { + System.Drawing.Color.White, + System.Drawing.Color.White, + System.Drawing.Color.White, + System.Drawing.Color.White}; + this.Gservoloc.NeedlesEnabled = new bool[] { + true, + true, + true, + false}; + this.Gservoloc.NeedlesRadius = new int[] { + 60, + 60, + 60, + 80}; + this.Gservoloc.NeedlesType = new int[] { + 0, + 0, + 0, + 0}; + this.Gservoloc.NeedlesWidth = new int[] { + 2, + 2, + 2, + 2}; + this.Gservoloc.NeedleType = 0; + this.Gservoloc.NeedleWidth = 2; + this.Gservoloc.Range_Idx = ((byte)(0)); + this.Gservoloc.RangeColor = System.Drawing.Color.LightGreen; + this.Gservoloc.RangeEnabled = false; + this.Gservoloc.RangeEndValue = 360F; + this.Gservoloc.RangeInnerRadius = 1; + this.Gservoloc.RangeOuterRadius = 60; + this.Gservoloc.RangesColor = new System.Drawing.Color[] { + System.Drawing.Color.LightGreen, + System.Drawing.Color.Red, + System.Drawing.Color.Orange, + System.Drawing.SystemColors.Control, + System.Drawing.SystemColors.Control}; + this.Gservoloc.RangesEnabled = new bool[] { + false, + false, + false, + false, + false}; + this.Gservoloc.RangesEndValue = new float[] { + 360F, + 200F, + 150F, + 0F, + 0F}; + this.Gservoloc.RangesInnerRadius = new int[] { + 1, + 1, + 1, + 70, + 70}; + this.Gservoloc.RangesOuterRadius = new int[] { + 60, + 60, + 60, + 80, + 80}; + this.Gservoloc.RangesStartValue = new float[] { + 0F, + 150F, + 75F, + 0F, + 0F}; + this.Gservoloc.RangeStartValue = 0F; + this.Gservoloc.ScaleLinesInterColor = System.Drawing.Color.White; + this.Gservoloc.ScaleLinesInterInnerRadius = 52; + this.Gservoloc.ScaleLinesInterOuterRadius = 60; + this.Gservoloc.ScaleLinesInterWidth = 1; + this.Gservoloc.ScaleLinesMajorColor = System.Drawing.Color.White; + this.Gservoloc.ScaleLinesMajorInnerRadius = 50; + this.Gservoloc.ScaleLinesMajorOuterRadius = 60; + this.Gservoloc.ScaleLinesMajorStepValue = 30F; + this.Gservoloc.ScaleLinesMajorWidth = 2; + this.Gservoloc.ScaleLinesMinorColor = System.Drawing.Color.White; + this.Gservoloc.ScaleLinesMinorInnerRadius = 55; + this.Gservoloc.ScaleLinesMinorNumOf = 2; + this.Gservoloc.ScaleLinesMinorOuterRadius = 60; + this.Gservoloc.ScaleLinesMinorWidth = 1; + this.Gservoloc.ScaleNumbersColor = System.Drawing.Color.White; + this.Gservoloc.ScaleNumbersFormat = null; + this.Gservoloc.ScaleNumbersRadius = 44; + this.Gservoloc.ScaleNumbersRotation = 45; + this.Gservoloc.ScaleNumbersStartScaleLine = 2; + this.Gservoloc.ScaleNumbersStepScaleLines = 1; + this.Gservoloc.Value = 0F; + this.Gservoloc.Value0 = -60F; + this.Gservoloc.Value1 = 60F; + this.Gservoloc.Value2 = 180F; + this.Gservoloc.Value3 = 0F; + // + // label44 + // + resources.ApplyResources(this.label44, "label44"); + this.label44.Name = "label44"; + // + // label43 + // + resources.ApplyResources(this.label43, "label43"); + this.label43.Name = "label43"; + // + // label42 + // + resources.ApplyResources(this.label42, "label42"); + this.label42.Name = "label42"; + // + // HS4_TRIM + // + resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM"); + this.HS4_TRIM.Maximum = new decimal(new int[] { + 2000, + 0, + 0, + 0}); + this.HS4_TRIM.Minimum = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.HS4_TRIM.Name = "HS4_TRIM"; + this.HS4_TRIM.Value = new decimal(new int[] { + 1500, + 0, + 0, + 0}); + this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged); + // + // HS4_REV + // + resources.ApplyResources(this.HS4_REV, "HS4_REV"); + this.HS4_REV.Name = "HS4_REV"; + this.HS4_REV.UseVisualStyleBackColor = true; + this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged); + // + // ConfigTradHeli + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.label44); + this.Controls.Add(this.label43); + this.Controls.Add(this.label42); + this.Controls.Add(this.HS4_TRIM); + this.Controls.Add(this.HS4_REV); + this.Controls.Add(this.groupBox5); + this.Controls.Add(this.BUT_swash_manual); + this.Controls.Add(this.groupBox3); + this.Controls.Add(this.BUT_HS4save); + this.Controls.Add(this.groupBox1); + this.Controls.Add(this.groupBox2); + this.Controls.Add(this.HS3_TRIM); + this.Controls.Add(this.HS2_TRIM); + this.Controls.Add(this.HS1_TRIM); + this.Controls.Add(this.label39); + this.Controls.Add(this.label38); + this.Controls.Add(this.label37); + this.Controls.Add(this.label36); + this.Controls.Add(this.label26); + this.Controls.Add(this.PIT_MAX); + this.Controls.Add(this.label25); + this.Controls.Add(this.ROL_MAX); + this.Controls.Add(this.label23); + this.Controls.Add(this.label22); + this.Controls.Add(this.label20); + this.Controls.Add(this.label19); + this.Controls.Add(this.label18); + this.Controls.Add(this.SV3_POS); + this.Controls.Add(this.SV2_POS); + this.Controls.Add(this.SV1_POS); + this.Controls.Add(this.HS3_REV); + this.Controls.Add(this.HS2_REV); + this.Controls.Add(this.HS1_REV); + this.Controls.Add(this.label17); + this.Controls.Add(this.HS4); + this.Controls.Add(this.HS3); + this.Controls.Add(this.Gservoloc); + this.Name = "ConfigTradHeli"; + this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.ConfigTradHeli_FormClosing); + this.Load += new System.EventHandler(this.ConfigTradHeli_Load); + this.groupBox5.ResumeLayout(false); + this.groupBox5.PerformLayout(); + this.groupBox3.ResumeLayout(false); + this.groupBox3.PerformLayout(); + this.groupBox1.ResumeLayout(false); + this.groupBox1.PerformLayout(); + this.groupBox2.ResumeLayout(false); + this.groupBox2.PerformLayout(); + ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.GroupBox groupBox5; + private System.Windows.Forms.RadioButton H1_ENABLE; + private System.Windows.Forms.RadioButton CCPM; + private MyButton BUT_swash_manual; + private System.Windows.Forms.Label label41; + private System.Windows.Forms.GroupBox groupBox3; + private System.Windows.Forms.Label label46; + private System.Windows.Forms.Label label45; + private System.Windows.Forms.CheckBox GYR_ENABLE; + private System.Windows.Forms.TextBox GYR_GAIN; + private MyButton BUT_HS4save; + private System.Windows.Forms.Label label21; + private System.Windows.Forms.TextBox COL_MIN; + private System.Windows.Forms.GroupBox groupBox1; + private System.Windows.Forms.TextBox COL_MID; + private System.Windows.Forms.TextBox COL_MAX; + private MyButton BUT_0collective; + private System.Windows.Forms.GroupBox groupBox2; + private System.Windows.Forms.Label label24; + private System.Windows.Forms.TextBox HS4_MIN; + private System.Windows.Forms.TextBox HS4_MAX; + private System.Windows.Forms.Label label40; + private System.Windows.Forms.NumericUpDown HS3_TRIM; + private System.Windows.Forms.NumericUpDown HS2_TRIM; + private System.Windows.Forms.NumericUpDown HS1_TRIM; + private System.Windows.Forms.Label label39; + private System.Windows.Forms.Label label38; + private System.Windows.Forms.Label label37; + private System.Windows.Forms.Label label36; + private System.Windows.Forms.Label label26; + private System.Windows.Forms.TextBox PIT_MAX; + private System.Windows.Forms.Label label25; + private System.Windows.Forms.TextBox ROL_MAX; + private System.Windows.Forms.Label label23; + private System.Windows.Forms.Label label22; + private System.Windows.Forms.Label label20; + private System.Windows.Forms.Label label19; + private System.Windows.Forms.Label label18; + private System.Windows.Forms.TextBox SV3_POS; + private System.Windows.Forms.TextBox SV2_POS; + private System.Windows.Forms.TextBox SV1_POS; + private System.Windows.Forms.CheckBox HS3_REV; + private System.Windows.Forms.CheckBox HS2_REV; + private System.Windows.Forms.CheckBox HS1_REV; + private System.Windows.Forms.Label label17; + private HorizontalProgressBar2 HS4; + private VerticalProgressBar2 HS3; + private AGaugeApp.AGauge Gservoloc; + private System.Windows.Forms.BindingSource currentStateBindingSource; + private System.Windows.Forms.Label label44; + private System.Windows.Forms.Label label43; + private System.Windows.Forms.Label label42; + private System.Windows.Forms.NumericUpDown HS4_TRIM; + private System.Windows.Forms.CheckBox HS4_REV; + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx index 9ec943c76a..99fe5c163d 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx @@ -1,1581 +1,1581 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - True - - - - NoControl - - - - 67, 19 - - - 39, 17 - - - 137 - - - H1 - - - H1_ENABLE - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 0 - - - True - - - NoControl - - - 6, 19 - - - 55, 17 - - - 136 - - - CCPM - - - CCPM - - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox5 - - - 1 - - - 257, 11 - - - 120, 43 - - - 169 - - - Swash Type - - - groupBox5 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - NoControl - - - 302, 83 - - - 69, 23 - - - 138 - - - Manual - - - BUT_swash_manual - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - - - $this - - - 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 - - - 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 - - - 437, 314 - - - 101, 63 - - - 168 - - - Gyro - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - NoControl - - - 483, 174 - - - 69, 23 - - - 167 - - - Manual - - - BUT_HS4save - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - - - $this - - - 8 - - - True - - - NoControl - - - 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 - - - False - - - 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 - - - False - - - 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 - - - False - - - 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 - - - False - - - NoControl - - - 11, 89 - - - 58, 23 - - - 110 - - - Zero - - - BUT_0collective - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - - - groupBox1 - - - 5 - - - 297, 95 - - - 80, 209 - - - 165 - - - groupBox1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 9 - - - 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 - - - False - - - 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 - - - False - - - 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 - - - 437, 186 - - - 169, 78 - - - 166 - - - groupBox2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - - 126, 314 - - - 44, 20 - - - 164 - - - HS3_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 11 - - - 126, 288 - - - 44, 20 - - - 163 - - - HS2_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 12 - - - 126, 262 - - - 44, 20 - - - 162 - - - HS1_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 13 - - - True - - - NoControl - - - 131, 249 - - - 27, 13 - - - 161 - - - Trim - - - label39 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 14 - - - True - - - NoControl - - - 102, 249 - - - 27, 13 - - - 160 - - - Rev - - - label38 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 15 - - - True - - - NoControl - - - 54, 249 - - - 44, 13 - - - 159 - - - Position - - - label37 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 16 - - - True - - - NoControl - - - 17, 249 - - - 35, 13 - - - 158 - - - Servo - - - label36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 17 - - - True - - - NoControl - - - 260, 365 - - - 54, 13 - - - 157 - - - Pitch Max - - - label26 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 18 - - - 314, 362 - - - 47, 20 - - - 156 - - - 4500 - - - PIT_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 19 - - - True - - - NoControl - - - 260, 341 - - - 48, 13 - - - 155 - - - Roll Max - - - label25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 20 - - - 314, 336 - - - 47, 20 - - - 154 - - - 4500 - - - ROL_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 21 - - - True - - - NoControl - - - 480, 66 - - - 75, 13 - - - 153 - - - Rudder Travel - - - label23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 22 - - - True - - - NoControl - - - 236, 66 - - - 72, 13 - - - 150 - - - Swash Travel - - - label22 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 23 - - - True - - - NoControl - - - 27, 317 - - - 13, 13 - - - 149 - - - 3 - - - label20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 24 - - - True - - - NoControl - - - 27, 291 - - - 13, 13 - - - 148 - - - 2 - - - label19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 25 - - - True - - - NoControl - - - 27, 265 - - - 13, 13 - - - 147 - - - 1 - - - label18 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 26 - - - 57, 314 - - - 39, 20 - - - 146 - - - 180 - - - SV3_POS - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 27 - - - 57, 288 - - - 39, 20 - - - 145 - - - 60 - - - SV2_POS - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 28 - - - 57, 262 - - - 39, 20 - - - 144 - - - -60 - - - SV1_POS - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 29 - - - True - - - NoControl - - - 105, 317 - - - 15, 14 - - - 143 - - - HS3_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 30 - - - True - - - NoControl - - - 105, 291 - - - 15, 14 - - - 142 - - - HS2_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 31 - - - True - - - NoControl - - - 105, 268 - - - 15, 14 - - - 141 - - - HS1_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 32 - - - True - - - NoControl - - - 42, 66 - - - 109, 13 - - - 140 - - - Swash-Servo position - - - label17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 33 - - - 17, 17 - - - 396, 93 - - - 242, 42 - - - 152 - - - HS4 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - - - $this - - - 34 - - - 239, 95 - - - 42, 213 - - - 151 - - - HS3 - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - - - $this - - - 35 - - - Zoom - - - Microsoft Sans Serif, 9pt - - - 20, 93 - - - 0, 0, 0, 0 - - - 150, 150 - - - 139 - - - Gservoloc - - - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - - - $this - - - 36 - - - True - - - NoControl - - - 529, 268 - - - 27, 13 - - - 174 - - - Trim - - - label44 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - True - - - NoControl - - - 496, 268 - - - 27, 13 - - - 173 - - - Rev - - - label43 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 1 - - - True - - - NoControl - - - 448, 288 - - - 42, 13 - - - 172 - - - Rudder - - - label42 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - 532, 284 - - - 44, 20 - - - 171 - - - HS4_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - - - True - - - NoControl - - - 499, 287 - - - 15, 14 - - - 170 - - - HS4_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 4 - - - True - - - 6, 13 - - - 654, 397 - - - currentStateBindingSource - - - System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ConfigTradHeli - - - ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + True + + + + NoControl + + + + 67, 19 + + + 39, 17 + + + 137 + + + H1 + + + H1_ENABLE + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + True + + + NoControl + + + 6, 19 + + + 55, 17 + + + 136 + + + CCPM + + + CCPM + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 1 + + + 257, 11 + + + 120, 43 + + + 169 + + + Swash Type + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + NoControl + + + 302, 83 + + + 69, 23 + + + 138 + + + Manual + + + BUT_swash_manual + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + + + $this + + + 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 + + + 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 + + + 437, 314 + + + 101, 63 + + + 168 + + + Gyro + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + NoControl + + + 483, 174 + + + 69, 23 + + + 167 + + + Manual + + + BUT_HS4save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + + + $this + + + 8 + + + True + + + NoControl + + + 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 + + + False + + + 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 + + + False + + + 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 + + + False + + + 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 + + + False + + + NoControl + + + 11, 89 + + + 58, 23 + + + 110 + + + Zero + + + BUT_0collective + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 5 + + + 297, 95 + + + 80, 209 + + + 165 + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + 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 + + + False + + + 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 + + + False + + + 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 + + + 437, 186 + + + 169, 78 + + + 166 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + 126, 314 + + + 44, 20 + + + 164 + + + HS3_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + 126, 288 + + + 44, 20 + + + 163 + + + HS2_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + 126, 262 + + + 44, 20 + + + 162 + + + HS1_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + True + + + NoControl + + + 131, 249 + + + 27, 13 + + + 161 + + + Trim + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + True + + + NoControl + + + 102, 249 + + + 27, 13 + + + 160 + + + Rev + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + True + + + NoControl + + + 54, 249 + + + 44, 13 + + + 159 + + + Position + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + True + + + NoControl + + + 17, 249 + + + 35, 13 + + + 158 + + + Servo + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + True + + + NoControl + + + 260, 365 + + + 54, 13 + + + 157 + + + Pitch Max + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 18 + + + 314, 362 + + + 47, 20 + + + 156 + + + 4500 + + + PIT_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + True + + + NoControl + + + 260, 341 + + + 48, 13 + + + 155 + + + Roll Max + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 314, 336 + + + 47, 20 + + + 154 + + + 4500 + + + ROL_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + True + + + NoControl + + + 480, 66 + + + 75, 13 + + + 153 + + + Rudder Travel + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + True + + + NoControl + + + 236, 66 + + + 72, 13 + + + 150 + + + Swash Travel + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + True + + + NoControl + + + 27, 317 + + + 13, 13 + + + 149 + + + 3 + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + True + + + NoControl + + + 27, 291 + + + 13, 13 + + + 148 + + + 2 + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 25 + + + True + + + NoControl + + + 27, 265 + + + 13, 13 + + + 147 + + + 1 + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 26 + + + 57, 314 + + + 39, 20 + + + 146 + + + 180 + + + SV3_POS + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 27 + + + 57, 288 + + + 39, 20 + + + 145 + + + 60 + + + SV2_POS + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 28 + + + 57, 262 + + + 39, 20 + + + 144 + + + -60 + + + SV1_POS + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 29 + + + True + + + NoControl + + + 105, 317 + + + 15, 14 + + + 143 + + + HS3_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 30 + + + True + + + NoControl + + + 105, 291 + + + 15, 14 + + + 142 + + + HS2_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 31 + + + True + + + NoControl + + + 105, 268 + + + 15, 14 + + + 141 + + + HS1_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 32 + + + True + + + NoControl + + + 42, 66 + + + 109, 13 + + + 140 + + + Swash-Servo position + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 33 + + + 17, 17 + + + 396, 93 + + + 242, 42 + + + 152 + + + HS4 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + + + $this + + + 34 + + + 239, 95 + + + 42, 213 + + + 151 + + + HS3 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + + + $this + + + 35 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 20, 93 + + + 0, 0, 0, 0 + + + 150, 150 + + + 139 + + + Gservoloc + + + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + + + $this + + + 36 + + + True + + + NoControl + + + 529, 268 + + + 27, 13 + + + 174 + + + Trim + + + label44 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + True + + + NoControl + + + 496, 268 + + + 27, 13 + + + 173 + + + Rev + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + NoControl + + + 448, 288 + + + 42, 13 + + + 172 + + + Rudder + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 532, 284 + + + 44, 20 + + + 171 + + + HS4_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + True + + + NoControl + + + 499, 287 + + + 15, 14 + + + 170 + + + HS4_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + True + + + 6, 13 + + + 654, 397 + + + currentStateBindingSource + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigTradHeli + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx index f96892c423..0007a20b5c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx @@ -1,496 +1,244 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 遥控输入 - - - 模式 - - - 硬件 - - - 电池 - - - AC2 直升机 - - - 上降副翼 (Elevon) 配置 - - - - 115, 17 - - - Elevons CH2 逆转 - - - 91, 17 - - - Elevons 逆转 - - - 115, 17 - - - Elevons CH1 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 50, 17 - - - 逆转 - - - 校准遥控 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 74, 17 - - - 简单模式 - - - 64, 13 - - - 当前 PWM: - - - 58, 13 - - - 当前模式: - - - 64, 13 - - - 飞行模式 6 - - - 64, 13 - - - 飞行模式 5 - - - 64, 13 - - - 飞行模式 4 - - - 64, 13 - - - 飞行模式 3 - - - 64, 13 - - - 飞行模式 2 - - - 64, 13 - - - 飞行模式 1 - - - 保存模式 - - - 十进制, 2° 3' W 就是 -2.3 - - - 启用光流 - - - 67, 13 - - - 磁偏角网站 - - - 磁偏角 - - - 启用空速计 - - - 启用声纳 - - - 启用罗盘 - - - 58, 13 - - - 输入电压: - - - 94, 13 - - - 测量的电池电压: - - - 58, 13 - - - 电池电压: - - - 52, 13 - - - 分 压 比: - - - 63, 13 - - - 安培/伏特: - - - 48, 18 - - - 传感器 - - - 电压传感器校准: -1. 测量APM输入电压,输入到下方的文本框中 -2. 测量电池电压,输入到下方的文本框中 -3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中 - - - 31, 13 - - - 容量 - - - 48, 13 - - - 监控器 - - - 175, 13 - - - 设置水平面的默认加速度计偏移 - - - 261, 13 - - - 注: 图片只是用于展示,设置可以用于六轴等机架 - - - 93, 13 - - - 机架设置 (+ 或 x) - - - 找平 - - - 手动 - - - 手动 - - - 31, 13 - - - 感度 - - - 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 - - - 最大俯仰 - - - 55, 13 - - - 最大侧倾 - - - 55, 13 - - - 舵机行程 - - - 79, 13 - - - 斜盘水平微调 - - - 79, 13 - - - 斜盘舵机位置 - - - 重置 - - - 重置 APM 为默认设置 - - - APM设置 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 斜盘类型 + + + 手动 + + + + 31, 13 + + + 最低 + + + 陀螺仪 + + + 31, 13 + + + 感度 + + + 31, 13 + + + 启用 + + + 手动 + + + 31, 13 + + + 最高 + + + 0度 + + + 31, 13 + + + 最大 + + + 31, 13 + + + 最小 + + + 31, 13 + + + 微调 + + + 31, 13 + + + 逆转 + + + 31, 13 + + + 位置 + + + 31, 13 + + + 舵机 + + + 55, 13 + + + 最大俯仰 + + + 55, 13 + + + 最大侧倾 + + + 55, 13 + + + 舵机行程 + + + 79, 13 + + + 斜盘水平微调 + + + 79, 13 + + + 斜盘舵机位置 + + + 31, 13 + + + 微调 + + + 31, 13 + + + 逆转 + + + 43, 13 + + + 方向舵 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 295cbb8ff0..9b17adaae6 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -53,6 +53,8 @@ this.tableMap = new System.Windows.Forms.TableLayoutPanel(); this.splitContainer1 = new System.Windows.Forms.SplitContainer(); this.zg1 = new ZedGraph.ZedGraphControl(); + this.lbl_hdop = new ArdupilotMega.MyLabel(); + this.lbl_sats = new ArdupilotMega.MyLabel(); this.lbl_winddir = new ArdupilotMega.MyLabel(); this.lbl_windvel = new ArdupilotMega.MyLabel(); this.gMapControl1 = new ArdupilotMega.myGMAP(); @@ -1075,6 +1077,8 @@ // // splitContainer1.Panel2 // + this.splitContainer1.Panel2.Controls.Add(this.lbl_hdop); + this.splitContainer1.Panel2.Controls.Add(this.lbl_sats); this.splitContainer1.Panel2.Controls.Add(this.lbl_winddir); this.splitContainer1.Panel2.Controls.Add(this.lbl_windvel); this.splitContainer1.Panel2.Controls.Add(this.gMapControl1); @@ -1092,6 +1096,22 @@ this.zg1.ScrollMinY2 = 0D; this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); // + // lbl_hdop + // + resources.ApplyResources(this.lbl_hdop, "lbl_hdop"); + this.lbl_hdop.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "gpshdop", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "hdop: 0")); + this.lbl_hdop.Name = "lbl_hdop"; + this.lbl_hdop.resize = true; + this.toolTip1.SetToolTip(this.lbl_hdop, resources.GetString("lbl_hdop.ToolTip")); + // + // lbl_sats + // + resources.ApplyResources(this.lbl_sats, "lbl_sats"); + this.lbl_sats.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "satcount", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Sats: 0")); + this.lbl_sats.Name = "lbl_sats"; + this.lbl_sats.resize = true; + this.toolTip1.SetToolTip(this.lbl_sats, resources.GetString("lbl_sats.ToolTip")); + // // lbl_winddir // this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0")); @@ -1348,5 +1368,7 @@ private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem; private System.Windows.Forms.SplitContainer splitContainer1; private MyButton BUT_script; + private MyLabel lbl_hdop; + private MyLabel lbl_sats; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index fcbfad4a2a..2cbf5522e0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -208,7 +208,7 @@ hud1 - hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + hud.HUD, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null SubMainLeft.Panel1 @@ -247,7 +247,7 @@ BUT_script - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -280,7 +280,7 @@ BUT_joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -310,7 +310,7 @@ BUT_quickmanual - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -340,7 +340,7 @@ BUT_quickrtl - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -370,7 +370,7 @@ BUT_quickauto - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -424,7 +424,7 @@ BUT_setwp - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -475,7 +475,7 @@ BUT_setmode - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -505,7 +505,7 @@ BUT_clear_track - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -556,7 +556,7 @@ BUT_Homealt - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -586,7 +586,7 @@ BUT_RAWSensor - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -616,7 +616,7 @@ BUTrestartmission - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -646,7 +646,7 @@ BUTactiondo - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -700,7 +700,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -730,7 +730,7 @@ Gheading - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -760,7 +760,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -793,7 +793,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -874,7 +874,7 @@ lbl_logpercent - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -925,7 +925,7 @@ BUT_log2kml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -976,7 +976,7 @@ BUT_playlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1003,7 +1003,7 @@ BUT_loadtelem - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1167,6 +1167,72 @@ 0 + + Bottom, Left + + + NoControl + + + -1, 390 + + + 43, 12 + + + 70 + + + hdop: 0 + + + gps hdop + + + lbl_hdop + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 0 + + + Bottom, Left + + + NoControl + + + -1, 408 + + + 40, 12 + + + 71 + + + Sats: 0 + + + Satalite Count + + + lbl_sats + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 1 + NoControl @@ -1189,13 +1255,13 @@ lbl_winddir - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 - 0 + 2 NoControl @@ -1219,13 +1285,13 @@ lbl_windvel - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 - 1 + 3 Fill @@ -1391,13 +1457,13 @@ gMapControl1 - ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 - 2 + 4 splitContainer1.Panel2 @@ -1454,7 +1520,7 @@ TXT_lat - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1511,7 +1577,7 @@ label1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1541,7 +1607,7 @@ TXT_long - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1571,7 +1637,7 @@ TXT_alt - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1772,7 +1838,7 @@ label6 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null $this @@ -1850,6 +1916,6 @@ FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs index a03d29139f..74d460a504 100644 --- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs +++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs @@ -2,14 +2,14 @@ - + - - + + @@ -31,224 +31,227 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + - - - - + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - + + + + + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - + + + - - - + + + - - - + + + - - - - + + + + - - - - - - + + + + + + + - - - + + + - - - - - - + + + + + + - - - + + + - - - + + + - - - + + + @@ -290,27 +293,27 @@ - - - - - - - - - - - + + + + + + + + + + - - - - - - + + + + + + + @@ -331,7 +334,7 @@ - + - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Windows Form Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - private void InitializeComponent() - { - this.components = new System.ComponentModel.Container(); - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(_3DRradio)); - this.Progressbar = new System.Windows.Forms.ProgressBar(); - this.S1 = new System.Windows.Forms.ComboBox(); - this.label1 = new System.Windows.Forms.Label(); - this.S0 = new System.Windows.Forms.TextBox(); - this.label2 = new System.Windows.Forms.Label(); - this.label3 = new System.Windows.Forms.Label(); - this.S2 = new System.Windows.Forms.ComboBox(); - this.label4 = new System.Windows.Forms.Label(); - this.S3 = new System.Windows.Forms.ComboBox(); - this.label5 = new System.Windows.Forms.Label(); - this.S4 = new System.Windows.Forms.ComboBox(); - this.label6 = new System.Windows.Forms.Label(); - this.S5 = new System.Windows.Forms.CheckBox(); - this.label7 = new System.Windows.Forms.Label(); - this.S6 = new System.Windows.Forms.CheckBox(); - this.label8 = new System.Windows.Forms.Label(); - this.S7 = new System.Windows.Forms.CheckBox(); - this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); - this.RS7 = new System.Windows.Forms.CheckBox(); - this.RS6 = new System.Windows.Forms.CheckBox(); - this.RS5 = new System.Windows.Forms.CheckBox(); - this.RS4 = new System.Windows.Forms.ComboBox(); - this.RS3 = new System.Windows.Forms.ComboBox(); - this.RS2 = new System.Windows.Forms.ComboBox(); - this.RS1 = new System.Windows.Forms.ComboBox(); - this.RSSI = new System.Windows.Forms.TextBox(); - this.RS0 = new System.Windows.Forms.TextBox(); - this.label9 = new System.Windows.Forms.Label(); - this.label10 = new System.Windows.Forms.Label(); - this.RTI = new System.Windows.Forms.TextBox(); - this.ATI = new System.Windows.Forms.TextBox(); - this.label11 = new System.Windows.Forms.Label(); - this.label12 = new System.Windows.Forms.Label(); - this.BUT_savesettings = new ArdupilotMega.MyButton(); - this.BUT_getcurrent = new ArdupilotMega.MyButton(); - this.lbl_status = new System.Windows.Forms.Label(); - this.BUT_upload = new ArdupilotMega.MyButton(); - this.BUT_syncS2 = new ArdupilotMega.MyButton(); - this.BUT_syncS3 = new ArdupilotMega.MyButton(); - this.BUT_syncS5 = new ArdupilotMega.MyButton(); - this.SuspendLayout(); - // - // Progressbar - // - this.Progressbar.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left))); - this.Progressbar.Location = new System.Drawing.Point(12, 402); - this.Progressbar.Name = "Progressbar"; - this.Progressbar.Size = new System.Drawing.Size(294, 36); - this.Progressbar.TabIndex = 2; - // - // S1 - // - this.S1.FormattingEnabled = true; - this.S1.Items.AddRange(new object[] { - "115", - "111", - "57", - "38", - "19", - "9", - "4", - "2", - "1"}); - this.S1.Location = new System.Drawing.Point(87, 141); - this.S1.Name = "S1"; - this.S1.Size = new System.Drawing.Size(80, 21); - this.S1.TabIndex = 4; - this.toolTip1.SetToolTip(this.S1, "Serial baud rate in rounded kbps. So 57 means 57600. \r\n"); - // - // label1 - // - this.label1.AutoSize = true; - this.label1.Location = new System.Drawing.Point(15, 149); - this.label1.Name = "label1"; - this.label1.Size = new System.Drawing.Size(32, 13); - this.label1.TabIndex = 5; - this.label1.Text = "Baud"; - // - // S0 - // - this.S0.Location = new System.Drawing.Point(87, 115); - this.S0.Name = "S0"; - this.S0.ReadOnly = true; - this.S0.Size = new System.Drawing.Size(80, 20); - this.S0.TabIndex = 7; - // - // label2 - // - this.label2.AutoSize = true; - this.label2.Location = new System.Drawing.Point(15, 122); - this.label2.Name = "label2"; - this.label2.Size = new System.Drawing.Size(39, 13); - this.label2.TabIndex = 8; - this.label2.Text = "Format"; - // - // label3 - // - this.label3.AutoSize = true; - this.label3.Location = new System.Drawing.Point(15, 176); - this.label3.Name = "label3"; - this.label3.Size = new System.Drawing.Size(53, 13); - this.label3.TabIndex = 10; - this.label3.Text = "Air Speed"; - // - // S2 - // - this.S2.FormattingEnabled = true; - this.S2.Items.AddRange(new object[] { - "250", - "192", - "128", - "96", - "64", - "32", - "16", - "8", - "4", - "2"}); - this.S2.Location = new System.Drawing.Point(87, 168); - this.S2.Name = "S2"; - this.S2.Size = new System.Drawing.Size(80, 21); - this.S2.TabIndex = 9; - this.toolTip1.SetToolTip(this.S2, "AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max" + - " is 192, min is 2. I would not recommend values below 16 as the frequency hoppin" + - "g and tdm sync times get too long. "); - // - // label4 - // - this.label4.AutoSize = true; - this.label4.Location = new System.Drawing.Point(15, 203); - this.label4.Name = "label4"; - this.label4.Size = new System.Drawing.Size(38, 13); - this.label4.TabIndex = 12; - this.label4.Text = "Net ID"; - // - // S3 - // - this.S3.FormattingEnabled = true; - this.S3.Items.AddRange(new object[] { - "1", - "2", - "3", - "4", - "5", - "6", - "7", - "8", - "9", - "10", - "11", - "12", - "13", - "14", - "15", - "16", - "17", - "18", - "19", - "20", - "21", - "22", - "23", - "24", - "25", - "26", - "27", - "28", - "29", - "30"}); - this.S3.Location = new System.Drawing.Point(87, 195); - this.S3.Name = "S3"; - this.S3.Size = new System.Drawing.Size(80, 21); - this.S3.TabIndex = 11; - this.toolTip1.SetToolTip(this.S3, resources.GetString("S3.ToolTip")); - // - // label5 - // - this.label5.AutoSize = true; - this.label5.Location = new System.Drawing.Point(15, 230); - this.label5.Name = "label5"; - this.label5.Size = new System.Drawing.Size(52, 13); - this.label5.TabIndex = 14; - this.label5.Text = "Tx Power"; - // - // S4 - // - this.S4.FormattingEnabled = true; - this.S4.Items.AddRange(new object[] { - "0", - "1", - "2", - "3", - "4", - "5", - "6", - "7", - "8", - "9", - "10", - "11", - "12", - "13", - "14", - "15", - "16", - "17", - "18", - "19", - "20"}); - this.S4.Location = new System.Drawing.Point(87, 222); - this.S4.Name = "S4"; - this.S4.Size = new System.Drawing.Size(80, 21); - this.S4.TabIndex = 13; - this.toolTip1.SetToolTip(this.S4, "TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to" + - " lower levels for short range testing.\r\n"); - // - // label6 - // - this.label6.AutoSize = true; - this.label6.Location = new System.Drawing.Point(15, 257); - this.label6.Name = "label6"; - this.label6.Size = new System.Drawing.Size(28, 13); - this.label6.TabIndex = 16; - this.label6.Text = "ECC"; - // - // S5 - // - this.S5.Location = new System.Drawing.Point(87, 249); - this.S5.Name = "S5"; - this.S5.Size = new System.Drawing.Size(80, 21); - this.S5.TabIndex = 15; - this.toolTip1.SetToolTip(this.S5, resources.GetString("S5.ToolTip")); - // - // label7 - // - this.label7.AutoSize = true; - this.label7.Location = new System.Drawing.Point(15, 284); - this.label7.Name = "label7"; - this.label7.Size = new System.Drawing.Size(44, 13); - this.label7.TabIndex = 18; - this.label7.Text = "Mavlink"; - // - // S6 - // - this.S6.Location = new System.Drawing.Point(87, 276); - this.S6.Name = "S6"; - this.S6.Size = new System.Drawing.Size(80, 21); - this.S6.TabIndex = 17; - this.toolTip1.SetToolTip(this.S6, resources.GetString("S6.ToolTip")); - // - // label8 - // - this.label8.AutoSize = true; - this.label8.Location = new System.Drawing.Point(15, 311); - this.label8.Name = "label8"; - this.label8.Size = new System.Drawing.Size(61, 13); - this.label8.TabIndex = 20; - this.label8.Text = "Op Resend"; - // - // S7 - // - this.S7.Location = new System.Drawing.Point(87, 303); - this.S7.Name = "S7"; - this.S7.Size = new System.Drawing.Size(80, 21); - this.S7.TabIndex = 19; - this.toolTip1.SetToolTip(this.S7, resources.GetString("S7.ToolTip")); - // - // RS7 - // - this.RS7.Location = new System.Drawing.Point(201, 303); - this.RS7.Name = "RS7"; - this.RS7.Size = new System.Drawing.Size(80, 21); - this.RS7.TabIndex = 29; - this.toolTip1.SetToolTip(this.RS7, resources.GetString("RS7.ToolTip")); - // - // RS6 - // - this.RS6.Location = new System.Drawing.Point(201, 276); - this.RS6.Name = "RS6"; - this.RS6.Size = new System.Drawing.Size(80, 21); - this.RS6.TabIndex = 28; - this.toolTip1.SetToolTip(this.RS6, resources.GetString("RS6.ToolTip")); - // - // RS5 - // - this.RS5.Location = new System.Drawing.Point(201, 249); - this.RS5.Name = "RS5"; - this.RS5.Size = new System.Drawing.Size(80, 21); - this.RS5.TabIndex = 27; - this.toolTip1.SetToolTip(this.RS5, resources.GetString("RS5.ToolTip")); - // - // RS4 - // - this.RS4.FormattingEnabled = true; - this.RS4.Items.AddRange(new object[] { - "0", - "1", - "2", - "3", - "4", - "5", - "6", - "7", - "8", - "9", - "10", - "11", - "12", - "13", - "14", - "15", - "16", - "17", - "18", - "19", - "20"}); - this.RS4.Location = new System.Drawing.Point(201, 222); - this.RS4.Name = "RS4"; - this.RS4.Size = new System.Drawing.Size(80, 21); - this.RS4.TabIndex = 26; - this.toolTip1.SetToolTip(this.RS4, "TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to" + - " lower levels for short range testing.\r\n"); - // - // RS3 - // - this.RS3.FormattingEnabled = true; - this.RS3.Items.AddRange(new object[] { - "1", - "2", - "3", - "4", - "5", - "6", - "7", - "8", - "9", - "10", - "11", - "12", - "13", - "14", - "15", - "16", - "17", - "18", - "19", - "20", - "21", - "22", - "23", - "24", - "25", - "26", - "27", - "28", - "29", - "30"}); - this.RS3.Location = new System.Drawing.Point(201, 195); - this.RS3.Name = "RS3"; - this.RS3.Size = new System.Drawing.Size(80, 21); - this.RS3.TabIndex = 25; - this.toolTip1.SetToolTip(this.RS3, resources.GetString("RS3.ToolTip")); - // - // RS2 - // - this.RS2.FormattingEnabled = true; - this.RS2.Items.AddRange(new object[] { - "250", - "192", - "128", - "96", - "64", - "32", - "16", - "8", - "4", - "2"}); - this.RS2.Location = new System.Drawing.Point(201, 168); - this.RS2.Name = "RS2"; - this.RS2.Size = new System.Drawing.Size(80, 21); - this.RS2.TabIndex = 24; - this.toolTip1.SetToolTip(this.RS2, "AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max" + - " is 192, min is 2. I would not recommend values below 16 as the frequency hoppin" + - "g and tdm sync times get too long. "); - // - // RS1 - // - this.RS1.FormattingEnabled = true; - this.RS1.Items.AddRange(new object[] { - "115", - "111", - "57", - "38", - "19", - "9", - "4", - "2", - "1"}); - this.RS1.Location = new System.Drawing.Point(201, 141); - this.RS1.Name = "RS1"; - this.RS1.Size = new System.Drawing.Size(80, 21); - this.RS1.TabIndex = 22; - this.toolTip1.SetToolTip(this.RS1, "Serial baud rate in rounded kbps. So 57 means 57600. \r\n"); - // - // RSSI - // - this.RSSI.Location = new System.Drawing.Point(87, 51); - this.RSSI.Multiline = true; - this.RSSI.Name = "RSSI"; - this.RSSI.ReadOnly = true; - this.RSSI.Size = new System.Drawing.Size(194, 58); - this.RSSI.TabIndex = 34; - this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip")); - // - // RS0 - // - this.RS0.Location = new System.Drawing.Point(201, 115); - this.RS0.Name = "RS0"; - this.RS0.ReadOnly = true; - this.RS0.Size = new System.Drawing.Size(80, 20); - this.RS0.TabIndex = 23; - // - // label9 - // - this.label9.AutoSize = true; - this.label9.Location = new System.Drawing.Point(108, 9); - this.label9.Name = "label9"; - this.label9.Size = new System.Drawing.Size(33, 13); - this.label9.TabIndex = 30; - this.label9.Text = "Local"; - // - // label10 - // - this.label10.AutoSize = true; - this.label10.Location = new System.Drawing.Point(225, 9); - this.label10.Name = "label10"; - this.label10.Size = new System.Drawing.Size(44, 13); - this.label10.TabIndex = 31; - this.label10.Text = "Remote"; - // - // RTI - // - this.RTI.Location = new System.Drawing.Point(201, 25); - this.RTI.Name = "RTI"; - this.RTI.ReadOnly = true; - this.RTI.Size = new System.Drawing.Size(80, 20); - this.RTI.TabIndex = 33; - // - // ATI - // - this.ATI.Location = new System.Drawing.Point(87, 25); - this.ATI.Name = "ATI"; - this.ATI.ReadOnly = true; - this.ATI.Size = new System.Drawing.Size(80, 20); - this.ATI.TabIndex = 32; - // - // label11 - // - this.label11.AutoSize = true; - this.label11.Location = new System.Drawing.Point(15, 32); - this.label11.Name = "label11"; - this.label11.Size = new System.Drawing.Size(42, 13); - this.label11.TabIndex = 36; - this.label11.Text = "Version"; - // - // label12 - // - this.label12.AutoSize = true; - this.label12.Location = new System.Drawing.Point(15, 58); - this.label12.Name = "label12"; - this.label12.Size = new System.Drawing.Size(32, 13); - this.label12.TabIndex = 37; - this.label12.Text = "RSSI"; - // - // BUT_savesettings - // - this.BUT_savesettings.Enabled = false; - this.BUT_savesettings.Location = new System.Drawing.Point(99, 330); - this.BUT_savesettings.Name = "BUT_savesettings"; - this.BUT_savesettings.Size = new System.Drawing.Size(75, 39); - this.BUT_savesettings.TabIndex = 21; - this.BUT_savesettings.Text = "Save Settings"; - this.BUT_savesettings.UseVisualStyleBackColor = true; - this.BUT_savesettings.Click += new System.EventHandler(this.BUT_savesettings_Click); - // - // BUT_getcurrent - // - this.BUT_getcurrent.Location = new System.Drawing.Point(18, 330); - this.BUT_getcurrent.Name = "BUT_getcurrent"; - this.BUT_getcurrent.Size = new System.Drawing.Size(75, 39); - this.BUT_getcurrent.TabIndex = 6; - this.BUT_getcurrent.Text = "Load Settings"; - this.BUT_getcurrent.UseVisualStyleBackColor = true; - this.BUT_getcurrent.Click += new System.EventHandler(this.BUT_getcurrent_Click); - // - // lbl_status - // - this.lbl_status.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left))); - this.lbl_status.BackColor = System.Drawing.Color.Transparent; - this.lbl_status.Location = new System.Drawing.Point(12, 374); - this.lbl_status.Name = "lbl_status"; - this.lbl_status.Size = new System.Drawing.Size(294, 22); - this.lbl_status.TabIndex = 3; - // - // BUT_upload - // - this.BUT_upload.Location = new System.Drawing.Point(180, 330); - this.BUT_upload.Name = "BUT_upload"; - this.BUT_upload.Size = new System.Drawing.Size(127, 39); - this.BUT_upload.TabIndex = 0; - this.BUT_upload.Text = "Upload Firmware (Local)"; - this.BUT_upload.UseVisualStyleBackColor = true; - this.BUT_upload.Click += new System.EventHandler(this.BUT_upload_Click); - // - // BUT_syncS2 - // - this.BUT_syncS2.Location = new System.Drawing.Point(173, 168); - this.BUT_syncS2.Name = "BUT_syncS2"; - this.BUT_syncS2.Size = new System.Drawing.Size(22, 23); - this.BUT_syncS2.TabIndex = 38; - this.BUT_syncS2.Text = ">"; - this.BUT_syncS2.UseVisualStyleBackColor = true; - this.BUT_syncS2.Click += new System.EventHandler(this.BUT_syncS2_Click); - // - // BUT_syncS3 - // - this.BUT_syncS3.Location = new System.Drawing.Point(173, 195); - this.BUT_syncS3.Name = "BUT_syncS3"; - this.BUT_syncS3.Size = new System.Drawing.Size(22, 23); - this.BUT_syncS3.TabIndex = 39; - this.BUT_syncS3.Text = ">"; - this.BUT_syncS3.UseVisualStyleBackColor = true; - this.BUT_syncS3.Click += new System.EventHandler(this.BUT_syncS3_Click); - // - // BUT_syncS5 - // - this.BUT_syncS5.Location = new System.Drawing.Point(173, 247); - this.BUT_syncS5.Name = "BUT_syncS5"; - this.BUT_syncS5.Size = new System.Drawing.Size(22, 23); - this.BUT_syncS5.TabIndex = 40; - this.BUT_syncS5.Text = ">"; - this.BUT_syncS5.UseVisualStyleBackColor = true; - this.BUT_syncS5.Click += new System.EventHandler(this.BUT_syncS5_Click); - // - // _3DRradio - // - this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); - this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.BUT_syncS5); - this.Controls.Add(this.BUT_syncS3); - this.Controls.Add(this.BUT_syncS2); - this.Controls.Add(this.label12); - this.Controls.Add(this.label11); - this.Controls.Add(this.RSSI); - this.Controls.Add(this.RTI); - this.Controls.Add(this.ATI); - this.Controls.Add(this.label10); - this.Controls.Add(this.label9); - this.Controls.Add(this.RS7); - this.Controls.Add(this.RS6); - this.Controls.Add(this.RS5); - this.Controls.Add(this.RS4); - this.Controls.Add(this.RS3); - this.Controls.Add(this.RS2); - this.Controls.Add(this.RS0); - this.Controls.Add(this.RS1); - this.Controls.Add(this.BUT_savesettings); - this.Controls.Add(this.label8); - this.Controls.Add(this.S7); - this.Controls.Add(this.label7); - this.Controls.Add(this.S6); - this.Controls.Add(this.label6); - this.Controls.Add(this.S5); - this.Controls.Add(this.label5); - this.Controls.Add(this.S4); - this.Controls.Add(this.label4); - this.Controls.Add(this.S3); - this.Controls.Add(this.label3); - this.Controls.Add(this.S2); - this.Controls.Add(this.label2); - this.Controls.Add(this.S0); - this.Controls.Add(this.BUT_getcurrent); - this.Controls.Add(this.label1); - this.Controls.Add(this.S1); - this.Controls.Add(this.lbl_status); - this.Controls.Add(this.Progressbar); - this.Controls.Add(this.BUT_upload); - this.MinimumSize = new System.Drawing.Size(334, 482); - this.Name = "_3DRradio"; - this.Size = new System.Drawing.Size(334, 482); - this.ResumeLayout(false); - this.PerformLayout(); - - } - - #endregion - - private MyButton BUT_upload; - private System.Windows.Forms.ProgressBar Progressbar; - private System.Windows.Forms.Label lbl_status; - private System.Windows.Forms.ComboBox S1; - private System.Windows.Forms.Label label1; - private MyButton BUT_getcurrent; - private System.Windows.Forms.TextBox S0; - private System.Windows.Forms.Label label2; - private System.Windows.Forms.Label label3; - private System.Windows.Forms.ComboBox S2; - private System.Windows.Forms.Label label4; - private System.Windows.Forms.ComboBox S3; - private System.Windows.Forms.Label label5; - private System.Windows.Forms.ComboBox S4; - private System.Windows.Forms.Label label6; - private System.Windows.Forms.CheckBox S5; - private System.Windows.Forms.Label label7; - private System.Windows.Forms.CheckBox S6; - private System.Windows.Forms.Label label8; - private System.Windows.Forms.CheckBox S7; - private MyButton BUT_savesettings; - private System.Windows.Forms.ToolTip toolTip1; - private System.Windows.Forms.CheckBox RS7; - private System.Windows.Forms.CheckBox RS6; - private System.Windows.Forms.CheckBox RS5; - private System.Windows.Forms.ComboBox RS4; - private System.Windows.Forms.ComboBox RS3; - private System.Windows.Forms.ComboBox RS2; - private System.Windows.Forms.TextBox RS0; - private System.Windows.Forms.ComboBox RS1; - private System.Windows.Forms.Label label9; - private System.Windows.Forms.Label label10; - private System.Windows.Forms.TextBox RTI; - private System.Windows.Forms.TextBox ATI; - private System.Windows.Forms.TextBox RSSI; - private System.Windows.Forms.Label label11; - private System.Windows.Forms.Label label12; - private MyButton BUT_syncS2; - private MyButton BUT_syncS3; - private MyButton BUT_syncS5; - } +namespace ArdupilotMega +{ + partial class _3DRradio + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Windows Form Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + this.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(_3DRradio)); + this.Progressbar = new System.Windows.Forms.ProgressBar(); + this.S1 = new System.Windows.Forms.ComboBox(); + this.label1 = new System.Windows.Forms.Label(); + this.S0 = new System.Windows.Forms.TextBox(); + this.label2 = new System.Windows.Forms.Label(); + this.label3 = new System.Windows.Forms.Label(); + this.S2 = new System.Windows.Forms.ComboBox(); + this.label4 = new System.Windows.Forms.Label(); + this.S3 = new System.Windows.Forms.ComboBox(); + this.label5 = new System.Windows.Forms.Label(); + this.S4 = new System.Windows.Forms.ComboBox(); + this.label6 = new System.Windows.Forms.Label(); + this.S5 = new System.Windows.Forms.CheckBox(); + this.label7 = new System.Windows.Forms.Label(); + this.S6 = new System.Windows.Forms.CheckBox(); + this.label8 = new System.Windows.Forms.Label(); + this.S7 = new System.Windows.Forms.CheckBox(); + this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); + this.RS7 = new System.Windows.Forms.CheckBox(); + this.RS6 = new System.Windows.Forms.CheckBox(); + this.RS5 = new System.Windows.Forms.CheckBox(); + this.RS4 = new System.Windows.Forms.ComboBox(); + this.RS3 = new System.Windows.Forms.ComboBox(); + this.RS2 = new System.Windows.Forms.ComboBox(); + this.RS1 = new System.Windows.Forms.ComboBox(); + this.RSSI = new System.Windows.Forms.TextBox(); + this.RS0 = new System.Windows.Forms.TextBox(); + this.label9 = new System.Windows.Forms.Label(); + this.label10 = new System.Windows.Forms.Label(); + this.RTI = new System.Windows.Forms.TextBox(); + this.ATI = new System.Windows.Forms.TextBox(); + this.label11 = new System.Windows.Forms.Label(); + this.label12 = new System.Windows.Forms.Label(); + this.BUT_savesettings = new ArdupilotMega.MyButton(); + this.BUT_getcurrent = new ArdupilotMega.MyButton(); + this.lbl_status = new System.Windows.Forms.Label(); + this.BUT_upload = new ArdupilotMega.MyButton(); + this.BUT_syncS2 = new ArdupilotMega.MyButton(); + this.BUT_syncS3 = new ArdupilotMega.MyButton(); + this.BUT_syncS5 = new ArdupilotMega.MyButton(); + this.SuspendLayout(); + // + // Progressbar + // + resources.ApplyResources(this.Progressbar, "Progressbar"); + this.Progressbar.Name = "Progressbar"; + // + // S1 + // + this.S1.FormattingEnabled = true; + this.S1.Items.AddRange(new object[] { + resources.GetString("S1.Items"), + resources.GetString("S1.Items1"), + resources.GetString("S1.Items2"), + resources.GetString("S1.Items3"), + resources.GetString("S1.Items4"), + resources.GetString("S1.Items5"), + resources.GetString("S1.Items6"), + resources.GetString("S1.Items7"), + resources.GetString("S1.Items8")}); + resources.ApplyResources(this.S1, "S1"); + this.S1.Name = "S1"; + this.toolTip1.SetToolTip(this.S1, resources.GetString("S1.ToolTip")); + // + // label1 + // + resources.ApplyResources(this.label1, "label1"); + this.label1.Name = "label1"; + // + // S0 + // + resources.ApplyResources(this.S0, "S0"); + this.S0.Name = "S0"; + this.S0.ReadOnly = true; + // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // + // label3 + // + resources.ApplyResources(this.label3, "label3"); + this.label3.Name = "label3"; + // + // S2 + // + this.S2.FormattingEnabled = true; + this.S2.Items.AddRange(new object[] { + resources.GetString("S2.Items"), + resources.GetString("S2.Items1"), + resources.GetString("S2.Items2"), + resources.GetString("S2.Items3"), + resources.GetString("S2.Items4"), + resources.GetString("S2.Items5"), + resources.GetString("S2.Items6"), + resources.GetString("S2.Items7"), + resources.GetString("S2.Items8"), + resources.GetString("S2.Items9")}); + resources.ApplyResources(this.S2, "S2"); + this.S2.Name = "S2"; + this.toolTip1.SetToolTip(this.S2, resources.GetString("S2.ToolTip")); + // + // label4 + // + resources.ApplyResources(this.label4, "label4"); + this.label4.Name = "label4"; + // + // S3 + // + this.S3.FormattingEnabled = true; + this.S3.Items.AddRange(new object[] { + resources.GetString("S3.Items"), + resources.GetString("S3.Items1"), + resources.GetString("S3.Items2"), + resources.GetString("S3.Items3"), + resources.GetString("S3.Items4"), + resources.GetString("S3.Items5"), + resources.GetString("S3.Items6"), + resources.GetString("S3.Items7"), + resources.GetString("S3.Items8"), + resources.GetString("S3.Items9"), + resources.GetString("S3.Items10"), + resources.GetString("S3.Items11"), + resources.GetString("S3.Items12"), + resources.GetString("S3.Items13"), + resources.GetString("S3.Items14"), + resources.GetString("S3.Items15"), + resources.GetString("S3.Items16"), + resources.GetString("S3.Items17"), + resources.GetString("S3.Items18"), + resources.GetString("S3.Items19"), + resources.GetString("S3.Items20"), + resources.GetString("S3.Items21"), + resources.GetString("S3.Items22"), + resources.GetString("S3.Items23"), + resources.GetString("S3.Items24"), + resources.GetString("S3.Items25"), + resources.GetString("S3.Items26"), + resources.GetString("S3.Items27"), + resources.GetString("S3.Items28"), + resources.GetString("S3.Items29")}); + resources.ApplyResources(this.S3, "S3"); + this.S3.Name = "S3"; + this.toolTip1.SetToolTip(this.S3, resources.GetString("S3.ToolTip")); + // + // label5 + // + resources.ApplyResources(this.label5, "label5"); + this.label5.Name = "label5"; + // + // S4 + // + this.S4.FormattingEnabled = true; + this.S4.Items.AddRange(new object[] { + resources.GetString("S4.Items"), + resources.GetString("S4.Items1"), + resources.GetString("S4.Items2"), + resources.GetString("S4.Items3"), + resources.GetString("S4.Items4"), + resources.GetString("S4.Items5"), + resources.GetString("S4.Items6"), + resources.GetString("S4.Items7"), + resources.GetString("S4.Items8"), + resources.GetString("S4.Items9"), + resources.GetString("S4.Items10"), + resources.GetString("S4.Items11"), + resources.GetString("S4.Items12"), + resources.GetString("S4.Items13"), + resources.GetString("S4.Items14"), + resources.GetString("S4.Items15"), + resources.GetString("S4.Items16"), + resources.GetString("S4.Items17"), + resources.GetString("S4.Items18"), + resources.GetString("S4.Items19"), + resources.GetString("S4.Items20")}); + resources.ApplyResources(this.S4, "S4"); + this.S4.Name = "S4"; + this.toolTip1.SetToolTip(this.S4, resources.GetString("S4.ToolTip")); + // + // label6 + // + resources.ApplyResources(this.label6, "label6"); + this.label6.Name = "label6"; + // + // S5 + // + resources.ApplyResources(this.S5, "S5"); + this.S5.Name = "S5"; + this.toolTip1.SetToolTip(this.S5, resources.GetString("S5.ToolTip")); + // + // label7 + // + resources.ApplyResources(this.label7, "label7"); + this.label7.Name = "label7"; + // + // S6 + // + resources.ApplyResources(this.S6, "S6"); + this.S6.Name = "S6"; + this.toolTip1.SetToolTip(this.S6, resources.GetString("S6.ToolTip")); + // + // label8 + // + resources.ApplyResources(this.label8, "label8"); + this.label8.Name = "label8"; + // + // S7 + // + resources.ApplyResources(this.S7, "S7"); + this.S7.Name = "S7"; + this.toolTip1.SetToolTip(this.S7, resources.GetString("S7.ToolTip")); + // + // RS7 + // + resources.ApplyResources(this.RS7, "RS7"); + this.RS7.Name = "RS7"; + this.toolTip1.SetToolTip(this.RS7, resources.GetString("RS7.ToolTip")); + // + // RS6 + // + resources.ApplyResources(this.RS6, "RS6"); + this.RS6.Name = "RS6"; + this.toolTip1.SetToolTip(this.RS6, resources.GetString("RS6.ToolTip")); + // + // RS5 + // + resources.ApplyResources(this.RS5, "RS5"); + this.RS5.Name = "RS5"; + this.toolTip1.SetToolTip(this.RS5, resources.GetString("RS5.ToolTip")); + // + // RS4 + // + this.RS4.FormattingEnabled = true; + this.RS4.Items.AddRange(new object[] { + resources.GetString("RS4.Items"), + resources.GetString("RS4.Items1"), + resources.GetString("RS4.Items2"), + resources.GetString("RS4.Items3"), + resources.GetString("RS4.Items4"), + resources.GetString("RS4.Items5"), + resources.GetString("RS4.Items6"), + resources.GetString("RS4.Items7"), + resources.GetString("RS4.Items8"), + resources.GetString("RS4.Items9"), + resources.GetString("RS4.Items10"), + resources.GetString("RS4.Items11"), + resources.GetString("RS4.Items12"), + resources.GetString("RS4.Items13"), + resources.GetString("RS4.Items14"), + resources.GetString("RS4.Items15"), + resources.GetString("RS4.Items16"), + resources.GetString("RS4.Items17"), + resources.GetString("RS4.Items18"), + resources.GetString("RS4.Items19"), + resources.GetString("RS4.Items20")}); + resources.ApplyResources(this.RS4, "RS4"); + this.RS4.Name = "RS4"; + this.toolTip1.SetToolTip(this.RS4, resources.GetString("RS4.ToolTip")); + // + // RS3 + // + this.RS3.FormattingEnabled = true; + this.RS3.Items.AddRange(new object[] { + resources.GetString("RS3.Items"), + resources.GetString("RS3.Items1"), + resources.GetString("RS3.Items2"), + resources.GetString("RS3.Items3"), + resources.GetString("RS3.Items4"), + resources.GetString("RS3.Items5"), + resources.GetString("RS3.Items6"), + resources.GetString("RS3.Items7"), + resources.GetString("RS3.Items8"), + resources.GetString("RS3.Items9"), + resources.GetString("RS3.Items10"), + resources.GetString("RS3.Items11"), + resources.GetString("RS3.Items12"), + resources.GetString("RS3.Items13"), + resources.GetString("RS3.Items14"), + resources.GetString("RS3.Items15"), + resources.GetString("RS3.Items16"), + resources.GetString("RS3.Items17"), + resources.GetString("RS3.Items18"), + resources.GetString("RS3.Items19"), + resources.GetString("RS3.Items20"), + resources.GetString("RS3.Items21"), + resources.GetString("RS3.Items22"), + resources.GetString("RS3.Items23"), + resources.GetString("RS3.Items24"), + resources.GetString("RS3.Items25"), + resources.GetString("RS3.Items26"), + resources.GetString("RS3.Items27"), + resources.GetString("RS3.Items28"), + resources.GetString("RS3.Items29")}); + resources.ApplyResources(this.RS3, "RS3"); + this.RS3.Name = "RS3"; + this.toolTip1.SetToolTip(this.RS3, resources.GetString("RS3.ToolTip")); + // + // RS2 + // + this.RS2.FormattingEnabled = true; + this.RS2.Items.AddRange(new object[] { + resources.GetString("RS2.Items"), + resources.GetString("RS2.Items1"), + resources.GetString("RS2.Items2"), + resources.GetString("RS2.Items3"), + resources.GetString("RS2.Items4"), + resources.GetString("RS2.Items5"), + resources.GetString("RS2.Items6"), + resources.GetString("RS2.Items7"), + resources.GetString("RS2.Items8"), + resources.GetString("RS2.Items9")}); + resources.ApplyResources(this.RS2, "RS2"); + this.RS2.Name = "RS2"; + this.toolTip1.SetToolTip(this.RS2, resources.GetString("RS2.ToolTip")); + // + // RS1 + // + this.RS1.FormattingEnabled = true; + this.RS1.Items.AddRange(new object[] { + resources.GetString("RS1.Items"), + resources.GetString("RS1.Items1"), + resources.GetString("RS1.Items2"), + resources.GetString("RS1.Items3"), + resources.GetString("RS1.Items4"), + resources.GetString("RS1.Items5"), + resources.GetString("RS1.Items6"), + resources.GetString("RS1.Items7"), + resources.GetString("RS1.Items8")}); + resources.ApplyResources(this.RS1, "RS1"); + this.RS1.Name = "RS1"; + this.toolTip1.SetToolTip(this.RS1, resources.GetString("RS1.ToolTip")); + // + // RSSI + // + resources.ApplyResources(this.RSSI, "RSSI"); + this.RSSI.Name = "RSSI"; + this.RSSI.ReadOnly = true; + this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip")); + // + // RS0 + // + resources.ApplyResources(this.RS0, "RS0"); + this.RS0.Name = "RS0"; + this.RS0.ReadOnly = true; + // + // label9 + // + resources.ApplyResources(this.label9, "label9"); + this.label9.Name = "label9"; + // + // label10 + // + resources.ApplyResources(this.label10, "label10"); + this.label10.Name = "label10"; + // + // RTI + // + resources.ApplyResources(this.RTI, "RTI"); + this.RTI.Name = "RTI"; + this.RTI.ReadOnly = true; + // + // ATI + // + resources.ApplyResources(this.ATI, "ATI"); + this.ATI.Name = "ATI"; + this.ATI.ReadOnly = true; + // + // label11 + // + resources.ApplyResources(this.label11, "label11"); + this.label11.Name = "label11"; + // + // label12 + // + resources.ApplyResources(this.label12, "label12"); + this.label12.Name = "label12"; + // + // BUT_savesettings + // + resources.ApplyResources(this.BUT_savesettings, "BUT_savesettings"); + this.BUT_savesettings.Name = "BUT_savesettings"; + this.BUT_savesettings.UseVisualStyleBackColor = true; + this.BUT_savesettings.Click += new System.EventHandler(this.BUT_savesettings_Click); + // + // BUT_getcurrent + // + resources.ApplyResources(this.BUT_getcurrent, "BUT_getcurrent"); + this.BUT_getcurrent.Name = "BUT_getcurrent"; + this.BUT_getcurrent.UseVisualStyleBackColor = true; + this.BUT_getcurrent.Click += new System.EventHandler(this.BUT_getcurrent_Click); + // + // lbl_status + // + resources.ApplyResources(this.lbl_status, "lbl_status"); + this.lbl_status.BackColor = System.Drawing.Color.Transparent; + this.lbl_status.Name = "lbl_status"; + // + // BUT_upload + // + resources.ApplyResources(this.BUT_upload, "BUT_upload"); + this.BUT_upload.Name = "BUT_upload"; + this.BUT_upload.UseVisualStyleBackColor = true; + this.BUT_upload.Click += new System.EventHandler(this.BUT_upload_Click); + // + // BUT_syncS2 + // + resources.ApplyResources(this.BUT_syncS2, "BUT_syncS2"); + this.BUT_syncS2.Name = "BUT_syncS2"; + this.BUT_syncS2.UseVisualStyleBackColor = true; + this.BUT_syncS2.Click += new System.EventHandler(this.BUT_syncS2_Click); + // + // BUT_syncS3 + // + resources.ApplyResources(this.BUT_syncS3, "BUT_syncS3"); + this.BUT_syncS3.Name = "BUT_syncS3"; + this.BUT_syncS3.UseVisualStyleBackColor = true; + this.BUT_syncS3.Click += new System.EventHandler(this.BUT_syncS3_Click); + // + // BUT_syncS5 + // + resources.ApplyResources(this.BUT_syncS5, "BUT_syncS5"); + this.BUT_syncS5.Name = "BUT_syncS5"; + this.BUT_syncS5.UseVisualStyleBackColor = true; + this.BUT_syncS5.Click += new System.EventHandler(this.BUT_syncS5_Click); + // + // _3DRradio + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.BUT_syncS5); + this.Controls.Add(this.BUT_syncS3); + this.Controls.Add(this.BUT_syncS2); + this.Controls.Add(this.label12); + this.Controls.Add(this.label11); + this.Controls.Add(this.RSSI); + this.Controls.Add(this.RTI); + this.Controls.Add(this.ATI); + this.Controls.Add(this.label10); + this.Controls.Add(this.label9); + this.Controls.Add(this.RS7); + this.Controls.Add(this.RS6); + this.Controls.Add(this.RS5); + this.Controls.Add(this.RS4); + this.Controls.Add(this.RS3); + this.Controls.Add(this.RS2); + this.Controls.Add(this.RS0); + this.Controls.Add(this.RS1); + this.Controls.Add(this.BUT_savesettings); + this.Controls.Add(this.label8); + this.Controls.Add(this.S7); + this.Controls.Add(this.label7); + this.Controls.Add(this.S6); + this.Controls.Add(this.label6); + this.Controls.Add(this.S5); + this.Controls.Add(this.label5); + this.Controls.Add(this.S4); + this.Controls.Add(this.label4); + this.Controls.Add(this.S3); + this.Controls.Add(this.label3); + this.Controls.Add(this.S2); + this.Controls.Add(this.label2); + this.Controls.Add(this.S0); + this.Controls.Add(this.BUT_getcurrent); + this.Controls.Add(this.label1); + this.Controls.Add(this.S1); + this.Controls.Add(this.lbl_status); + this.Controls.Add(this.Progressbar); + this.Controls.Add(this.BUT_upload); + this.MinimumSize = new System.Drawing.Size(334, 482); + this.Name = "_3DRradio"; + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private MyButton BUT_upload; + private System.Windows.Forms.ProgressBar Progressbar; + private System.Windows.Forms.Label lbl_status; + private System.Windows.Forms.ComboBox S1; + private System.Windows.Forms.Label label1; + private MyButton BUT_getcurrent; + private System.Windows.Forms.TextBox S0; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.ComboBox S2; + private System.Windows.Forms.Label label4; + private System.Windows.Forms.ComboBox S3; + private System.Windows.Forms.Label label5; + private System.Windows.Forms.ComboBox S4; + private System.Windows.Forms.Label label6; + private System.Windows.Forms.CheckBox S5; + private System.Windows.Forms.Label label7; + private System.Windows.Forms.CheckBox S6; + private System.Windows.Forms.Label label8; + private System.Windows.Forms.CheckBox S7; + private MyButton BUT_savesettings; + private System.Windows.Forms.ToolTip toolTip1; + private System.Windows.Forms.CheckBox RS7; + private System.Windows.Forms.CheckBox RS6; + private System.Windows.Forms.CheckBox RS5; + private System.Windows.Forms.ComboBox RS4; + private System.Windows.Forms.ComboBox RS3; + private System.Windows.Forms.ComboBox RS2; + private System.Windows.Forms.TextBox RS0; + private System.Windows.Forms.ComboBox RS1; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.TextBox RTI; + private System.Windows.Forms.TextBox ATI; + private System.Windows.Forms.TextBox RSSI; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label12; + private MyButton BUT_syncS2; + private MyButton BUT_syncS3; + private MyButton BUT_syncS5; + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx index 2e8ee646bd..0e0676fca2 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx @@ -1,166 +1,1550 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 17, 17 - - - 17, 17 - - - NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. - - - ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. - - - - MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet. - - - - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - - - - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - - - - MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet. - - - - ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. - - - - NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. - - - see the spec for a RSSI to dBm graph. The numbers at the end are: -txe: number of transmit errors (eg. transmit timeouts) -rxe: number of receive errors (crc error, framing error etc) -stx: number of serial transmit overflows -rrx: number of serial receive overflows -ecc: number of 12 bit words successfully corrected by the golay code -which result in a valid packet CRC - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + Bottom, Left + + + + 12, 402 + + + 294, 36 + + + + 2 + + + Progressbar + + + System.Windows.Forms.ProgressBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 37 + + + 115 + + + 111 + + + 57 + + + 38 + + + 19 + + + 9 + + + 4 + + + 2 + + + 1 + + + 87, 141 + + + 80, 21 + + + 4 + + + 17, 17 + + + Serial baud rate in rounded kbps. So 57 means 57600. + + + + S1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 35 + + + True + + + 15, 149 + + + 32, 13 + + + 5 + + + Baud + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 34 + + + 87, 115 + + + 80, 20 + + + 7 + + + S0 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 32 + + + True + + + 15, 122 + + + 39, 13 + + + 8 + + + Format + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 31 + + + True + + + 15, 176 + + + 53, 13 + + + 10 + + + Air Speed + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 29 + + + 250 + + + 192 + + + 128 + + + 96 + + + 64 + + + 32 + + + 16 + + + 8 + + + 4 + + + 2 + + + 87, 168 + + + 80, 21 + + + 9 + + + AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. + + + S2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 30 + + + True + + + 15, 203 + + + 38, 13 + + + 12 + + + Net ID + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 27 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 87, 195 + + + 80, 21 + + + 11 + + + NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. + + + S3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 28 + + + True + + + 15, 230 + + + 52, 13 + + + 14 + + + Tx Power + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 25 + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 87, 222 + + + 80, 21 + + + 13 + + + TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing. + + + + S4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 26 + + + True + + + 15, 257 + + + 28, 13 + + + 16 + + + ECC + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + 87, 249 + + + 80, 21 + + + 15 + + + ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. + + + + S5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + True + + + 15, 284 + + + 44, 13 + + + 18 + + + Mavlink + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + 87, 276 + + + 80, 21 + + + 17 + + + MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet. + + + + S6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + True + + + 15, 311 + + + 61, 13 + + + 20 + + + Op Resend + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + 87, 303 + + + 80, 21 + + + 19 + + + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + + + S7 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 201, 303 + + + 80, 21 + + + 29 + + + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + + + RS7 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + 201, 276 + + + 80, 21 + + + 28 + + + MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet. + + + + RS6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + 201, 249 + + + 80, 21 + + + 27 + + + ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. + + + + RS5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 201, 222 + + + 80, 21 + + + 26 + + + TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing. + + + + RS4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 201, 195 + + + 80, 21 + + + 25 + + + NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. + + + RS3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 250 + + + 192 + + + 128 + + + 96 + + + 64 + + + 32 + + + 16 + + + 8 + + + 4 + + + 2 + + + 201, 168 + + + 80, 21 + + + 24 + + + AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. + + + RS2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + 115 + + + 111 + + + 57 + + + 38 + + + 19 + + + 9 + + + 4 + + + 2 + + + 1 + + + 201, 141 + + + 80, 21 + + + 22 + + + Serial baud rate in rounded kbps. So 57 means 57600. + + + + RS1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + 87, 51 + + + True + + + 194, 58 + + + 34 + + + see the spec for a RSSI to dBm graph. The numbers at the end are: +txe: number of transmit errors (eg. transmit timeouts) +rxe: number of receive errors (crc error, framing error etc) +stx: number of serial transmit overflows +rrx: number of serial receive overflows +ecc: number of 12 bit words successfully corrected by the golay code +which result in a valid packet CRC + + + + RSSI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + 201, 115 + + + 80, 20 + + + 23 + + + RS0 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + + + True + + + 108, 9 + + + 33, 13 + + + 30 + + + Local + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + True + + + 225, 9 + + + 44, 13 + + + 31 + + + Remote + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 201, 25 + + + 80, 20 + + + 33 + + + RTI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + 87, 25 + + + 80, 20 + + + 32 + + + ATI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + True + + + 15, 32 + + + 42, 13 + + + 36 + + + Version + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + True + + + 15, 58 + + + 32, 13 + + + 37 + + + RSSI + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + False + + + 99, 330 + + + 75, 39 + + + 21 + + + Save Settings + + + BUT_savesettings + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 18 + + + 18, 330 + + + 75, 39 + + + 6 + + + Load Settings + + + BUT_getcurrent + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 33 + + + Bottom, Left + + + 12, 374 + + + 294, 22 + + + 3 + + + lbl_status + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 36 + + + 180, 330 + + + 127, 39 + + + 0 + + + Upload Firmware (Local) + + + BUT_upload + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 38 + + + 173, 168 + + + 22, 23 + + + 38 + + + > + + + BUT_syncS2 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 2 + + + 173, 195 + + + 22, 23 + + + 39 + + + > + + + BUT_syncS3 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 + + + 173, 247 + + + 22, 23 + + + 40 + + + > + + + BUT_syncS5 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + + + True + + + 6, 13 + + + 334, 482 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + _3DRradio + + + ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.zh-Hans.resx new file mode 100644 index 0000000000..c7eb3846be --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.zh-Hans.resx @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + + 49, 13 + + + 波 特 率 + + + 47, 13 + + + 格  式 + + + 47, 13 + + + 空  速 + + + 42, 13 + + + 网络ID + + + 55, 13 + + + 发射功率 + + + 31, 13 + + + 本地 + + + 31, 13 + + + 远程 + + + 47, 13 + + + 版  本 + + + 保存设置 + + + 加载设置 + + + 上传固件 (本地) + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs b/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs index 0ec56dfc8a..4467c2ac82 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs +++ b/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs @@ -34,7 +34,7 @@ namespace uploader // protocol constants PROG_MULTI_MAX = 64, // maximum number of bytes in a PROG_MULTI command - READ_MULTI_MAX = 255, // largest read that can be requested + READ_MULTI_MAX = 64, // from 255 // largest read that can be requested // device IDs XXX should come with the firmware image... DEVICE_ID_RF50 = 0x4d, @@ -389,6 +389,12 @@ namespace uploader } log ("\n", 5); + while (port.BytesToWrite > 50) + { + int fred = 1; + fred++; + Console.WriteLine("slowdown"); + } port.Write (b, 0, 1); } diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index 4c17f3f29f..9d8a0cd5e1 100644 Binary files a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb and b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt index f9ab193fe9..7fb755b96f 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt +++ b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt @@ -1 +1 @@ -1.1.4488.39145 \ No newline at end of file +1.1.4492.34709 \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs index 50c0cd1390..85248f6a7e 100644 --- a/Tools/ArdupilotMegaPlanner/georefimage.cs +++ b/Tools/ArdupilotMegaPlanner/georefimage.cs @@ -9,6 +9,8 @@ using com.drew.metadata; using log4net; using SharpKml.Base; using SharpKml.Dom; +using System.Drawing; +using System.Drawing.Imaging; namespace ArdupilotMega { @@ -28,20 +30,25 @@ namespace ArdupilotMega private MyButton BUT_estoffset; int latpos = 4, lngpos = 5, altpos = 7; + private MyButton BUT_Geotagimages; internal Georefimage() { InitializeComponent(); } - Hashtable filedatecahce = new Hashtable(); + Hashtable filedatecache = new Hashtable(); + Hashtable photocoords = new Hashtable(); + + Hashtable timecoordcache = new Hashtable(); + Hashtable imagetotime = new Hashtable(); DateTime getPhotoTime(string fn) { DateTime dtaken = DateTime.MinValue; - if (filedatecahce.ContainsKey(fn)) + if (filedatecache.ContainsKey(fn)) { - return (DateTime)filedatecahce[fn]; + return (DateTime)filedatecache[fn]; } try @@ -68,7 +75,7 @@ namespace ArdupilotMega dtaken = lcDirectory.GetDate(0x9003); log.InfoFormat("does " + lcDirectory.GetTagName(0x9003) + " " + dtaken); - filedatecahce[fn] = dtaken; + filedatecache[fn] = dtaken; break; } @@ -183,6 +190,10 @@ namespace ArdupilotMega DateTime startTime = DateTime.MinValue; + photocoords = new Hashtable(); + timecoordcache = new Hashtable(); + imagetotime = new Hashtable(); + //logFile = @"C:\Users\hog\Pictures\farm 1-10-2011\100SSCAM\2011-10-01 11-48 1.log"; List list = readLog(logFile); @@ -209,15 +220,17 @@ namespace ArdupilotMega int first = 0; int matchs = 0; - foreach (string file in files) + int lastmatchindex = 0; + + foreach (string filename in files) { - if (file.ToLower().EndsWith(".jpg")) + if (filename.ToLower().EndsWith(".jpg") && !filename.ToLower().Contains("_geotag")) { - DateTime dt = getPhotoTime(file); + DateTime photodt = getPhotoTime(filename); if (startTime == DateTime.MinValue) { - startTime = new DateTime(dt.Year, dt.Month, dt.Day, 0, 0, 0, 0, DateTimeKind.Utc).ToLocalTime(); + startTime = new DateTime(photodt.Year, photodt.Month, photodt.Day, 0, 0, 0, 0, DateTimeKind.Utc).ToLocalTime(); foreach (string[] arr in list) { @@ -233,20 +246,26 @@ namespace ArdupilotMega TXT_outputlog.AppendText("Log min " + localmin + " max " + localmax + "\r\n"); } - TXT_outputlog.AppendText("Photo " + Path.GetFileNameWithoutExtension(file) + " time " + dt + "\r\n"); + TXT_outputlog.AppendText("Photo " + Path.GetFileNameWithoutExtension(filename) + " time " + photodt + "\r\n"); + //Application.DoEvents(); + + int a = 0; foreach (string[] arr in list) { + a++; + + if (lastmatchindex > (a)) + continue; //Application.DoEvents(); - DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds); - + DateTime logdt = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds); if (first == 0) { - TXT_outputlog.AppendText("Photo " + Path.GetFileNameWithoutExtension(file) + " " + dt + " vs Log " + crap + "\r\n"); + TXT_outputlog.AppendText("Photo " + Path.GetFileNameWithoutExtension(filename) + " " + photodt + " vs Log " + logdt + "\r\n"); - TXT_outputlog.AppendText("offset should be about " + (dt - crap).TotalSeconds + "\r\n"); + TXT_outputlog.AppendText("offset should be about " + (photodt - logdt).TotalSeconds + "\r\n"); if (dooffset) return; @@ -256,30 +275,39 @@ namespace ArdupilotMega //Console.Write("ph " + dt + " log " + crap + " \r"); - sw4.WriteLine("ph " + file + " " + dt + " log " + crap); - if (dt.ToString("yyyy-MM-ddTHH:mm:ss") == crap.ToString("yyyy-MM-ddTHH:mm:ss")) + timecoordcache[(long)(logdt.AddSeconds(-offsetseconds) - DateTime.MinValue).TotalSeconds] = new double[] { + double.Parse(arr[latpos]), double.Parse(arr[lngpos]), double.Parse(arr[altpos]) + }; + + sw4.WriteLine("ph " + filename + " " + photodt + " log " + logdt); + + if (photodt.ToString("yyyy-MM-ddTHH:mm:ss") == logdt.ToString("yyyy-MM-ddTHH:mm:ss")) { - TXT_outputlog.AppendText("MATCH Photo " + Path.GetFileNameWithoutExtension(file) + " " + dt + "\r\n"); + lastmatchindex = a; + + TXT_outputlog.AppendText("MATCH Photo " + Path.GetFileNameWithoutExtension(filename) + " " + photodt + "\r\n"); matchs++; + + SharpKml.Dom.Timestamp tstamp = new SharpKml.Dom.Timestamp(); - tstamp.When = dt; + tstamp.When = photodt; kml.AddFeature( new Placemark() { Time = tstamp, - Name = Path.GetFileNameWithoutExtension(file), + Name = Path.GetFileNameWithoutExtension(filename), Geometry = new SharpKml.Dom.Point() { Coordinate = new Vector(double.Parse(arr[latpos]), double.Parse(arr[lngpos]), double.Parse(arr[altpos])) }, Description = new Description() { - Text = "
" + Text = "
" }, StyleSelector = new Style() { @@ -288,13 +316,15 @@ namespace ArdupilotMega } ); + photocoords[filename] = new double[] { double.Parse(arr[latpos]), double.Parse(arr[lngpos]), double.Parse(arr[altpos]) }; + imagetotime[filename] = (long)(logdt.AddSeconds(-offsetseconds) - DateTime.MinValue).TotalSeconds; - sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos]); - sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") + "\t" + arr[lngpos] + "\t" + arr[latpos] + "\t" + arr[altpos]); + sw2.WriteLine(Path.GetFileNameWithoutExtension(filename) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos]); + sw.WriteLine(Path.GetFileNameWithoutExtension(filename) + "\t" + logdt.ToString("yyyy:MM:dd HH:mm:ss") + "\t" + arr[lngpos] + "\t" + arr[latpos] + "\t" + arr[altpos]); sw.Flush(); sw2.Flush(); - log.InfoFormat(Path.GetFileNameWithoutExtension(file) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos] + " "); + log.InfoFormat(Path.GetFileNameWithoutExtension(filename) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos] + " "); break; } //Console.WriteLine(crap); @@ -322,42 +352,23 @@ namespace ArdupilotMega private void InitializeComponent() { this.openFileDialog1 = new System.Windows.Forms.OpenFileDialog(); - this.BUT_browselog = new ArdupilotMega.MyButton(); - this.BUT_browsedir = new ArdupilotMega.MyButton(); this.TXT_logfile = new System.Windows.Forms.TextBox(); this.TXT_jpgdir = new System.Windows.Forms.TextBox(); this.TXT_offsetseconds = new System.Windows.Forms.TextBox(); - this.BUT_doit = new ArdupilotMega.MyButton(); this.folderBrowserDialog1 = new System.Windows.Forms.FolderBrowserDialog(); this.TXT_outputlog = new System.Windows.Forms.TextBox(); this.label1 = new System.Windows.Forms.Label(); + this.BUT_Geotagimages = new ArdupilotMega.MyButton(); this.BUT_estoffset = new ArdupilotMega.MyButton(); + this.BUT_doit = new ArdupilotMega.MyButton(); + this.BUT_browsedir = new ArdupilotMega.MyButton(); + this.BUT_browselog = new ArdupilotMega.MyButton(); this.SuspendLayout(); // // openFileDialog1 // this.openFileDialog1.FileName = "openFileDialog1"; // - // BUT_browselog - // - this.BUT_browselog.Location = new System.Drawing.Point(351, 12); - this.BUT_browselog.Name = "BUT_browselog"; - this.BUT_browselog.Size = new System.Drawing.Size(75, 23); - this.BUT_browselog.TabIndex = 0; - this.BUT_browselog.Text = "Browse Log"; - this.BUT_browselog.UseVisualStyleBackColor = true; - this.BUT_browselog.Click += new System.EventHandler(this.BUT_browselog_Click); - // - // BUT_browsedir - // - this.BUT_browsedir.Location = new System.Drawing.Point(351, 41); - this.BUT_browsedir.Name = "BUT_browsedir"; - this.BUT_browsedir.Size = new System.Drawing.Size(75, 23); - this.BUT_browsedir.TabIndex = 1; - this.BUT_browsedir.Text = "Browse Directory"; - this.BUT_browsedir.UseVisualStyleBackColor = true; - this.BUT_browsedir.Click += new System.EventHandler(this.BUT_browsedir_Click); - // // TXT_logfile // this.TXT_logfile.Location = new System.Drawing.Point(28, 14); @@ -382,16 +393,6 @@ namespace ArdupilotMega this.TXT_offsetseconds.TabIndex = 4; this.TXT_offsetseconds.Text = "-86158"; // - // BUT_doit - // - this.BUT_doit.Location = new System.Drawing.Point(194, 105); - this.BUT_doit.Name = "BUT_doit"; - this.BUT_doit.Size = new System.Drawing.Size(75, 23); - this.BUT_doit.TabIndex = 5; - this.BUT_doit.Text = "Do It"; - this.BUT_doit.UseVisualStyleBackColor = true; - this.BUT_doit.Click += new System.EventHandler(this.BUT_doit_Click); - // // TXT_outputlog // this.TXT_outputlog.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom) @@ -414,6 +415,17 @@ namespace ArdupilotMega this.label1.TabIndex = 7; this.label1.Text = "Seconds offset"; // + // BUT_Geotagimages + // + this.BUT_Geotagimages.Enabled = false; + this.BUT_Geotagimages.Location = new System.Drawing.Point(366, 105); + this.BUT_Geotagimages.Name = "BUT_Geotagimages"; + this.BUT_Geotagimages.Size = new System.Drawing.Size(75, 23); + this.BUT_Geotagimages.TabIndex = 9; + this.BUT_Geotagimages.Text = "GeoTag Images"; + this.BUT_Geotagimages.UseVisualStyleBackColor = true; + this.BUT_Geotagimages.Click += new System.EventHandler(this.BUT_Geotagimages_Click); + // // BUT_estoffset // this.BUT_estoffset.Location = new System.Drawing.Point(286, 67); @@ -424,9 +436,40 @@ namespace ArdupilotMega this.BUT_estoffset.UseVisualStyleBackColor = true; this.BUT_estoffset.Click += new System.EventHandler(this.BUT_estoffset_Click); // + // BUT_doit + // + this.BUT_doit.Location = new System.Drawing.Point(285, 105); + this.BUT_doit.Name = "BUT_doit"; + this.BUT_doit.Size = new System.Drawing.Size(75, 23); + this.BUT_doit.TabIndex = 5; + this.BUT_doit.Text = "Do It"; + this.BUT_doit.UseVisualStyleBackColor = true; + this.BUT_doit.Click += new System.EventHandler(this.BUT_doit_Click); + // + // BUT_browsedir + // + this.BUT_browsedir.Location = new System.Drawing.Point(351, 41); + this.BUT_browsedir.Name = "BUT_browsedir"; + this.BUT_browsedir.Size = new System.Drawing.Size(75, 23); + this.BUT_browsedir.TabIndex = 1; + this.BUT_browsedir.Text = "Browse Directory"; + this.BUT_browsedir.UseVisualStyleBackColor = true; + this.BUT_browsedir.Click += new System.EventHandler(this.BUT_browsedir_Click); + // + // BUT_browselog + // + this.BUT_browselog.Location = new System.Drawing.Point(351, 12); + this.BUT_browselog.Name = "BUT_browselog"; + this.BUT_browselog.Size = new System.Drawing.Size(75, 23); + this.BUT_browselog.TabIndex = 0; + this.BUT_browselog.Text = "Browse Log"; + this.BUT_browselog.UseVisualStyleBackColor = true; + this.BUT_browselog.Click += new System.EventHandler(this.BUT_browselog_Click); + // // Georefimage // this.ClientSize = new System.Drawing.Size(453, 299); + this.Controls.Add(this.BUT_Geotagimages); this.Controls.Add(this.BUT_estoffset); this.Controls.Add(this.label1); this.Controls.Add(this.TXT_outputlog); @@ -480,11 +523,150 @@ namespace ArdupilotMega } catch { } BUT_doit.Enabled = true; + BUT_Geotagimages.Enabled = true; } private void BUT_estoffset_Click(object sender, EventArgs e) { dowork(TXT_logfile.Text, TXT_jpgdir.Text, 0, true); } + + private void BUT_Geotagimages_Click(object sender, EventArgs e) + { + + foreach (string file in photocoords.Keys) + { + WriteCoordinatesToImage(file, ((double[])photocoords[file])[0], ((double[])photocoords[file])[1], ((double[])photocoords[file])[2]); + } + + } + + byte[] coordtobytearray(double coordin) + { + double coord = Math.Abs(coordin); + + byte[] output = new byte[sizeof(double) * 3]; + + int d = (int)coord; + int m = (int)((coord - d) * 60); + double s = ((((coord - d) * 60) - m) * 60); + /* +21 00 00 00 01 00 00 00--> 33/1 +18 00 00 00 01 00 00 00--> 24/1 +06 02 00 00 0A 00 00 00--> 518/10 +*/ + + Array.Copy(BitConverter.GetBytes((uint)d), 0, output, 0, sizeof(uint)); + Array.Copy(BitConverter.GetBytes((uint)1), 0, output, 4, sizeof(uint)); + Array.Copy(BitConverter.GetBytes((uint)m), 0, output, 8, sizeof(uint)); + Array.Copy(BitConverter.GetBytes((uint)1), 0, output, 12, sizeof(uint)); + Array.Copy(BitConverter.GetBytes((uint)(s * 10)), 0, output, 16, sizeof(uint)); + Array.Copy(BitConverter.GetBytes((uint)10), 0, output, 20, sizeof(uint)); + + return output; + } + + void WriteCoordinatesToImage(string Filename, double dLat, double dLong, double alt) + { + using (MemoryStream ms = new MemoryStream(File.ReadAllBytes(Filename))) + { + TXT_outputlog.AppendText("GeoTagging "+Filename + "\n"); + Application.DoEvents(); + + using (Image Pic = Image.FromStream(ms)) + { + PropertyItem[] pi = Pic.PropertyItems; + + pi[0].Id = 0x0004; + pi[0].Type = 5; + pi[0].Len = sizeof(ulong) * 3; + pi[0].Value = coordtobytearray(dLong); + Pic.SetPropertyItem(pi[0]); + + pi[0].Id = 0x0002; + pi[0].Type = 5; + pi[0].Len = sizeof(ulong) * 3; + pi[0].Value = coordtobytearray(dLat); + Pic.SetPropertyItem(pi[0]); + + pi[0].Id = 0x0006; + pi[0].Type = 5; + pi[0].Len = 8; + pi[0].Value = new Rational(alt).GetBytes(); + Pic.SetPropertyItem(pi[0]); + + pi[0].Id = 1; + pi[0].Len = 2; + pi[0].Type = 2; + if (dLat < 0) + { + pi[0].Value = new byte[] { (byte)'S', 0 }; + } + else + { + pi[0].Value = new byte[] { (byte)'N', 0 }; + } + Pic.SetPropertyItem(pi[0]); + + pi[0].Id = 3; + pi[0].Len = 2; + pi[0].Type = 2; + if (dLong < 0) + { + pi[0].Value = new byte[] { (byte)'W', 0 }; + } + else + { + pi[0].Value = new byte[] { (byte)'E', 0 }; + } + Pic.SetPropertyItem(pi[0]); + + + + string outputfilename = Path.GetDirectoryName(Filename) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(Filename) + "_geotag" + Path.GetExtension(Filename); + + File.Delete(outputfilename); + + Pic.Save(outputfilename); + } + } + } + } + + public class Rational + { + uint dem = 0; + uint num = 0; + + public Rational(double input) + { + Value = input; + } + + public byte[] GetBytes() + { + byte[] answer = new byte[8]; + + Array.Copy(BitConverter.GetBytes((uint)num), 0, answer, 0, sizeof(uint)); + Array.Copy(BitConverter.GetBytes((uint)dem), 0, answer, 4, sizeof(uint)); + + return answer; + } + + public double Value { + get { + return num / dem; + } + set { + if ((value % 1.0) != 0) + { + dem = 100; num = (uint)(value * dem); + } + else + { + dem = 1; num = (uint)(value); + } + } + } } } diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index a4d60e15ae..a5cfb5e19b 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -7,4 +7,4 @@ list below Test Developer ... Chris Anderson -Phil Cole put this here after rebasing an old branch to master. +Phil Cole after following the instructions explicitly. diff --git a/cmake/ArduinoToolchain.cmake b/cmake/ArduinoToolchain.cmake new file mode 100644 index 0000000000..dfc40aa4bc --- /dev/null +++ b/cmake/ArduinoToolchain.cmake @@ -0,0 +1,11 @@ +set(CMAKE_SYSTEM_NAME Arduino) + +set(CMAKE_C_COMPILER avr-gcc) +set(CMAKE_CXX_COMPILER avr-g++) + +# Add current directory to CMake Module path automatically +if(EXISTS ${CMAKE_CURRENT_LIST_DIR}/Platform/Arduino.cmake) + set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}) +endif() + + diff --git a/cmake/Platform/Arduino.cmake b/cmake/Platform/Arduino.cmake new file mode 100644 index 0000000000..75ac68ac2e --- /dev/null +++ b/cmake/Platform/Arduino.cmake @@ -0,0 +1,1555 @@ +# - Generate firmware and libraries for Arduino Devices +# generate_arduino_firmware(TARGET_NAME) +# TARGET_NAME - Name of target +# Creates a Arduino firmware target. +# +# The target options can be configured by setting options of +# the following format: +# ${TARGET_NAME}${SUFFIX} +# The following suffixes are availabe: +# _SRCS # Sources +# _HDRS # Headers +# _SKETCHES # Arduino sketch files +# _LIBS # Libraries to linked in +# _BOARD # Board name (such as uno, mega2560, ...) +# _PORT # Serial port, for upload and serial targets [OPTIONAL] +# _AFLAGS # Override global Avrdude flags for target +# _SERIAL # Serial command for serial target [OPTIONAL] +# _NO_AUTOLIBS # Disables Arduino library detection +# Here is a short example for a target named test: +# set(test_SRCS test.cpp) +# set(test_HDRS test.h) +# set(test_BOARD uno) +# +# generate_arduino_firmware(test) +# +# +# generate_arduino_library(TARGET_NAME) +# TARGET_NAME - Name of target +# Creates a Arduino firmware target. +# +# The target options can be configured by setting options of +# the following format: +# ${TARGET_NAME}${SUFFIX} +# The following suffixes are availabe: +# +# _SRCS # Sources +# _HDRS # Headers +# _LIBS # Libraries to linked in +# _BOARD # Board name (such as uno, mega2560, ...) +# _NO_AUTOLIBS # Disables Arduino library detection +# +# Here is a short example for a target named test: +# set(test_SRCS test.cpp) +# set(test_HDRS test.h) +# set(test_BOARD uno) +# +# generate_arduino_library(test) +# +# +# +# generate_arduino_example(LIBRARY_NAME EXAMPLE_NAME BOARD_ID [PORT] [SERIAL]) +# +# BOARD_ID - Board ID +# LIBRARY_NAME - Library name +# EXAMPLE_NAME - Example name +# PORT - Serial port [optional] +# SERIAL - Serial command [optional] +# Creates a example from the specified library. +# +# +# print_board_list() +# +# Print list of detected Arduino Boards. +# +# +# +# print_programmer_list() +# +# Print list of detected Programmers. +# +# +# +# print_programmer_settings(PROGRAMMER) +# +# PROGRAMMER - programmer id +# +# Print the detected Programmer settings. +# +# +# +# print_board_settings(ARDUINO_BOARD) +# +# ARDUINO_BOARD - Board id +# +# Print the detected Arduino board settings. + + + + + + + +#=============================================================================# +# User Functions # +#=============================================================================# + +# [PUBLIC/USER] +# +# print_board_list() +# +# see documentation at top +function(PRINT_BOARD_LIST) + message(STATUS "Arduino Boards:") + print_list(ARDUINO_BOARDS) + message(STATUS "") +endfunction() + +# [PUBLIC/USER] +# +# print_programmer_list() +# +# see documentation at top +function(PRINT_PROGRAMMER_LIST) + message(STATUS "Arduino Programmers:") + print_list(ARDUINO_PROGRAMMERS) + message(STATUS "") +endfunction() + +# [PUBLIC/USER] +# +# print_programmer_settings(PROGRAMMER) +# +# see documentation at top +function(PRINT_PROGRAMMER_SETTINGS PROGRAMMER) + if(${PROGRAMMER}.SETTINGS) + message(STATUS "Programmer ${PROGRAMMER} Settings:") + print_settings(${PROGRAMMER}) + endif() +endfunction() + +# [PUBLIC/USER] +# +# print_board_settings(ARDUINO_BOARD) +# +# see documentation at top +function(PRINT_BOARD_SETTINGS ARDUINO_BOARD) + if(${ARDUINO_BOARD}.SETTINGS) + message(STATUS "Arduino ${ARDUINO_BOARD} Board:") + print_settings(${ARDUINO_BOARD}) + endif() +endfunction() + + + +# [PUBLIC/USER] +# +# generate_arduino_library(TARGET_NAME) +# +# see documentation at top +function(GENERATE_ARDUINO_LIBRARY TARGET_NAME) + load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources + _HDRS # Headers + _LIBS # Libraries to linked in + _BOARD) # Board name (such as uno, mega2560, ...) + set(INPUT_AUTOLIBS True) + if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) + set(INPUT_AUTOLIBS False) + endif() + + message(STATUS "Generating ${TARGET_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + + setup_arduino_core(CORE_LIB ${INPUT_BOARD}) + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}") + set(LIB_DEP_INCLUDES) + foreach(LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + message(STATUS "includes: ${LIB_DEP_INCLUDES}") + + if(INPUT_AUTOLIBS) + setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "${LIB_DEP_INCLUDES}" "") + endif() + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + add_library(${TARGET_NAME} ${ALL_SRCS}) + target_link_libraries(${TARGET_NAME} ${ALL_LIBS} "-lc -lm") +endfunction() + +# [PUBLIC/USER] +# +# generate_arduino_firmware(TARGET_NAME) +# +# see documentation at top +function(GENERATE_ARDUINO_FIRMWARE TARGET_NAME) + load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources + _HDRS # Headers + _LIBS # Libraries to linked in + _BOARD # Board name (such as uno, mega2560, ...) + _PORT # Serial port, for upload and serial targets + _AFLAGS # Override global Avrdude flags for target + _SKETCH # Arduino sketch + _SERIAL) # Serial command for serial target + + set(INPUT_AUTOLIBS True) + if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) + set(INPUT_AUTOLIBS False) + endif() + + if(NOT INPUT_BOARD) + message(FATAL_ERROR "Missing board ID (set ${TARGET_NAME}_BOARD)!") + endif() + + message(STATUS "Generating ${TARGET_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + + setup_arduino_core(CORE_LIB ${INPUT_BOARD}) + + if(INPUT_SKETCH) + setup_arduino_sketch(${INPUT_SKETCH} ALL_SRCS) + endif() + + if(NOT ALL_SRCS) + message(FATAL_ERROR "Missing sources (${TARGET_NAME}_SRCS or ${TARGET_NAME}_SKETCH), aborting!") + endif() + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}") + set(LIB_DEP_INCLUDES) + foreach(LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + + if(INPUT_AUTOLIBS) + setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "${LIB_DEP_INCLUDES}" "") + endif() + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + setup_arduino_target(${TARGET_NAME} ${INPUT_BOARD} "${ALL_SRCS}" "${ALL_LIBS}" "-I${INPUT_SKETCH} ${LIB_DEP_INCLUDES}" "") + + if(INPUT_PORT) + setup_arduino_upload(${INPUT_BOARD} ${TARGET_NAME} ${INPUT_PORT}) + endif() + + if(INPUT_SERIAL) + setup_serial_target(${TARGET_NAME} "${INPUT_SERIAL}") + endif() +endfunction() + +# [PUBLIC/USER] +# +# generate_arduino_example(LIBRARY_NAME EXAMPLE_NAME BOARD_ID [PORT] [SERIAL]) +# +# see documentation at top +function(GENERATE_ARDUINO_EXAMPLE LIBRARY_NAME EXAMPLE_NAME BOARD_ID) + + set(TARGET_NAME "example-${LIBRARY_NAME}-${EXAMPLE_NAME}") + + message(STATUS "Generating example ${LIBRARY_NAME}-${EXAMPLE_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS) + + set(INPUT_PORT ${ARGV3}) + set(INPUT_SERIAL ${ARGV4}) + + setup_arduino_core(CORE_LIB ${BOARD_ID}) + + setup_arduino_example("${LIBRARY_NAME}" "${EXAMPLE_NAME}" ALL_SRCS) + + if(NOT ALL_SRCS) + message(FATAL_ERROR "Missing sources for example, aborting!") + endif() + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}") + set(LIB_DEP_INCLUDES) + foreach(LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + + message(STATUS "includes: ${LIB_DEP_INCLUDES}") + setup_arduino_libraries(ALL_LIBS ${BOARD_ID} "${ALL_SRCS}" "${LIB_DEP_INCLUDES}" "") + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + setup_arduino_target(${TARGET_NAME} "${ALL_SRCS}" "${ALL_LIBS}" "${LIB_DEP_INCLUDES}" "") + + if(INPUT_PORT) + setup_arduino_upload(${BOARD_ID} ${TARGET_NAME} ${INPUT_PORT}) + endif() + + if(INPUT_SERIAL) + setup_serial_target(${TARGET_NAME} "${INPUT_SERIAL}") + endif() +endfunction() + + + + + + + + + + +#=============================================================================# +# Internal Functions # +#=============================================================================# + +# [PRIVATE/INTERNAL] +# +# load_board_settings() +# +# Load the Arduino SDK board settings from the boards.txt file. +# +function(LOAD_BOARD_SETTINGS) + load_arduino_style_settings(ARDUINO_BOARDS "${ARDUINO_BOARDS_PATH}") +endfunction() + +# [PRIVATE/INTERNAL] +# +function(LOAD_PROGRAMMERS_SETTINGS) + load_arduino_style_settings(ARDUINO_PROGRAMMERS "${ARDUINO_PROGRAMMERS_PATH}") +endfunction() + +# [PRIVATE/INTERNAL] +# +# load_generator_settings(TARGET_NAME PREFIX [SUFFIX_1 SUFFIX_2 .. SUFFIX_N]) +# +# TARGET_NAME - The base name of the user settings +# PREFIX - The prefix name used for generator settings +# SUFFIX_XX - List of suffixes to load +# +# Loads a list of user settings into the generators scope. User settings have +# the following syntax: +# +# ${BASE_NAME}${SUFFIX} +# +# The BASE_NAME is the target name and the suffix is a specific generator settings. +# +# For every user setting found a generator setting is created of the follwoing fromat: +# +# ${PREFIX}${SUFFIX} +# +# The purpose of loading the settings into the generator is to not modify user settings +# and to have a generic naming of the settings within the generator. +# +function(LOAD_GENERATOR_SETTINGS TARGET_NAME PREFIX) + foreach(GEN_SUFFIX ${ARGN}) + if(${TARGET_NAME}${GEN_SUFFIX}) + set(${PREFIX}${GEN_SUFFIX} ${${TARGET_NAME}${GEN_SUFFIX}} PARENT_SCOPE) + endif() + endforeach() +endfunction() + +# [PRIVATE/INTERNAL] +# +# get_arduino_flags(COMPILE_FLAGS LINK_FLAGS BOARD_ID) +# +# COMPILE_FLAGS_VAR -Variable holding compiler flags +# LINK_FLAGS_VAR - Variable holding linker flags +# BOARD_ID - The board id name +# +# Configures the the build settings for the specified Arduino Board. +# +function(get_arduino_flags COMPILE_FLAGS_VAR LINK_FLAGS_VAR BOARD_ID) + set(BOARD_CORE ${${BOARD_ID}.build.core}) + if(BOARD_CORE) + if(ARDUINO_SDK_VERSION MATCHES "([0-9]+)[.]([0-9]+)") + string(REPLACE "." "" ARDUINO_VERSION_DEFINE "${ARDUINO_SDK_VERSION}") # Normalize version (remove all periods) + set(ARDUINO_VERSION_DEFINE "") + if(CMAKE_MATCH_1 GREATER 0) + set(ARDUINO_VERSION_DEFINE "${CMAKE_MATCH_1}") + endif() + if(CMAKE_MATCH_2 GREATER 10) + set(ARDUINO_VERSION_DEFINE "${ARDUINO_VERSION_DEFINE}${CMAKE_MATCH_2}") + else() + set(ARDUINO_VERSION_DEFINE "${ARDUINO_VERSION_DEFINE}0${CMAKE_MATCH_2}") + endif() + else() + message("Invalid Arduino SDK Version (${ARDUINO_SDK_VERSION})") + endif() + + # output + set(COMPILE_FLAGS "-DF_CPU=${${BOARD_ID}.build.f_cpu} -DARDUINO=${ARDUINO_VERSION_DEFINE} -mmcu=${${BOARD_ID}.build.mcu} -I${ARDUINO_CORES_PATH}/${BOARD_CORE} -I${ARDUINO_LIBRARIES_PATH}") + set(LINK_FLAGS "-mmcu=${${BOARD_ID}.build.mcu}") + if(ARDUINO_SDK_VERSION VERSION_GREATER 1.0 OR ARDUINO_SDK_VERSION VERSION_EQUAL 1.0) + set(PIN_HEADER ${${BOARD_ID}.build.variant}) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -I${ARDUINO_VARIANTS_PATH}/${PIN_HEADER}") + endif() + + # output + set(${COMPILE_FLAGS_VAR} "${COMPILE_FLAGS}" PARENT_SCOPE) + set(${LINK_FLAGS_VAR} "${LINK_FLAGS}" PARENT_SCOPE) + + else() + message(FATAL_ERROR "Invalid Arduino board ID (${BOARD_ID}), aborting.") + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_core(VAR_NAME BOARD_ID) +# +# VAR_NAME - Variable name that will hold the generated library name +# BOARD_ID - Arduino board id +# +# Creates the Arduino Core library for the specified board, +# each board gets it's own version of the library. +# +function(setup_arduino_core VAR_NAME BOARD_ID) + set(CORE_LIB_NAME ${BOARD_ID}_CORE) + set(BOARD_CORE ${${BOARD_ID}.build.core}) + if(BOARD_CORE AND NOT TARGET ${CORE_LIB_NAME}) + set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) + find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) + # Debian/Ubuntu fix + list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") + add_library(${CORE_LIB_NAME} ${CORE_SRCS}) + get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID}) + set_target_properties(${CORE_LIB_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS}") + set(${VAR_NAME} ${CORE_LIB_NAME} PARENT_SCOPE) + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# find_arduino_libraries(VAR_NAME SRCS) +# +# VAR_NAME - Variable name which will hold the results +# SRCS - Sources that will be analized +# +# returns a list of paths to libraries found. +# +# Finds all Arduino type libraries included in sources. Available libraries +# are ${ARDUINO_SDK_PATH}/libraries and ${CMAKE_CURRENT_SOURCE_DIR}. +# +# A Arduino library is a folder that has the same name as the include header. +# For example, if we have a include "#include " then the following +# directory structure is considered a Arduino library: +# +# LibraryName/ +# |- LibraryName.h +# `- LibraryName.c +# +# If such a directory is found then all sources within that directory are considred +# to be part of that Arduino library. +# +function(find_arduino_libraries VAR_NAME SRCS) + set(ARDUINO_LIBS ) + foreach(SRC ${SRCS}) + file(STRINGS ${SRC} SRC_CONTENTS) + foreach(SRC_LINE ${SRC_CONTENTS}) + if("${SRC_LINE}" MATCHES "^ *#include *[<\"](.*)[>\"]") + get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries ${ARDUINO_EXTRA_LIBRARIES_PATH}) + if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) + break() + endif() + endforeach() + endif() + endforeach() + endforeach() + if(ARDUINO_LIBS) + list(REMOVE_DUPLICATES ARDUINO_LIBS) + endif() + set(${VAR_NAME} ${ARDUINO_LIBS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_library(VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) +# +# VAR_NAME - Vairable wich will hold the generated library names +# BOARD_ID - Board name +# LIB_PATH - path of the library +# COMPILE_FLAGS - compile flags +# LINK_FLAGS - link flags +# +# Creates an Arduino library, with all it's library dependencies. +# +# ${LIB_NAME}_RECURSE controls if the library will recurse +# when looking for source files. +# + +# For known libraries can list recurse here +set(Wire_RECURSE True) +set(Ethernet_RECURSE True) +set(SD_RECURSE True) +function(setup_arduino_library VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) + set(LIB_TARGETS) + + get_filename_component(LIB_NAME ${LIB_PATH} NAME) + set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) + if(NOT TARGET ${TARGET_LIB_NAME}) + string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) + + # Detect if recursion is needed + if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) + set(${LIB_SHORT_NAME}_RECURSE False) + endif() + + find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) + if(LIB_SRCS) + + message(STATUS "Generating Arduino ${LIB_NAME} library") + add_library(${TARGET_LIB_NAME} STATIC ${LIB_SRCS}) + + get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID}) + + find_arduino_libraries(LIB_DEPS "${LIB_SRCS}") + + foreach(LIB_DEP ${LIB_DEPS}) + setup_arduino_library(DEP_LIB_SRCS ${BOARD_ID} ${LIB_DEP} "${COMPILE_FLAGS}" "${LINK_FLAGS}") + list(APPEND LIB_TARGETS ${DEP_LIB_SRCS}) + endforeach() + + set_target_properties(${TARGET_LIB_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} -I${LIB_PATH} -I${LIB_PATH}/utility ${COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + + target_link_libraries(${TARGET_LIB_NAME} ${BOARD_ID}_CORE ${LIB_TARGETS}) + list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) + + endif() + else() + # Target already exists, skiping creating + list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) + endif() + if(LIB_TARGETS) + list(REMOVE_DUPLICATES LIB_TARGETS) + endif() + set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_libraries(VAR_NAME BOARD_ID SRCS COMPILE_FLAGS LINK_FLAGS) +# +# VAR_NAME - Vairable wich will hold the generated library names +# BOARD_ID - Board ID +# SRCS - source files +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Linker flags +# +# Finds and creates all dependency libraries based on sources. +# +function(setup_arduino_libraries VAR_NAME BOARD_ID SRCS COMPILE_FLAGS LINK_FLAGS) + set(LIB_TARGETS) + find_arduino_libraries(TARGET_LIBS "${SRCS}") + foreach(TARGET_LIB ${TARGET_LIBS}) + # Create static library instead of returning sources + setup_arduino_library(LIB_DEPS ${BOARD_ID} ${TARGET_LIB} "${COMPILE_FLAGS}" "${LINK_FLAGS}") + list(APPEND LIB_TARGETS ${LIB_DEPS}) + endforeach() + set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# setup_arduino_target(TARGET_NAME ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS) +# +# TARGET_NAME - Target name +# BOARD_ID - The arduino board +# ALL_SRCS - All sources +# ALL_LIBS - All libraries +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Linker flags +# +# Creates an Arduino firmware target. +# +function(setup_arduino_target TARGET_NAME BOARD_ID ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS) + + foreach(LIB_DEP ${ALL_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + + add_executable(${TARGET_NAME} ${ALL_SRCS}) + set_target_properties(${TARGET_NAME} PROPERTIES SUFFIX ".elf") + + get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID}) + + set_target_properties(${TARGET_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${COMPILE_FLAGS} ${LIB_DEP_INCLUDES}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + target_link_libraries(${TARGET_NAME} ${ALL_LIBS} "-lc -lm") + + set(TARGET_PATH ${CMAKE_CURRENT_BINARY_DIR}/${TARGET_NAME}) + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} + ARGS ${ARDUINO_OBJCOPY_EEP_FLAGS} + ${TARGET_PATH}.elf + ${TARGET_PATH}.eep + COMMENT "Generating EEP image" + VERBATIM) + + # Convert firmware image to ASCII HEX format + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} + ARGS ${ARDUINO_OBJCOPY_HEX_FLAGS} + ${TARGET_PATH}.elf + ${TARGET_PATH}.hex + COMMENT "Generating HEX image" + VERBATIM) + + # Display target size + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_COMMAND} + ARGS -DFIRMWARE_IMAGE=${TARGET_PATH}.hex + -P ${ARDUINO_SIZE_SCRIPT} + COMMENT "Calculating image size" + VERBATIM) + + # Create ${TARGET_NAME}-size target + add_custom_target(${TARGET_NAME}-size + COMMAND ${CMAKE_COMMAND} + -DFIRMWARE_IMAGE=${TARGET_PATH}.hex + -P ${ARDUINO_SIZE_SCRIPT} + DEPENDS ${TARGET_NAME} + COMMENT "Calculating ${TARGET_NAME} image size") +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_upload(BOARD_ID TARGET_NAME PORT) +# +# BOARD_ID - Arduino board id +# TARGET_NAME - Target name +# PORT - Serial port for upload +# +# Create an upload target (${TARGET_NAME}-upload) for the specified Arduino target. +# +function(setup_arduino_upload BOARD_ID TARGET_NAME PORT) +# setup_arduino_bootloader_upload() + setup_arduino_bootloader_upload(${TARGET_NAME} ${BOARD_ID} ${PORT}) + + # Add programmer support if defined + if(${TARGET_NAME}_PROGRAMMER AND ${${TARGET_NAME}_PROGRAMMER}.protocol) + setup_arduino_programmer_burn(${TARGET_NAME} ${BOARD_ID} ${${TARGET_NAME}_PROGRAMMER} ${PORT}) + setup_arduino_bootloader_burn(${TARGET_NAME} ${BOARD_ID} ${${TARGET_NAME}_PROGRAMMER} ${PORT}) + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_upload(TARGET_NAME BOARD_ID PORT) +# +# TARGET_NAME - target name +# BOARD_ID - board id +# PORT - serial port +# +# Set up target for upload firmware via the bootloader. +# +# The target for uploading the firmware is ${TARGET_NAME}-upload . +# +function(setup_arduino_bootloader_upload TARGET_NAME BOARD_ID PORT) + set(UPLOAD_TARGET ${TARGET_NAME}-upload) + set(AVRDUDE_ARGS) + + setup_arduino_bootloader_args(${BOARD_ID} ${TARGET_NAME} ${PORT} AVRDUDE_ARGS) + + if(NOT AVRDUDE_ARGS) + message("Could not generate default avrdude bootloader args, aborting!") + return() + endif() + + list(APPEND AVRDUDE_ARGS "-Uflash:w:${TARGET_NAME}.hex") + add_custom_target(${UPLOAD_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + DEPENDS ${TARGET_NAME}) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_programmer_burn(TARGET_NAME BOARD_ID PROGRAMMER) +# +# TARGET_NAME - name of target to burn +# BOARD_ID - board id +# PROGRAMMER - programmer id +# +# Sets up target for burning firmware via a programmer. +# +# The target for burning the firmware is ${TARGET_NAME}-burn . +# +function(setup_arduino_programmer_burn TARGET_NAME BOARD_ID PROGRAMMER) + set(PROGRAMMER_TARGET ${TARGET_NAME}-burn) + + set(AVRDUDE_ARGS) + + setup_arduino_programmer_args(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} AVRDUDE_ARGS) + + if(NOT AVRDUDE_ARGS) + message("Could not generate default avrdude programmer args, aborting!") + return() + endif() + + list(APPEND AVRDUDE_ARGS "-Uflash:w:${TARGET_NAME}.hex") + + add_custom_target(${PROGRAMMER_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + DEPENDS ${TARGET_NAME}) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_burn(TARGET_NAME BOARD_ID PROGRAMMER) +# +# TARGET_NAME - name of target to burn +# BOARD_ID - board id +# PROGRAMMER - programmer id +# +# Create a target for burning a bootloader via a programmer. +# +# The target for burning the bootloader is ${TARGET_NAME}-burn-bootloader +# +function(setup_arduino_bootloader_burn TARGET_NAME BOARD_ID PROGRAMMER PORT) + set(BOOTLOADER_TARGET ${TARGET_NAME}-burn-bootloader) + + set(AVRDUDE_ARGS) + + setup_arduino_programmer_args(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} AVRDUDE_ARGS) + + if(NOT AVRDUDE_ARGS) + message("Could not generate default avrdude programmer args, aborting!") + return() + endif() + + if(NOT ${BOARD_ID}.bootloader.unlock_bits) + message("Missing ${BOARD_ID}.bootloader.unlock_bits, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.high_fuses) + message("Missing ${BOARD_ID}.bootloader.high_fuses, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.low_fuses) + message("Missing ${BOARD_ID}.bootloader.low_fuses, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.path) + message("Missing ${BOARD_ID}.bootloader.path, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.file) + message("Missing ${BOARD_ID}.bootloader.file, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + + if(NOT EXISTS "${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path}/${${BOARD_ID}.bootloader.file}") + message("${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path}/${${BOARD_ID}.bootloader.file}") + message("Missing bootloader image, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + + # Erase the chip + list(APPEND AVRDUDE_ARGS "-e") + + # Set unlock bits and fuses (because chip is going to be erased) + list(APPEND AVRDUDE_ARGS "-Ulock:w:${${BOARD_ID}.bootloader.unlock_bits}:m") + if(${BOARD_ID}.bootloader.extended_fuses) + list(APPEND AVRDUDE_ARGS "-Uefuse:w:${${BOARD_ID}.bootloader.extended_fuses}:m") + endif() + list(APPEND AVRDUDE_ARGS "-Uhfuse:w:${${BOARD_ID}.bootloader.high_fuses}:m") + list(APPEND AVRDUDE_ARGS "-Ulfuse:w:${${BOARD_ID}.bootloader.low_fuses}:m") + + # Set bootloader image + list(APPEND AVRDUDE_ARGS "-Uflash:w:${${BOARD_ID}.bootloader.file}:i") + + # Set lockbits + list(APPEND AVRDUDE_ARGS "-Ulock:w:${${BOARD_ID}.bootloader.lock_bits}:m") + + # Create burn bootloader target + add_custom_target(${BOOTLOADER_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + WORKING_DIRECTORY ${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path} + DEPENDS ${TARGET_NAME}) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_programmer_args(PROGRAMMER OUTPUT_VAR) +# +# PROGRAMMER - programmer id +# TARGET_NAME - target name +# OUTPUT_VAR - name of output variable for result +# +# Sets up default avrdude settings for burning firmware via a programmer. +function(setup_arduino_programmer_args BOARD_ID PROGRAMMER TARGET_NAME PORT OUTPUT_VAR) + set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) + + set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) + if(DEFINED ${TARGET_NAME}_AFLAGS) + set(AVRDUDE_FLAGS ${${TARGET_NAME}_AFLAGS}) + endif() + + list(APPEND AVRDUDE_ARGS "-C${ARDUINO_AVRDUDE_CONFIG_PATH}") + + #TODO: Check mandatory settings before continuing + if(NOT ${PROGRAMMER}.protocol) + message(FATAL_ERROR "Missing ${PROGRAMMER}.protocol, aborting!") + endif() + + list(APPEND AVRDUDE_ARGS "-c${${PROGRAMMER}.protocol}") # Set programmer + + if(${PROGRAMMER}.communication STREQUAL "usb") + list(APPEND AVRDUDE_ARGS "-Pusb") # Set USB as port + elseif(${PROGRAMMER}.communication STREQUAL "serial") + list(APPEND AVRDUDE_ARGS "-P${PORT}") # Set port + if(${PROGRAMMER}.speed) + list(APPEND AVRDUDE_ARGS "-b${${PROGRAMMER}.speed}") # Set baud rate + endif() + endif() + + if(${PROGRAMMER}.force) + list(APPEND AVRDUDE_ARGS "-F") # Set force + endif() + + if(${PROGRAMMER}.delay) + list(APPEND AVRDUDE_ARGS "-i${${PROGRAMMER}.delay}") # Set delay + endif() + + list(APPEND AVRDUDE_ARGS "-p${${BOARD_ID}.build.mcu}") # MCU Type + + list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) + + set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_args(BOARD_ID TARGET_NAME PORT OUTPUT_VAR) +# +# BOARD_ID - board id +# TARGET_NAME - target name +# PORT - serial port +# OUTPUT_VAR - name of output variable for result +# +# Sets up default avrdude settings for uploading firmware via the bootloader. +function(setup_arduino_bootloader_args BOARD_ID TARGET_NAME PORT OUTPUT_VAR) + set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) + + set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) + if(DEFINED ${TARGET_NAME}_AFLAGS) + set(AVRDUDE_FLAGS ${${TARGET_NAME}_AFLAGS}) + endif() + + list(APPEND AVRDUDE_ARGS "-C${ARDUINO_AVRDUDE_CONFIG_PATH}") # avrdude config + + list(APPEND AVRDUDE_ARGS "-p${${BOARD_ID}.build.mcu}") # MCU Type + + # Programmer + if(${BOARD_ID}.upload.protocol STREQUAL "stk500") + list(APPEND AVRDUDE_ARGS "-cstk500v1") + else() + list(APPEND AVRDUDE_ARGS "-c${${BOARD_ID}.upload.protocol}") + endif() + + list(APPEND AVRDUDE_ARGS "-b${${BOARD_ID}.upload.speed}") # Baud rate + + list(APPEND AVRDUDE_ARGS "-P${PORT}") # Serial port + + list(APPEND AVRDUDE_ARGS "-D") # Dont erase + + list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) + + set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# find_sources(VAR_NAME LIB_PATH RECURSE) +# +# VAR_NAME - Variable name that will hold the detected sources +# LIB_PATH - The base path +# RECURSE - Whether or not to recurse +# +# Finds all C/C++ sources located at the specified path. +# +function(find_sources VAR_NAME LIB_PATH RECURSE) + set(FILE_SEARCH_LIST + ${LIB_PATH}/*.cpp + ${LIB_PATH}/*.c + ${LIB_PATH}/*.cc + ${LIB_PATH}/*.cxx + ${LIB_PATH}/*.h + ${LIB_PATH}/*.hh + ${LIB_PATH}/*.hxx) + + if(RECURSE) + file(GLOB_RECURSE LIB_FILES ${FILE_SEARCH_LIST}) + else() + file(GLOB LIB_FILES ${FILE_SEARCH_LIST}) + endif() + + if(LIB_FILES) + set(${VAR_NAME} ${LIB_FILES} PARENT_SCOPE) + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_serial_target(TARGET_NAME CMD) +# +# TARGET_NAME - Target name +# CMD - Serial terminal command +# +# Creates a target (${TARGET_NAME}-serial) for launching the serial termnial. +# +function(setup_serial_target TARGET_NAME CMD) + string(CONFIGURE "${CMD}" FULL_CMD @ONLY) + add_custom_target(${TARGET_NAME}-serial + ${FULL_CMD}) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# detect_arduino_version(VAR_NAME) +# +# VAR_NAME - Variable name where the detected version will be saved +# +# Detects the Arduino SDK Version based on the revisions.txt file. +# +function(detect_arduino_version VAR_NAME) + if(ARDUINO_VERSION_PATH) + file(READ ${ARDUINO_VERSION_PATH} ARD_VERSION) + if("${ARD_VERSION}" MATCHES " *[0]+([0-9]+)") + set(${VAR_NAME} 0.${CMAKE_MATCH_1} PARENT_SCOPE) + elseif("${ARD_VERSION}" MATCHES "[ ]*([0-9]+[.][0-9]+)") + set(${VAR_NAME} ${CMAKE_MATCH_1} PARENT_SCOPE) + endif() + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# load_arduino_style_settings(SETTINGS_LIST SETTINGS_PATH) +# +# SETTINGS_LIST - Variable name of settings list +# SETTINGS_PATH - File path of settings file to load. +# +# Load a Arduino style settings file into the cache. +# +# Examples of this type of settings file is the boards.txt and +# programmers.txt files located in ${ARDUINO_SDK}/hardware/arduino. +# +# Settings have to following format: +# +# entry.setting[.subsetting] = value +# +# where [.subsetting] is optional +# +# For example, the following settings: +# +# uno.name=Arduino Uno +# uno.upload.protocol=stk500 +# uno.upload.maximum_size=32256 +# uno.build.mcu=atmega328p +# uno.build.core=arduino +# +# will generate the follwoing equivalent CMake variables: +# +# set(uno.name "Arduino Uno") +# set(uno.upload.protocol "stk500") +# set(uno.upload.maximum_size "32256") +# set(uno.build.mcu "atmega328p") +# set(uno.build.core "arduino") +# +# set(uno.SETTINGS name upload build) # List of settings for uno +# set(uno.upload.SUBSETTINGS protocol maximum_size) # List of sub-settings for uno.upload +# set(uno.build.SUBSETTINGS mcu core) # List of sub-settings for uno.build +# +# The ${ENTRY_NAME}.SETTINGS variable lists all settings for the entry, while +# ${ENTRY_NAME}.SUBSETTINGS variables lists all settings for a sub-setting of +# a entry setting pair. +# +# These variables are generated in order to be able to programatically traverse +# all settings (for a example see print_board_settings() function). +# +function(LOAD_ARDUINO_STYLE_SETTINGS SETTINGS_LIST SETTINGS_PATH) + + if(NOT ${SETTINGS_LIST} AND EXISTS ${SETTINGS_PATH}) + file(STRINGS ${SETTINGS_PATH} FILE_ENTRIES) # Settings file split into lines + + foreach(FILE_ENTRY ${FILE_ENTRIES}) + if("${FILE_ENTRY}" MATCHES "^[^#]+=.*") + string(REGEX MATCH "^[^=]+" SETTING_NAME ${FILE_ENTRY}) + string(REGEX MATCH "[^=]+$" SETTING_VALUE ${FILE_ENTRY}) + string(REPLACE "." ";" ENTRY_NAME_TOKENS ${SETTING_NAME}) + string(STRIP "${SETTING_VALUE}" SETTING_VALUE) + + list(LENGTH ENTRY_NAME_TOKENS ENTRY_NAME_TOKENS_LEN) + + + # Add entry to settings list if it does not exist + list(GET ENTRY_NAME_TOKENS 0 ENTRY_NAME) + list(FIND ${SETTINGS_LIST} ${ENTRY_NAME} ENTRY_NAME_INDEX) + if(ENTRY_NAME_INDEX LESS 0) + # Add entry to main list + list(APPEND ${SETTINGS_LIST} ${ENTRY_NAME}) + endif() + + # Add entry setting to entry settings list if it does not exist + set(ENTRY_SETTING_LIST ${ENTRY_NAME}.SETTINGS) + list(GET ENTRY_NAME_TOKENS 1 ENTRY_SETTING) + list(FIND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING} ENTRY_SETTING_INDEX) + if(ENTRY_SETTING_INDEX LESS 0) + # Add setting to entry + list(APPEND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING}) + set(${ENTRY_SETTING_LIST} ${${ENTRY_SETTING_LIST}} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board settings list") + endif() + + set(FULL_SETTING_NAME ${ENTRY_NAME}.${ENTRY_SETTING}) + + # Add entry sub-setting to entry sub-settings list if it does not exists + if(ENTRY_NAME_TOKENS_LEN GREATER 2) + set(ENTRY_SUBSETTING_LIST ${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) + list(GET ENTRY_NAME_TOKENS 2 ENTRY_SUBSETTING) + list(FIND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING} ENTRY_SUBSETTING_INDEX) + if(ENTRY_SUBSETTING_INDEX LESS 0) + list(APPEND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING}) + set(${ENTRY_SUBSETTING_LIST} ${${ENTRY_SUBSETTING_LIST}} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board sub-settings list") + endif() + set(FULL_SETTING_NAME ${FULL_SETTING_NAME}.${ENTRY_SUBSETTING}) + endif() + + # Save setting value + set(${FULL_SETTING_NAME} ${SETTING_VALUE} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board setting") + + + endif() + endforeach() + set(${SETTINGS_LIST} ${${SETTINGS_LIST}} + CACHE STRING "List of detected Arduino Board configurations") + mark_as_advanced(${SETTINGS_LIST}) + endif() +endfunction() + +# print_settings(ENTRY_NAME) +# +# ENTRY_NAME - name of entry +# +# Print the entry settings (see load_arduino_syle_settings()). +# +function(PRINT_SETTINGS ENTRY_NAME) + if(${ENTRY_NAME}.SETTINGS) + + foreach(ENTRY_SETTING ${${ENTRY_NAME}.SETTINGS}) + if(${ENTRY_NAME}.${ENTRY_SETTING}) + message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}}") + endif() + if(${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) + foreach(ENTRY_SUBSETTING ${${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS}) + if(${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}) + message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}}") + endif() + endforeach() + endif() + message(STATUS "") + endforeach() + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# print_list(SETTINGS_LIST) +# +# SETTINGS_LIST - Variables name of settings list +# +# Print list settings and names (see load_arduino_syle_settings()). +function(PRINT_LIST SETTINGS_LIST) + if(${SETTINGS_LIST}) + set(MAX_LENGTH 0) + foreach(ENTRY_NAME ${${SETTINGS_LIST}}) + string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) + if(CURRENT_LENGTH GREATER MAX_LENGTH) + set(MAX_LENGTH ${CURRENT_LENGTH}) + endif() + endforeach() + foreach(ENTRY_NAME ${${SETTINGS_LIST}}) + string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) + math(EXPR PADDING_LENGTH "${MAX_LENGTH}-${CURRENT_LENGTH}") + set(PADDING "") + foreach(X RANGE ${PADDING_LENGTH}) + set(PADDING "${PADDING} ") + endforeach() + message(STATUS " ${PADDING}${ENTRY_NAME}: ${${ENTRY_NAME}.name}") + endforeach() + endif() +endfunction() + +function(SETUP_ARDUINO_EXAMPLE LIBRARY_NAME EXAMPLE_NAME OUTPUT_VAR) + set(EXAMPLE_SKETCH_PATH ) + + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) + if(EXISTS "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") + set(EXAMPLE_SKETCH_PATH "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") + break() + endif() + endforeach() + + if(EXAMPLE_SKETCH_PATH) + setup_arduino_sketch(${EXAMPLE_SKETCH_PATH} SKETCH_CPP) + set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else() + message(FATAL_ERROR "Could not find example ${EXAMPLE_NAME} from library ${LIBRARY_NAME}") + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_sketch(SKETCH_PATH OUTPUT_VAR) +# +# SKETCH_PATH - Path to sketch directory +# OUTPUT_VAR - Variable name where to save generated sketch source +# +# Generates C++ sources from Arduino Sketch. +function(SETUP_ARDUINO_SKETCH SKETCH_PATH OUTPUT_VAR) + get_filename_component(SKETCH_NAME "${SKETCH_PATH}" NAME) + get_filename_component(SKETCH_PATH "${SKETCH_PATH}" ABSOLUTE) + + if(EXISTS "${SKETCH_PATH}") + set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}.cpp) + set(MAIN_SKETCH ${SKETCH_PATH}/${SKETCH_NAME}) + + if(EXISTS "${MAIN_SKETCH}.pde") + set(MAIN_SKETCH "${MAIN_SKETCH}.pde") + elseif(EXISTS "${MAIN_SKETCH}.ino") + set(MAIN_SKETCH "${MAIN_SKETCH}.ino") + else() + message(FATAL_ERROR "Could not find main sketch (${SKETCH_NAME}.pde or ${SKETCH_NAME}.ino) at ${SKETCH_PATH}!") + endif() + arduino_debug("sketch: ${MAIN_SKETCH}") + + # Find all sketch files + file(GLOB SKETCH_SOURCES ${SKETCH_PATH}/*.pde ${SKETCH_PATH}/*.ino) + list(REMOVE_ITEM SKETCH_SOURCES ${MAIN_SKETCH}) + list(SORT SKETCH_SOURCES) + + generate_cpp_from_sketch("${MAIN_SKETCH}" "${SKETCH_SOURCES}" "${SKETCH_CPP}") + + # Regenerate build system if sketch changes + add_custom_command(OUTPUT ${SKETCH_CPP} + COMMAND ${CMAKE_COMMAND} ${CMAKE_SOURCE_DIR} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + DEPENDS ${MAIN_SKETCH} ${SKETCH_SOURCES} + COMMENT "Regnerating ${SKETCH_NAME} Sketch") + set_source_files_properties(${SKETCH_CPP} PROPERTIES GENERATED TRUE) + + set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else() + message(FATAL_ERROR "Sketch does not exist: ${SKETCH_PDE}") + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# generate_cpp_from_sketch(MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) +# +# MAIN_SKETCH_PATH - Main sketch file path +# SKETCH_SOURCES - Setch source paths +# SKETCH_CPP - Name of file to generate +# +# Generate C++ source file from Arduino sketch files. +function(GENERATE_CPP_FROM_SKETCH MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) + file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n") + file(READ ${MAIN_SKETCH_PATH} MAIN_SKETCH) + + # remove comments + remove_comments(MAIN_SKETCH "${MAIN_SKETCH_PATH}") + + # find first statement + string(REGEX MATCH "[\n][_a-zA-Z0-9]+[^\n]*" FIRST_STATEMENT "${MAIN_SKETCH}") + string(FIND "${MAIN_SKETCH}" "${FIRST_STATEMENT}" FIRST_STATEMENT_POSITION) + if ("${FIRST_STATEMENT_POSITION}" STREQUAL "-1") + set(FIRST_STATEMENT_POSITION 0) + endif() + #message(STATUS "FIRST STATEMENT: ${FIRST_STATEMENT}") + #message(STATUS "FIRST STATEMENT POSITION: ${FIRST_STATEMENT_POSITION}") + string(LENGTH "${MAIN_SKETCH}" MAIN_SKETCH_LENGTH) + math(EXPR LENGTH_STR1 "${MAIN_SKETCH_LENGTH}-(${FIRST_STATEMENT_POSITION})") + string(SUBSTRING "${MAIN_SKETCH}" ${FIRST_STATEMENT_POSITION} ${LENGTH_STR1} STR1) + #arduino_debug("STR1:\n${STR1}") + + string(SUBSTRING "${MAIN_SKETCH}" 0 ${FIRST_STATEMENT_POSITION} SKETCH_HEAD) + #arduino_debug("SKETCH_HEAD:\n${SKETCH_HEAD}") + + # find the body of the main pde + math(EXPR BODY_LENGTH "${MAIN_SKETCH_LENGTH}-${FIRST_STATEMENT_POSITION}-1") + string(SUBSTRING "${MAIN_SKETCH}" "${FIRST_STATEMENT_POSITION}+1" "${BODY_LENGTH}" SKETCH_BODY) + #arduino_debug("BODY:\n${SKETCH_BODY}") + + # write the file head + file(APPEND ${SKETCH_CPP} "\n${SKETCH_HEAD}\n") + if(ARDUINO_SDK_VERSION VERSION_LESS 1.0) + file(APPEND ${SKETCH_CPP} "#include \"WProgram.h\"\n") + else() + file(APPEND ${SKETCH_CPP} "#include \"Arduino.h\"\n") + endif() + file(APPEND ${SKETCH_CPP} "\n") + + # Find function prototypes + foreach(SKETCH_SOURCE_PATH ${SKETCH_SOURCES} ${MAIN_SKETCH_PATH}) + arduino_debug("Sketch: ${SKETCH_SOURCE_PATH}") + file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) + remove_comments(SKETCH_SOURCE "${SKETCH_SOURCE_PATH}") + string(REGEX MATCHALL "(^|[\n])([a-zA-Z]+[ ])*[_a-zA-Z0-9]+([ ]*[\n][\t]*|[ ])[_a-zA-Z0-9]+[ ]?[\n]?[\t]*[ ]*[(]([\t]*[ ]*[*&]?[ ]?[a-zA-Z0-9_](\\[([0-9]+)?\\])*[,]?[ ]*[\n]?)*([,]?[ ]*[\n]?[.][.][.])?[)]([ ]*[\n][\t]*|[ ]|[\n])*{" SKETCH_PROTOTYPES "${SKETCH_SOURCE}") + + # Write function prototypes + file(APPEND ${SKETCH_CPP} "\n//=== START Forward: ${SKETCH_SOURCE_PATH}\n") + foreach(SKETCH_PROTOTYPE ${SKETCH_PROTOTYPES}) + string(REPLACE "\n" " " SKETCH_PROTOTYPE "${SKETCH_PROTOTYPE}") + string(REPLACE "{" " " SKETCH_PROTOTYPE "${SKETCH_PROTOTYPE}") + arduino_debug("\tprototype: ${SKETCH_PROTOTYPE};") + file(APPEND ${SKETCH_CPP} "${SKETCH_PROTOTYPE};\n") + endforeach() + file(APPEND ${SKETCH_CPP} "//=== END Forward: ${SKETCH_SOURCE_PATH}\n") + endforeach() + + # Write Sketch CPP source + file(APPEND ${SKETCH_CPP} "\n${SKETCH_BODY}") + foreach (SKETCH_SOURCE_PATH ${SKETCH_SOURCES}) + file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) + remove_comments(SKETCH_SOURCE "${SKETCH_SOURCE_PATH}") + file(APPEND ${SKETCH_CPP} "${SKETCH_SOURCE}") + endforeach() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_size_script(OUTPUT_VAR) +# +# OUTPUT_VAR - Output variable that will contain the script path +# +# Generates script used to display the firmware size. +function(SETUP_ARDUINO_SIZE_SCRIPT OUTPUT_VAR) + set(ARDUINO_SIZE_SCRIPT_PATH ${CMAKE_BINARY_DIR}/CMakeFiles/FirmwareSize.cmake) + + file(WRITE ${ARDUINO_SIZE_SCRIPT_PATH} " + set(AVRSIZE_PROGRAM ${AVRSIZE_PROGRAM}) + set(AVRSIZE_FLAGS --target=ihex -d) + + execute_process(COMMAND \${AVRSIZE_PROGRAM} \${AVRSIZE_FLAGS} \${FIRMWARE_IMAGE} + OUTPUT_VARIABLE SIZE_OUTPUT) + + string(STRIP \"\${SIZE_OUTPUT}\" SIZE_OUTPUT) + + # Convert lines into a list + string(REPLACE \"\\n\" \";\" SIZE_OUTPUT \"\${SIZE_OUTPUT}\") + + list(GET SIZE_OUTPUT 1 SIZE_ROW) + + if(SIZE_ROW MATCHES \"[ \\t]*[0-9]+[ \\t]*[0-9]+[ \\t]*[0-9]+[ \\t]*([0-9]+)[ \\t]*([0-9a-fA-F]+).*\") + message(\"Total size \${CMAKE_MATCH_1} bytes\") + endif()") + + set(${OUTPUT_VAR} ${ARDUINO_SIZE_SCRIPT_PATH} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# arduino_debug_on() +# +# Enables Arduino module debugging. +function(ARDUINO_DEBUG_ON) + set(ARDUINO_DEBUG_ON True PARENT_SCOPE) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# arduino_debug_off() +# +# Disables Arduino module debugging. +function(ARDUINO_DEBUG_OFF) + set(ARDUINO_DEBUG_ON False PARENT_SCOPE) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# arduino_debug(MSG) +# +# MSG - Message to print +# +# Print Arduino debugging information. In order to enable printing +# use arduino_debug_on() and to disable use arduino_debug_off(). +function(ARDUINO_DEBUG MSG) + if(ARDUINO_DEBUG_ON) + message("## ${MSG}") + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# remove_comments(SRC_VAR NAME) +# +# SRC_VAR - variable holding sources +# NAME - variable for labelling output debug files +# +function(REMOVE_COMMENTS SRC_VAR NAME) + string(REGEX REPLACE "[\\./\\\\]" "_" FILE "${NAME}") + + set(SRC "${${SRC_VAR}}") + + #message(STATUS "removing comments from: ${FILE}") + #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_pre_remove_comments.txt" ${SRC}) + #message(STATUS "\n${SRC}") + + # remove all comments + string(REGEX REPLACE "([/][/][^\n]*)|([/][\\*]([^\\*]|([\\*]+[^/\\*]))*[\\*]+[/])" "" SRC "${SRC}") + + #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_post_remove_comments.txt" ${SRC}) + #message(STATUS "\n${SRC}") + + set(${SRC_VAR} "${SRC}" PARENT_SCOPE) +endfunction() + + +#=============================================================================# +# C Flags # +#=============================================================================# +set(ARDUINO_C_FLAGS "-mcall-prologues -ffunction-sections -fdata-sections") +set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_RELEASE "-Os -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_RELWITHDEBINFO "-Os -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") + +#=============================================================================# +# C++ Flags # +#=============================================================================# +set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") +set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_RELEASE "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-Os -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") + +#=============================================================================# +# Executable Linker Flags # +#=============================================================================# +set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections -lm") +set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + +#=============================================================================# +# Shared Lbrary Linker Flags # +#=============================================================================# +set(CMAKE_SHARED_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + +set(CMAKE_MODULE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + +#=============================================================================# +# System Paths # +#=============================================================================# +if(UNIX) + include(Platform/UnixPaths) + if(APPLE) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ~/Applications + /Applications + /Developer/Applications + /sw # Fink + /opt/local) # MacPorts + endif() +elseif(WIN32) + include(Platform/WindowsPaths) +endif() + +#=============================================================================# +# Arduino Settings # +#=============================================================================# +set(ARDUINO_OBJCOPY_EEP_FLAGS -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load + --no-change-warnings --change-section-lma .eeprom=0 CACHE STRING "") +set(ARDUINO_OBJCOPY_HEX_FLAGS -O ihex -R .eeprom CACHE STRING "") +set(ARDUINO_AVRDUDE_FLAGS -V CACHE STRING "") + +#=============================================================================# +# Initialization # +#=============================================================================# +if(NOT ARDUINO_FOUND) + set(ARDUINO_PATHS) + foreach(VERSION 22 1) + list(APPEND ARDUINO_PATHS arduino-00${VERSION}) + endforeach() + + file(GLOB SDK_PATH_HINTS /usr/share/arduino* + /opt/local/arduino* + /usr/local/share/arduino*) + list(SORT SDK_PATH_HINTS) + list(REVERSE SDK_PATH_HINTS) + + find_path(ARDUINO_SDK_PATH + NAMES lib/version.txt + PATH_SUFFIXES share/arduino + Arduino.app/Contents/Resources/Java/ + ${ARDUINO_PATHS} + HINTS ${SDK_PATH_HINTS} + DOC "Arduino SDK path.") + + if(ARDUINO_SDK_PATH) + if(WIN32) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/utils/bin) + elseif(APPLE) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) + endif() + else() + message(FATAL_ERROR "Could not find Arduino SDK (set ARDUINO_SDK_PATH)!") + endif() + + find_file(ARDUINO_CORES_PATH + NAMES cores + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to directory containing the Arduino core sources.") + + find_file(ARDUINO_VARIANTS_PATH + NAMES variants + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to directory containing the Arduino variant sources.") + + find_file(ARDUINO_BOOTLOADERS_PATH + NAMES bootloaders + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to directory containing the Arduino bootloader images and sources.") + + find_file(ARDUINO_LIBRARIES_PATH + NAMES libraries + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to directory containing the Arduino libraries.") + + find_file(ARDUINO_BOARDS_PATH + NAMES boards.txt + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to Arduino boards definition file.") + + find_file(ARDUINO_PROGRAMMERS_PATH + NAMES programmers.txt + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to Arduino programmers definition file.") + + find_file(ARDUINO_VERSION_PATH + NAMES lib/version.txt + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to Arduino version file.") + + find_program(ARDUINO_AVRDUDE_PROGRAM + NAMES avrdude + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/tools + NO_DEFAULT_PATH) + + find_program(ARDUINO_AVRDUDE_PROGRAM + NAMES avrdude + DOC "Path to avrdude programmer binary.") + + find_program(AVRSIZE_PROGRAM + NAMES avr-size) + + find_file(ARDUINO_AVRDUDE_CONFIG_PATH + NAMES avrdude.conf + PATHS ${ARDUINO_SDK_PATH} /etc/avrdude + PATH_SUFFIXES hardware/tools + hardware/tools/avr/etc + DOC "Path to avrdude programmer configuration file.") + + # Ensure that all required paths are found + foreach(VAR_NAME ARDUINO_CORES_PATH + ARDUINO_BOOTLOADERS_PATH + ARDUINO_LIBRARIES_PATH + ARDUINO_BOARDS_PATH + ARDUINO_PROGRAMMERS_PATH + ARDUINO_VERSION_PATH + ARDUINO_AVRDUDE_FLAGS + ARDUINO_AVRDUDE_PROGRAM + ARDUINO_AVRDUDE_CONFIG_PATH + AVRSIZE_PROGRAM) + if(NOT ${VAR_NAME}) + message(FATAL_ERROR "\nMissing ${VAR_NAME}!\nInvalid Arduino SDK path (${ARDUINO_SDK_PATH}).\n") + endif() + endforeach() + + + detect_arduino_version(ARDUINO_SDK_VERSION) + set(ARDUINO_SDK_VERSION ${ARDUINO_SDK_VERSION} CACHE STRING "Arduino SDK Version") + + + if(ARDUINO_SDK_VERSION VERSION_LESS 0.19) + message(FATAL_ERROR "Unsupported Arduino SDK (require verion 0.19 or higher)") + endif() + + message(STATUS "Arduino SDK version ${ARDUINO_SDK_VERSION}: ${ARDUINO_SDK_PATH}") + + + setup_arduino_size_script(ARDUINO_SIZE_SCRIPT) + set(ARDUINO_SIZE_SCRIPT ${ARDUINO_SIZE_SCRIPT} CACHE INTERNAL "Arduino Size Script") + + load_board_settings() + load_programmers_settings() + + print_board_list() + print_programmer_list() + + + + set(ARDUINO_FOUND True CACHE INTERNAL "Arduino Found") + mark_as_advanced(ARDUINO_CORES_PATH + ARDUINO_VARIANTS_PATH + ARDUINO_BOOTLOADERS_PATH + ARDUINO_LIBRARIES_PATH + ARDUINO_BOARDS_PATH + ARDUINO_PROGRAMMERS_PATH + ARDUINO_VERSION_PATH + ARDUINO_AVRDUDE_FLAGS + ARDUINO_AVRDUDE_PROGRAM + ARDUINO_AVRDUDE_CONFIG_PATH + ARDUINO_OBJCOPY_EEP_FLAGS + ARDUINO_OBJCOPY_HEX_FLAGS + AVRSIZE_PROGRAM) + +endif() + + diff --git a/cmake/modules/APMCPackConfig.cmake b/cmake/modules/APMCPackConfig.cmake new file mode 100644 index 0000000000..1e2a08e49b --- /dev/null +++ b/cmake/modules/APMCPackConfig.cmake @@ -0,0 +1,20 @@ +# packaging settings +set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "${PROJECT_DESCRIPTION}") +set(CPACK_PACKAGE_VENDOR "DIYDRONES") +set(CPACK_DEBIAN_PACKAGE_MAINTAINER "james.goppert@gmail.com") +set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com") +set(CPACK_PACKAGE_DESCRIPTION_FILE "${CMAKE_SOURCE_DIR}/../README.txt") +set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_SOURCE_DIR}/../COPYING.txt") +set(CPACK_RESOURCE_FILE_README "${CMAKE_SOURCE_DIR}/../README.txt") +set(CPACK_PACKAGE_VERSION_MAJOR "${PROJECT_VERSION_MAJOR}") +set(CPACK_PACKAGE_VERSION_MINOR "${PROJECT_VERSION_MINOR}") +set(CPACK_PACKAGE_VERSION_PATCH "${PROJECT_VERSION_PATCH}") +set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}") +set(CPACK_SET_DESTDIR TRUE) +set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES} + /.git/;/build/;~$;.*\\\\.bin$;.*\\\\.swp$) +set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") +set(CPACK_SOURCE_GENERATOR "ZIP") +set(CPACK_GENERATOR "ZIP") +set(CPACK_PACKAGE_NAME "${FIRMWARE_NAME}") +include(CPack) diff --git a/cmake/modules/APMOption.cmake b/cmake/modules/APMOption.cmake new file mode 100644 index 0000000000..6114ff44aa --- /dev/null +++ b/cmake/modules/APMOption.cmake @@ -0,0 +1,126 @@ +# apm_option: options parsing for ardupilotmega +# +# OPTIONS: +# ADVANCED - indicates this option is advaned (hidden in gui unless advanced selected) +# DEFINE_ONLY - this flag is either indicates that the variable is defined if true, and not defined if false +# BUILD_FLAG - this flag forces the variable to be added to build flags, for files that +# don't include the config header +# +# SINGLE INPUT ARGUMENTS: (can only pass one arguments) +# TYPE - the type of the argument (BOOL for on/off variables/ STRING for all others) +# DESCRIPTION - description of option, shown as tool-tip and written in config file +# DEFAULT - the default value of the option +# +# MULTIPLE VARIABLE ARGUMENTS: (can pass a lit of items) +# OPTIONS - values that this option may take, if only a finite set is possible, creates combo-box in gui +# DEPENDS - a list of booleans that this argument depends on, can be used to disable options when the +# are not appropriate +# +# Author: James Goppert +# +function(apm_option NAME) + cmake_parse_arguments(ARG + "ADVANCED;DEFINE_ONLY;BUILD_FLAG" + "TYPE;DESCRIPTION;DEFAULT" "OPTIONS;DEPENDS" ${ARGN}) + + #message(STATUS "parsing argument: ${NAME}") + + # if option dependencies not met, hide the option + foreach(DEPEND ${ARG_DEPENDS}) + if (NOT ${${DEPEND}}) + #message(STATUS "\tfailed dep: ${DEPEND}") + set(ARG_TYPE "INTERNAL") + set("${NAME}" "${ARG_DEFAULT}" CACHE INTERNAL "${ARG_DESCRIPTION}" FORCE) + return() + endif() + endforeach() + + # set variable + set("${NAME}" "${ARG_DEFAULT}" CACHE "${ARG_TYPE}" "${ARG_DESCRIPTION}") + + # force variable reinit if it was internal (hidden) + get_property(VAR_TYPE CACHE ${NAME} PROPERTY TYPE) + if ("${VAR_TYPE}" STREQUAL "INTERNAL") + #message(STATUS "\tVAR_TYPE: ${VAR_TYPE}") + set("${NAME}" "${ARG_DEFAULT}" CACHE "${ARG_TYPE}" "${ARG_DESCRIPTION}" FORCE) + + # if a build flag, initialize it and add it to the global options list + elseif(${ARG_BUILD_FLAG}) + #message(STATUS "build flag found for item ${NAME}") + set(APM_BUILD_FLAGS_LIST ${APM_BUILD_FLAGS_LIST} ${NAME} CACHE INTERNAL "list of all build flags") + list(REMOVE_DUPLICATES APM_BUILD_FLAGS_LIST) + + # if not hidden, and not a build flag, add it to the global options list + else() + set(APM_OPTIONS_LIST ${APM_OPTIONS_LIST} ${NAME} CACHE INTERNAL "list of all options") + list(REMOVE_DUPLICATES APM_OPTIONS_LIST) + + endif() + + # set list of options + if (NOT "${ARG_OPTIONS}" STREQUAL "") + set_property(CACHE "${NAME}" PROPERTY STRINGS ${ARG_OPTIONS}) + list(FIND ARG_OPTIONS "${ARG_DEFAULT}" ARG_POSITION) + if (ARG_POSITION EQUAL -1) + message(FATAL_ERROR "default value: ${ARG_DEFAULT} not in given set of options: ${ARG_OPTIONS}") + endif() + endif() + + # mark as advanced if advanced option given + if(ARG_ADVANCED) + mark_as_advanced(FORCE "${NAME}") + endif() + + if(ARG_DEFINE_ONLY) + set("${NAME}_DEFINE_ONLY" TRUE CACHE INTERNAL "Define only?" FORCE) + else() + set("${NAME}_DEFINE_ONLY" FALSE CACHE INTERNAL "Define only?" FORCE) + endif() + +endfunction() + +# apm_option_generate_config: generates a config file using the list of options. +# +# SINGLE INPUT ARGUMENTS: (can only pass one arguments) +# FILE - the file to write the config to +# BUILD_FLAGS - variable to store build flags in +# +# Author: James Goppert +# +function(apm_option_generate_config) + cmake_parse_arguments(ARG "" "FILE;BUILD_FLAGS" "" ${ARGN}) + + # options + list(REMOVE_DUPLICATES APM_OPTIONS_LIST) + file (WRITE "${CMAKE_BINARY_DIR}/${ARG_FILE}" "//automatically generated, do not edit\n") + file (APPEND "${CMAKE_BINARY_DIR}/${ARG_FILE}" "#define OFF 0\n#define ON 1\n") + foreach(ITEM ${APM_OPTIONS_LIST}) + #message(STATUS "option: ${ITEM}") + get_property(ITEM_VALUE CACHE ${ITEM} PROPERTY VALUE) + get_property(ITEM_HELP CACHE ${ITEM} PROPERTY HELPSTRING) + if (${${ITEM}_DEFINE_ONLY}) + if (${ITEM_VALUE}) + file(APPEND "${CMAKE_BINARY_DIR}/${ARG_FILE}" "\n#define ${ITEM} // ${ITEM_HELP}") + else() + file(APPEND "${CMAKE_BINARY_DIR}/${ARG_FILE}" "\n//#define ${ITEM} // ${ITEM_HELP}") + endif() + else() + file(APPEND "${CMAKE_BINARY_DIR}/${ARG_FILE}" "\n#define ${ITEM} ${ITEM_VALUE} // ${ITEM_HELP}") + endif() + endforeach() + + # build flags + list(REMOVE_DUPLICATES APM_BUILD_FLAGS_LIST) + foreach(ITEM ${APM_BUILD_FLAGS_LIST}) + #message(STATUS "build flags: ${ITEM}") + get_property(ITEM_VALUE CACHE ${ITEM} PROPERTY VALUE) + if (${${ITEM}_DEFINE_ONLY}) + if (${ITEM_VALUE}) + set(${ARG_BUILD_FLAGS} ${${ARG_BUILD_FLAGS}} "-D${ITEM}" CACHE INTERNAL "build flags") + endif() + else() + set(${ARG_BUILD_FLAGS} ${${ARG_BUILD_FLAGS}} "-D${ITEM}=${ITEM_VALUE}" CACHE INTERNAL "build flags") + endif() + endforeach() + +endfunction() diff --git a/cmake/modules/ArduinoProcessing.cmake b/cmake/modules/ArduinoProcessing.cmake deleted file mode 100644 index c7a2407a2a..0000000000 --- a/cmake/modules/ArduinoProcessing.cmake +++ /dev/null @@ -1,103 +0,0 @@ -# 1. Concatenate all PDE files -# 2. Write #include "WProgram.h" -# 3. Write prototypes -# 4. Write original sources -# -# -# Prefix Writer -# 1. Scrub comments -# 2. Optionally subsitute Unicode -# 3. Find imports -# 4. Find prototypes -# -# Find prototypes -# 1. Strip comments, quotes, preprocessor directives -# 2. Collapse braches -# 3. Regex - - -set(SINGLE_QUOTES_REGEX "('.')") -set(DOUBLE_QUOTES_REGEX "(\"([^\"\\\\]|\\\\.)*\")") -set(SINGLE_COMMENT_REGEX "([ ]*//[^\n]*)") -set(MULTI_COMMENT_REGEX "(/[*][^/]*[*]/)") -set(PREPROC_REGEX "([ ]*#(\\\\[\n]|[^\n])*)") - -#"[\w\[\]\*]+\s+[&\[\]\*\w\s]+\([&,\[\]\*\w\s]*\)(?=\s*\{)" -set(PROTOTPYE_REGEX "([a-zA-Z0-9]+[ ]*)*[a-zA-Z0-9]+[ ]*\([^{]*\)[ ]*{") - -function(READ_SKETCHES VAR_NAME ) - set(SKETCH_SOURCE) - foreach(SKETCH ${ARGN}) - if(EXISTS ${SKETCH}) - message(STATUS "${SKETCH}") - file(READ ${SKETCH} SKETCH_CONTENTS) - set(SKETCH_SOURCE "${SKETCH_SOURCE}\n${SKETCH_CONTENTS}") - else() - message(FATAL_ERROR "Sketch file does not exist: ${SKETCH}") - endif() - endforeach() - set(${VAR_NAME} "${SKETCH_SOURCE}" PARENT_SCOPE) -endfunction() - -function(STRIP_SOURCES VAR_NAME SOURCES) - string(REGEX REPLACE "${SINGLE_QUOTES_REGEX}|${DOUBLE_QUOTES_REGEX}|${SINGLE_COMMENT_REGEX}|${MULTI_COMMENT_REGEX}|${PREPROC_REGEX}" - "" - SOURCES - "${SOURCES}") - set(${VAR_NAME} "${SOURCES}" PARENT_SCOPE) -endfunction() - -function(COLLAPSE_BRACES VAR_NAME SOURCES) - set(PARSED_SOURCES) - string(LENGTH "${SOURCES}" SOURCES_LENGTH) - math(EXPR SOURCES_LENGTH "${SOURCES_LENGTH}-1") - - set(NESTING 0) - set(START 0) - foreach(INDEX RANGE ${SOURCES_LENGTH}) - string(SUBSTRING "${SOURCES}" ${INDEX} 1 CURRENT_CHAR) - #message("${CURRENT_CHAR}") - if(CURRENT_CHAR STREQUAL "{") - if(NESTING EQUAL 0) - math(EXPR SUBLENGTH "${INDEX}-${START} +1") - string(SUBSTRING "${SOURCES}" ${START} ${SUBLENGTH} CURRENT_CHUNK) - set(PARSED_SOURCES "${PARSED_SOURCES}${CURRENT_CHUNK}") - #message("INDEX: ${INDEX} START: ${START} LENGTH: ${SUBLENGTH}") - endif() - math(EXPR NESTING "${NESTING}+1") - elseif(CURRENT_CHAR STREQUAL "}") - math(EXPR NESTING "${NESTING}-1") - if(NESTING EQUAL 0) - set(START ${INDEX}) - endif() - endif() - endforeach() - - math(EXPR SUBLENGTH "${SOURCES_LENGTH}-${START} +1") - string(SUBSTRING "${SOURCES}" ${START} ${SUBLENGTH} CURRENT_CHUNK) - set(PARSED_SOURCES "${PARSED_SOURCES}${CURRENT_CHUNK}") - - set(${VAR_NAME} "${PARSED_SOURCES}" PARENT_SCOPE) -endfunction() - -function(extract_prototypes VAR_NAME SOURCES) - string(REGEX MATCHALL "${PROTOTPYE_REGEX}" - SOURCES - "${SOURCES}") - set(${VAR_NAME} "${SOURCES}" PARENT_SCOPE) -endfunction() - -read_sketches(SKETCH_SOURCE ${FILES}) -strip_sources(SKETCH_SOURCE "${SKETCH_SOURCE}") -collapse_braces(SKETCH_SOURCE "${SKETCH_SOURCE}") -extract_prototypes(SKETCH_SOURCE "${SKETCH_SOURCE}") - - - - -message("===============") -foreach(ENTRY ${SKETCH_SOURCE}) - message("START]]]${ENTRY}[[[END") -endforeach() -message("===============") -#message("${SKETCH_SOURCE}") diff --git a/cmake/modules/FindArduino.cmake b/cmake/modules/FindArduino.cmake deleted file mode 100644 index dc2b18659a..0000000000 --- a/cmake/modules/FindArduino.cmake +++ /dev/null @@ -1,611 +0,0 @@ -# - Generate firmware and libraries for Arduino Devices -# generate_arduino_firmware(TARGET_NAME) -# TARGET_NAME - Name of target -# Creates a Arduino firmware target. -# -# The target options can be configured by setting options of -# the following format: -# ${TARGET_NAME}${SUFFIX} -# The following suffixes are availabe: -# _SRCS # Sources -# _HDRS # Headers -# _SKETCHES # Arduino sketch files -# _LIBS # Libraries to linked in -# _BOARD # Board name (such as uno, mega2560, ...) -# _PORT # Serial port, for upload and serial targets [OPTIONAL] -# _AFLAGS # Override global Avrdude flags for target -# _SERIAL # Serial command for serial target [OPTIONAL] -# _NO_AUTOLIBS # Disables Arduino library detection -# Here is a short example for a target named test: -# set(test_SRCS test.cpp) -# set(test_HDRS test.h) -# set(test_BOARD uno) -# -# generate_arduino_firmware(test) -# -# -# generate_arduino_library(TARGET_NAME) -# TARGET_NAME - Name of target -# Creates a Arduino firmware target. -# -# The target options can be configured by setting options of -# the following format: -# ${TARGET_NAME}${SUFFIX} -# The following suffixes are availabe: -# -# _SRCS # Sources -# _HDRS # Headers -# _LIBS # Libraries to linked in -# _BOARD # Board name (such as uno, mega2560, ...) -# _NO_AUTOLIBS # Disables Arduino library detection -# -# Here is a short example for a target named test: -# set(test_SRCS test.cpp) -# set(test_HDRS test.h) -# set(test_BOARD uno) -# -# generate_arduino_library(test) - - -find_path(ARDUINO_SDK_PATH - NAMES lib/version.txt hardware libraries - PATH_SUFFIXES share/arduino - DOC "Arduino Development Kit path.") - - -# load_board_settings() -# -# Load the Arduino SDK board settings from the boards.txt file. -# -function(LOAD_BOARD_SETTINGS) - if(NOT ARDUINO_BOARDS AND ARDUINO_BOARDS_PATH) - file(STRINGS ${ARDUINO_BOARDS_PATH} BOARD_SETTINGS) - foreach(BOARD_SETTING ${BOARD_SETTINGS}) - if("${BOARD_SETTING}" MATCHES "^.*=.*") - string(REGEX MATCH "^[^=]+" SETTING_NAME ${BOARD_SETTING}) - string(REGEX MATCH "[^=]+$" SETTING_VALUE ${BOARD_SETTING}) - string(REPLACE "." ";" SETTING_NAME_TOKENS ${SETTING_NAME}) - - list(LENGTH SETTING_NAME_TOKENS SETTING_NAME_TOKENS_LEN) - - - # Add Arduino to main list of arduino boards - list(GET SETTING_NAME_TOKENS 0 BOARD_ID) - list(FIND ARDUINO_BOARDS ${BOARD_ID} ARDUINO_BOARD_INDEX) - if(ARDUINO_BOARD_INDEX LESS 0) - list(APPEND ARDUINO_BOARDS ${BOARD_ID}) - endif() - - # Add setting to board settings list - list(GET SETTING_NAME_TOKENS 1 BOARD_SETTING) - list(FIND ${BOARD_ID}.SETTINGS ${BOARD_SETTING} BOARD_SETTINGS_LEN) - if(BOARD_SETTINGS_LEN LESS 0) - list(APPEND ${BOARD_ID}.SETTINGS ${BOARD_SETTING}) - set(${BOARD_ID}.SETTINGS ${${BOARD_ID}.SETTINGS} - CACHE INTERNAL "Arduino ${BOARD_ID} Board settings list") - endif() - - set(ARDUINO_SETTING_NAME ${BOARD_ID}.${BOARD_SETTING}) - - # Add sub-setting to board sub-settings list - if(SETTING_NAME_TOKENS_LEN GREATER 2) - list(GET SETTING_NAME_TOKENS 2 BOARD_SUBSETTING) - list(FIND ${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS ${BOARD_SUBSETTING} BOARD_SUBSETTINGS_LEN) - if(BOARD_SUBSETTINGS_LEN LESS 0) - list(APPEND ${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS ${BOARD_SUBSETTING}) - set(${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS ${${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS} - CACHE INTERNAL "Arduino ${BOARD_ID} Board sub-settings list") - endif() - set(ARDUINO_SETTING_NAME ${ARDUINO_SETTING_NAME}.${BOARD_SUBSETTING}) - endif() - - # Save setting value - set(${ARDUINO_SETTING_NAME} ${SETTING_VALUE} CACHE INTERNAL "Arduino ${BOARD_ID} Board setting") - - - endif() - endforeach() - set(ARDUINO_BOARDS ${ARDUINO_BOARDS} CACHE STRING "List of detected Arduino Board configurations") - mark_as_advanced(ARDUINO_BOARDS) - endif() -endfunction() - -# print_board_settings(ARDUINO_BOARD) -# -# ARDUINO_BOARD - Board id -# -# Print the detected Arduino board settings. -# -function(PRINT_BOARD_SETTINGS ARDUINO_BOARD) - if(${ARDUINO_BOARD}.SETTINGS) - - message(STATUS "Arduino ${ARDUINO_BOARD} Board:") - foreach(BOARD_SETTING ${${ARDUINO_BOARD}.SETTINGS}) - if(${ARDUINO_BOARD}.${BOARD_SETTING}) - message(STATUS " ${ARDUINO_BOARD}.${BOARD_SETTING}=${${ARDUINO_BOARD}.${BOARD_SETTING}}") - endif() - if(${ARDUINO_BOARD}.${BOARD_SETTING}.SUBSETTINGS) - foreach(BOARD_SUBSETTING ${${ARDUINO_BOARD}.${BOARD_SETTING}.SUBSETTINGS}) - if(${ARDUINO_BOARD}.${BOARD_SETTING}.${BOARD_SUBSETTING}) - message(STATUS " ${ARDUINO_BOARD}.${BOARD_SETTING}.${BOARD_SUBSETTING}=${${ARDUINO_BOARD}.${BOARD_SETTING}.${BOARD_SUBSETTING}}") - endif() - endforeach() - endif() - message(STATUS "") - endforeach() - endif() -endfunction() - - - -# generate_arduino_library(TARGET_NAME) -# -# see documentation at top -function(GENERATE_ARDUINO_LIBRARY TARGET_NAME) - load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources - _HDRS # Headers - _LIBS # Libraries to linked in - _BOARD) # Board name (such as uno, mega2560, ...) - set(INPUT_AUTOLIBS True) - if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) - set(INPUT_AUTOLIBS False) - endif() - - message(STATUS "Generating ${TARGET_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) - - setup_arduino_compiler(${INPUT_BOARD}) - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - - if(INPUT_AUTOLIBS) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}") - endif() - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - add_library(${TARGET_NAME} ${ALL_SRCS}) - target_link_libraries(${TARGET_NAME} ${ALL_LIBS}) -endfunction() - -# generate_arduino_firmware(TARGET_NAME) -# -# see documentation at top -function(GENERATE_ARDUINO_FIRMWARE TARGET_NAME) - load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources - _HDRS # Headers - _LIBS # Libraries to linked in - _BOARD # Board name (such as uno, mega2560, ...) - _PORT # Serial port, for upload and serial targets - _AFLAGS # Override global Avrdude flags for target - _SKETCHES # Arduino sketch files - _SERIAL) # Serial command for serial target - - set(INPUT_AUTOLIBS True) - if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) - set(INPUT_AUTOLIBS False) - endif() - - message(STATUS "Generating ${TARGET_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) - - setup_arduino_compiler(${INPUT_BOARD}) - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - - #setup_arduino_sketch(SKETCH_SRCS ${INPUT_SKETCHES}) - - if(INPUT_AUTOLIBS) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}") - endif() - - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - setup_arduino_target(${TARGET_NAME} "${ALL_SRCS}" "${ALL_LIBS}") - - if(INPUT_PORT) - setup_arduino_upload(${INPUT_BOARD} ${TARGET_NAME} ${INPUT_PORT}) - endif() - - if(INPUT_SERIAL) - setup_serial_target(${TARGET_NAME} "${INPUT_SERIAL}") - endif() -endfunction() - - -# load_generator_settings(TARGET_NAME PREFIX [SUFFIX_1 SUFFIX_2 .. SUFFIX_N]) -# -# TARGET_NAME - The base name of the user settings -# PREFIX - The prefix name used for generator settings -# SUFFIX_XX - List of suffixes to load -# -# Loads a list of user settings into the generators scope. User settings have -# the following syntax: -# -# ${BASE_NAME}${SUFFIX} -# -# The BASE_NAME is the target name and the suffix is a specific generator settings. -# -# For every user setting found a generator setting is created of the follwoing fromat: -# -# ${PREFIX}${SUFFIX} -# -# The purpose of loading the settings into the generator is to not modify user settings -# and to have a generic naming of the settings within the generator. -# -function(LOAD_GENERATOR_SETTINGS TARGET_NAME PREFIX) - foreach(GEN_SUFFIX ${ARGN}) - if(${TARGET_NAME}${GEN_SUFFIX}) - set(${PREFIX}${GEN_SUFFIX} ${${TARGET_NAME}${GEN_SUFFIX}} PARENT_SCOPE) - endif() - endforeach() -endfunction() - -# setup_arduino_compiler(BOARD_ID) -# -# BOARD_ID - The board id name -# -# Configures the the build settings for the specified Arduino Board. -# -macro(setup_arduino_compiler BOARD_ID) - set(BOARD_CORE ${${BOARD_ID}.build.core}) - if(BOARD_CORE) - set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) - include_directories(${BOARD_CORE_PATH}) - include_directories(${ARDUINO_LIBRARIES_PATH}) - add_definitions(-DF_CPU=${${BOARD_ID}.build.f_cpu} - -DARDUINO=${ARDUINO_SDK_VERSION} - -mmcu=${${BOARD_ID}.build.mcu} - ) - set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -mmcu=${${BOARD_ID}.build.mcu}" PARENT_SCOPE) - set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -mmcu=${${BOARD_ID}.build.mcu}" PARENT_SCOPE) - set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -mmcu=${${BOARD_ID}.build.mcu}" PARENT_SCOPE) - endif() -endmacro() - -# setup_arduino_core(VAR_NAME BOARD_ID) -# -# VAR_NAME - Variable name that will hold the generated library name -# BOARD_ID - Arduino board id -# -# Creates the Arduino Core library for the specified board, -# each board gets it's own version of the library. -# -function(setup_arduino_core VAR_NAME BOARD_ID) - set(CORE_LIB_NAME ${BOARD_ID}_CORE) - set(BOARD_CORE ${${BOARD_ID}.build.core}) - if(BOARD_CORE AND NOT TARGET ${CORE_LIB_NAME}) - set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) - find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) - - # Debian/Ubuntu fix - list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") - - add_library(${CORE_LIB_NAME} ${CORE_SRCS}) - set(${VAR_NAME} ${CORE_LIB_NAME} PARENT_SCOPE) - endif() -endfunction() - -# find_arduino_libraries(VAR_NAME SRCS) -# -# VAR_NAME - Variable name which will hold the results -# SRCS - Sources that will be analized -# -# returns a list of paths to libraries found. -# -# Finds all Arduino type libraries included in sources. Available libraries -# are ${ARDUINO_SDK_PATH}/libraries and ${CMAKE_CURRENT_SOURCE_DIR}. -# -# A Arduino library is a folder that has the same name as the include header. -# For example, if we have a include "#include " then the following -# directory structure is considered a Arduino library: -# -# LibraryName/ -# |- LibraryName.h -# `- LibraryName.c -# -# If such a directory is found then all sources within that directory are considred -# to be part of that Arduino library. -# -function(find_arduino_libraries VAR_NAME SRCS) - set(ARDUINO_LIBS ) - foreach(SRC ${SRCS}) - file(STRINGS ${SRC} SRC_CONTENTS) - foreach(SRC_LINE ${SRC_CONTENTS}) - if("${SRC_LINE}" MATCHES "^ *#include *[<\"](.*)[>\"]") - get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) - get_property(LIBRARY_SEARCH_PATH - DIRECTORY # Property Scope - PROPERTY LINK_DIRECTORIES) - foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) - if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) - list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) - break() - endif() - endforeach() - endif() - endforeach() - endforeach() - if(ARDUINO_LIBS) - list(REMOVE_DUPLICATES ARDUINO_LIBS) - endif() - set(${VAR_NAME} ${ARDUINO_LIBS} PARENT_SCOPE) -endfunction() - -# setup_arduino_library(VAR_NAME BOARD_ID LIB_PATH) -# -# VAR_NAME - Vairable wich will hold the generated library names -# BOARD_ID - Board name -# LIB_PATH - path of the library -# -# Creates an Arduino library, with all it's library dependencies. -# -# ${LIB_NAME}_RECURSE controls if the library will recurse -# when looking for source files. -# - -# For known libraries can list recurse here -set(Wire_RECURSE True) -set(Ethernet_RECURSE True) -function(setup_arduino_library VAR_NAME BOARD_ID LIB_PATH) - set(LIB_TARGETS) - - get_filename_component(LIB_NAME ${LIB_PATH} NAME) - set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) - if(NOT TARGET ${TARGET_LIB_NAME}) - string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) - - # Detect if recursion is needed - if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) - set(${LIB_SHORT_NAME}_RECURSE False) - endif() - - find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) - if(LIB_SRCS) - - message(STATUS "Generating Arduino ${LIB_NAME} library") - include_directories(${LIB_PATH} ${LIB_PATH}/utility) - add_library(${TARGET_LIB_NAME} STATIC ${LIB_SRCS}) - - find_arduino_libraries(LIB_DEPS "${LIB_SRCS}") - foreach(LIB_DEP ${LIB_DEPS}) - setup_arduino_library(DEP_LIB_SRCS ${BOARD_ID} ${LIB_DEP}) - list(APPEND LIB_TARGETS ${DEP_LIB_SRCS}) - endforeach() - - target_link_libraries(${TARGET_LIB_NAME} ${BOARD_ID}_CORE ${LIB_TARGETS}) - list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) - endif() - else() - # Target already exists, skiping creating - include_directories(${LIB_PATH} ${LIB_PATH}/utility) - list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) - endif() - if(LIB_TARGETS) - list(REMOVE_DUPLICATES LIB_TARGETS) - endif() - set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) -endfunction() - -# setup_arduino_libraries(VAR_NAME BOARD_ID SRCS) -# -# VAR_NAME - Vairable wich will hold the generated library names -# BOARD_ID - Board ID -# SRCS - source files -# -# Finds and creates all dependency libraries based on sources. -# -function(setup_arduino_libraries VAR_NAME BOARD_ID SRCS) - set(LIB_TARGETS) - find_arduino_libraries(TARGET_LIBS "${SRCS}") - foreach(TARGET_LIB ${TARGET_LIBS}) - setup_arduino_library(LIB_DEPS ${BOARD_ID} ${TARGET_LIB}) # Create static library instead of returning sources - list(APPEND LIB_TARGETS ${LIB_DEPS}) - endforeach() - set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) -endfunction() - - -# setup_arduino_target(TARGET_NAME ALL_SRCS ALL_LIBS) -# -# TARGET_NAME - Target name -# ALL_SRCS - All sources -# ALL_LIBS - All libraries -# -# Creates an Arduino firmware target. -# -function(setup_arduino_target TARGET_NAME ALL_SRCS ALL_LIBS) - add_executable(${TARGET_NAME} ${ALL_SRCS}) - target_link_libraries(${TARGET_NAME} ${ALL_LIBS}) - set_target_properties(${TARGET_NAME} PROPERTIES SUFFIX ".elf") - - set(TARGET_PATH ${CMAKE_CURRENT_BINARY_DIR}/${TARGET_NAME}) - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_OBJCOPY} - ARGS ${ARDUINO_OBJCOPY_EEP_FLAGS} - ${TARGET_PATH}.elf - ${TARGET_PATH}.eep - VERBATIM) - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_OBJCOPY} - ARGS ${ARDUINO_OBJCOPY_HEX_FLAGS} - ${TARGET_PATH}.elf - ${TARGET_PATH}.hex - VERBATIM) -endfunction() - -# setup_arduino_upload(BOARD_ID TARGET_NAME PORT) -# -# BOARD_ID - Arduino board id -# TARGET_NAME - Target name -# PORT - Serial port for upload -# -# Create an upload target (${TARGET_NAME}-upload) for the specified Arduino target. -# -function(setup_arduino_upload BOARD_ID TARGET_NAME PORT) - set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) - if(DEFINED ${TARGET_NAME}_AFLAGS) - set(AVRDUDE_FLAGS ${${TARGET_NAME}_AFLAGS}) - endif() - if (${${BOARD_ID}.upload.protocol} STREQUAL "stk500") - set(${BOARD_ID}.upload.protocol "stk500v1") - endif() - add_custom_target(${TARGET_NAME}-upload - ${ARDUINO_AVRDUDE_PROGRAM} - ${AVRDUDE_FLAGS} - -C${ARDUINO_AVRDUDE_CONFIG_PATH} - -p${${BOARD_ID}.build.mcu} - -c${${BOARD_ID}.upload.protocol} - -P${PORT} -b${${BOARD_ID}.upload.speed} - #-D - -Uflash:w:${CMAKE_BINARY_DIR}/${TARGET_NAME}.hex:i - DEPENDS ${TARGET_NAME}) - if(NOT TARGET upload) - add_custom_target(upload) - endif() - add_dependencies(upload ${TARGET_NAME}-upload) -endfunction() - -# find_sources(VAR_NAME LIB_PATH RECURSE) -# -# VAR_NAME - Variable name that will hold the detected sources -# LIB_PATH - The base path -# RECURSE - Whether or not to recurse -# -# Finds all C/C++ sources located at the specified path. -# -function(find_sources VAR_NAME LIB_PATH RECURSE) - set(FILE_SEARCH_LIST - ${LIB_PATH}/*.cpp - ${LIB_PATH}/*.c - ${LIB_PATH}/*.cc - ${LIB_PATH}/*.cxx - ${LIB_PATH}/*.h - ${LIB_PATH}/*.hh - ${LIB_PATH}/*.hxx) - - if(RECURSE) - file(GLOB_RECURSE LIB_FILES ${FILE_SEARCH_LIST}) - else() - file(GLOB LIB_FILES ${FILE_SEARCH_LIST}) - endif() - - if(LIB_FILES) - set(${VAR_NAME} ${LIB_FILES} PARENT_SCOPE) - endif() -endfunction() - -# setup_serial_target(TARGET_NAME CMD) -# -# TARGET_NAME - Target name -# CMD - Serial terminal command -# -# Creates a target (${TARGET_NAME}-serial) for launching the serial termnial. -# -function(setup_serial_target TARGET_NAME CMD) - string(CONFIGURE "${CMD}" FULL_CMD @ONLY) - add_custom_target(${TARGET_NAME}-serial - ${FULL_CMD}) -endfunction() - - -# detect_arduino_version(VAR_NAME) -# -# VAR_NAME - Variable name where the detected version will be saved -# -# Detects the Arduino SDK Version based on the revisions.txt file. -# -function(detect_arduino_version VAR_NAME) - if(ARDUINO_VERSION_PATH) - file(READ ${ARDUINO_VERSION_PATH} ARD_VERSION) - if("${ARD_VERSION}" MATCHES " *[0]+([0-9]+)") - set(${VAR_NAME} ${CMAKE_MATCH_1} PARENT_SCOPE) - endif() - endif() -endfunction() - - -function(convert_arduino_sketch VAR_NAME SRCS) -endfunction() - - -# Setting up Arduino enviroment settings -find_file(ARDUINO_CORES_PATH - NAMES cores - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/arduino - NO_DEFAULT_PATH) - -find_file(ARDUINO_LIBRARIES_PATH - NAMES libraries - PATHS ${ARDUINO_SDK_PATH} - NO_DEFAULT_PATH) - -find_file(ARDUINO_BOARDS_PATH - NAMES boards.txt - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/arduino - NO_DEFAULT_PATH) - -find_file(ARDUINO_PROGRAMMERS_PATH - NAMES programmers.txt - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/arduino - NO_DEFAULT_PATH) - -find_file(ARDUINO_REVISIONS_PATH - NAMES revisions.txt - PATHS ${ARDUINO_SDK_PATH} - NO_DEFAULT_PATH) - -find_file(ARDUINO_VERSION_PATH - NAMES lib/version.txt - PATHS ${ARDUINO_SDK_PATH} - NO_DEFAULT_PATH) - -find_program(ARDUINO_AVRDUDE_PROGRAM - NAMES avrdude - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/tools - NO_DEFAULT_PATH) - -find_file(ARDUINO_AVRDUDE_CONFIG_PATH - NAMES avrdude.conf - PATHS ${ARDUINO_SDK_PATH} /etc/avrdude - PATH_SUFFIXES hardware/tools - hardware/tools/avr/etc - NO_DEFAULT_PATH) - -set(ARDUINO_OBJCOPY_EEP_FLAGS -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load --no-change-warnings --change-section-lma .eeprom=0 - CACHE STRING "") -set(ARDUINO_OBJCOPY_HEX_FLAGS -O ihex -R .eeprom - CACHE STRING "") -set(ARDUINO_AVRDUDE_FLAGS -V -F - CACHE STRING "Arvdude global flag list.") - -if(ARDUINO_SDK_PATH) - detect_arduino_version(ARDUINO_SDK_VERSION) - set(ARDUINO_SDK_VERSION ${ARDUINO_SDK_VERSION} CACHE STRING "Arduino SDK Version") -endif(ARDUINO_SDK_PATH) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Arduino - REQUIRED_VARS ARDUINO_SDK_PATH - ARDUINO_SDK_VERSION - VERSION_VAR ARDUINO_SDK_VERSION) - - -mark_as_advanced(ARDUINO_CORES_PATH - ARDUINO_SDK_VERSION - ARDUINO_LIBRARIES_PATH - ARDUINO_BOARDS_PATH - ARDUINO_PROGRAMMERS_PATH - ARDUINO_REVISIONS_PATH - ARDUINO_AVRDUDE_PROGRAM - ARDUINO_AVRDUDE_CONFIG_PATH - ARDUINO_OBJCOPY_EEP_FLAGS - ARDUINO_OBJCOPY_HEX_FLAGS) -load_board_settings() diff --git a/cmake/modules/Platform/Arduino.cmake b/cmake/modules/Platform/Arduino.cmake deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cmake/modules/Platform/ArduinoPaths.cmake b/cmake/modules/Platform/ArduinoPaths.cmake deleted file mode 100644 index 27372098cc..0000000000 --- a/cmake/modules/Platform/ArduinoPaths.cmake +++ /dev/null @@ -1,21 +0,0 @@ -if(UNIX) - include(Platform/UnixPaths) - if(APPLE) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ~/Applications - /Applications - /Developer/Applications - /sw # Fink - /opt/local) # MacPorts - endif() -elseif(WIN32) - include(Platform/WindowsPaths) -endif() - -if(ARDUINO_SDK_PATH) - if(WIN32) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/utils/bin) - elseif(APPLE) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) - endif() -endif() diff --git a/cmake/toolchains/Arduino.cmake b/cmake/toolchains/Arduino.cmake deleted file mode 100644 index 897ea4fa0c..0000000000 --- a/cmake/toolchains/Arduino.cmake +++ /dev/null @@ -1,72 +0,0 @@ -set(CMAKE_SYSTEM_NAME Arduino) - -set(CMAKE_C_COMPILER avr-gcc) -set(CMAKE_CXX_COMPILER avr-g++) - -#=============================================================================# -# C Flags # -#=============================================================================# -if (NOT DEFINED ARDUINO_C_FLAGS) - set(ARDUINO_C_FLAGS "-ffunction-sections -fdata-sections") -endif() -set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELEASE "-0s -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELWITHDEBINFO "-0s -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") - -#=============================================================================# -# C++ Flags # -#=============================================================================# -if (NOT DEFINED ARDUINO_CXX_FLAGS) - set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") -endif() -set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELEASE "-0s -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-0s -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") - -#=============================================================================# -# Executable Linker Flags # -#=============================================================================# -if (NOT DEFINED ARDUINO_LINKER_FLAGS) - set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections") -endif() -set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") - -#=============================================================================# -# Shared Lbrary Linker Flags # -#=============================================================================# -set(CMAKE_SHARED_LINKER_FLAGS "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_DEBUG "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO "" CACHE STRING "") - -set(CMAKE_MODULE_LINKER_FLAGS "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_DEBUG "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_RELEASE "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO "" CACHE STRING "") - - - - -set(ARDUINO_PATHS) -foreach(VERSION RANGE 22 1) - list(APPEND ARDUINO_PATHS arduino-00${VERSION}) -endforeach() - -find_path(ARDUINO_SDK_PATH - NAMES lib/version.txt - PATH_SUFFIXES share/arduino - Arduino.app/Contents/Resources/Java/ - ${ARDUINO_PATHS} - DOC "Arduino Development Kit path.") - -include(Platform/ArduinoPaths) diff --git a/cmake/updated-arduino-cmake.sh b/cmake/updated-arduino-cmake.sh index c8c26b6781..3cda692b83 100755 --- a/cmake/updated-arduino-cmake.sh +++ b/cmake/updated-arduino-cmake.sh @@ -1,5 +1,4 @@ #!/bin/bash git clone git://github.com/jgoppert/arduino-cmake.git tmp -cp -rf tmp/cmake/modules/* modules -cp -rf tmp/cmake/toolchains/* toolchains +cp -rf tmp/cmake/* . rm -rf tmp