Merge branch 'master' of https://code.google.com/p/ardupilot-mega into retro-loiter

This commit is contained in:
Adam M Rivera 2012-04-19 10:17:36 -05:00
commit 24363ccb83
72 changed files with 20799 additions and 12312 deletions

View File

@ -2174,6 +2174,10 @@ static void tuning(){
g.pid_optflow_roll.kD(tuning_value);
g.pid_optflow_pitch.kD(tuning_value);
break;
case CH6_AHRS_YAW_KP:
ahrs._kp_yaw.set(tuning_value);
break;
}
}

48
ArduCopter/CMakeLists.txt Normal file
View File

@ -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)

View File

@ -102,6 +102,7 @@ public:
k_param_rtl_land_enabled,
k_param_axis_enabled,
k_param_copter_leds_mode, //158
k_param_ahrs, // AHRS group
//
// 160: Navigation parameters

View File

@ -135,12 +135,13 @@ static const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(compass, "COMPASS_", Compass),
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
GOBJECT(imu, "IMU_", IMU)
GOBJECT(imu, "IMU_", IMU),
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#if FRAME_CONFIG == HELI_FRAME
,GOBJECT(motors, "H_", AP_MotorsHeli)
GOBJECT(motors, "H_", AP_MotorsHeli),
#else
,GOBJECT(motors, "MOT_", AP_Motors)
GOBJECT(motors, "MOT_", AP_Motors),
#endif
};

View File

@ -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
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////

View File

@ -184,6 +184,8 @@
#define CH6_LOITER_RATE_KI 28
#define CH6_LOITER_RATE_KD 23
#define CH6_AHRS_YAW_KP 30
// nav byte mask
// -------------

183
ArduCopter/options.cmake Normal file
View File

@ -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)

View File

@ -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

52
ArduPlane/CMakeLists.txt Normal file
View File

@ -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)

View File

@ -84,6 +84,7 @@ public:
k_param_airspeed_offset,
k_param_sonar_enabled,
k_param_airspeed_enabled,
k_param_ahrs, // AHRS group
//
// 150: Navigation parameters

View File

@ -125,7 +125,8 @@ static const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(compass, "COMPASS_", Compass),
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
GOBJECT(imu, "IMU_", IMU)
GOBJECT(imu, "IMU_", IMU),
GOBJECT(ahrs, "AHRS_", AP_AHRS)
};

View File

@ -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.

209
ArduPlane/options.cmake Normal file
View File

@ -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)

View File

@ -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})

View File

@ -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)

View File

@ -1,384 +1,293 @@
namespace ArdupilotMega.Antenna
{
partial class Tracker
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Windows Form Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Windows Form Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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;
}
}

View File

@ -1,120 +1,830 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="CMB_interface.Items" xml:space="preserve">
<value>Maestro</value>
</data>
<data name="CMB_interface.Items1" xml:space="preserve">
<value>ArduTracker</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CMB_interface.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 10</value>
</data>
<data name="CMB_interface.Size" type="System.Drawing.Size, System.Drawing">
<value>121, 21</value>
</data>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="CMB_interface.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="CMB_interface.Text" xml:space="preserve">
<value>Maestro</value>
</data>
<data name="&gt;&gt;CMB_interface.Name" xml:space="preserve">
<value>CMB_interface</value>
</data>
<data name="&gt;&gt;CMB_interface.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_interface.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_interface.ZOrder" xml:space="preserve">
<value>25</value>
</data>
<data name="label1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>13, 13</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>49, 13</value>
</data>
<data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>Interface</value>
</data>
<data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>24</value>
</data>
<data name="CMB_baudrate.Items" xml:space="preserve">
<value>4800</value>
</data>
<data name="CMB_baudrate.Items1" xml:space="preserve">
<value>9600</value>
</data>
<data name="CMB_baudrate.Items2" xml:space="preserve">
<value>14400</value>
</data>
<data name="CMB_baudrate.Items3" xml:space="preserve">
<value>19200</value>
</data>
<data name="CMB_baudrate.Items4" xml:space="preserve">
<value>28800</value>
</data>
<data name="CMB_baudrate.Items5" xml:space="preserve">
<value>38400</value>
</data>
<data name="CMB_baudrate.Items6" xml:space="preserve">
<value>57600</value>
</data>
<data name="CMB_baudrate.Items7" xml:space="preserve">
<value>115200</value>
</data>
<data name="CMB_baudrate.Location" type="System.Drawing.Point, System.Drawing">
<value>337, 9</value>
</data>
<data name="CMB_baudrate.Size" type="System.Drawing.Size, System.Drawing">
<value>121, 21</value>
</data>
<data name="CMB_baudrate.TabIndex" type="System.Int32, mscorlib">
<value>2</value>
</data>
<data name="&gt;&gt;CMB_baudrate.Name" xml:space="preserve">
<value>CMB_baudrate</value>
</data>
<data name="&gt;&gt;CMB_baudrate.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_baudrate.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_baudrate.ZOrder" xml:space="preserve">
<value>21</value>
</data>
<data name="CMB_serialport.Location" type="System.Drawing.Point, System.Drawing">
<value>210, 10</value>
</data>
<data name="CMB_serialport.Size" type="System.Drawing.Size, System.Drawing">
<value>121, 21</value>
</data>
<data name="CMB_serialport.TabIndex" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="&gt;&gt;CMB_serialport.Name" xml:space="preserve">
<value>CMB_serialport</value>
</data>
<data name="&gt;&gt;CMB_serialport.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_serialport.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_serialport.ZOrder" xml:space="preserve">
<value>23</value>
</data>
<data name="TRK_pantrim.Location" type="System.Drawing.Point, System.Drawing">
<value>153, 81</value>
</data>
<data name="TRK_pantrim.Size" type="System.Drawing.Size, System.Drawing">
<value>375, 45</value>
</data>
<data name="TRK_pantrim.TabIndex" type="System.Int32, mscorlib">
<value>5</value>
</data>
<data name="&gt;&gt;TRK_pantrim.Name" xml:space="preserve">
<value>TRK_pantrim</value>
</data>
<data name="&gt;&gt;TRK_pantrim.Type" xml:space="preserve">
<value>System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TRK_pantrim.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TRK_pantrim.ZOrder" xml:space="preserve">
<value>20</value>
</data>
<data name="TXT_panrange.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 81</value>
</data>
<data name="TXT_panrange.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 20</value>
</data>
<data name="TXT_panrange.TabIndex" type="System.Int32, mscorlib">
<value>4</value>
</data>
<data name="TXT_panrange.Text" xml:space="preserve">
<value>360</value>
</data>
<data name="&gt;&gt;TXT_panrange.Name" xml:space="preserve">
<value>TXT_panrange</value>
</data>
<data name="&gt;&gt;TXT_panrange.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TXT_panrange.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TXT_panrange.ZOrder" xml:space="preserve">
<value>19</value>
</data>
<data name="label3.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label3.Location" type="System.Drawing.Point, System.Drawing">
<value>326, 65</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>27, 13</value>
</data>
<data name="label3.TabIndex" type="System.Int32, mscorlib">
<value>10</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>Trim</value>
</data>
<data name="&gt;&gt;label3.Name" xml:space="preserve">
<value>label3</value>
</data>
<data name="&gt;&gt;label3.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label3.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label3.ZOrder" xml:space="preserve">
<value>18</value>
</data>
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label4.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 65</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>39, 13</value>
</data>
<data name="label4.TabIndex" type="System.Int32, mscorlib">
<value>11</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>Range</value>
</data>
<data name="&gt;&gt;label4.Name" xml:space="preserve">
<value>label4</value>
</data>
<data name="&gt;&gt;label4.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label4.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label4.ZOrder" xml:space="preserve">
<value>17</value>
</data>
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label5.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 141</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>39, 13</value>
</data>
<data name="label5.TabIndex" type="System.Int32, mscorlib">
<value>17</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>Range</value>
</data>
<data name="&gt;&gt;label5.Name" xml:space="preserve">
<value>label5</value>
</data>
<data name="&gt;&gt;label5.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
<value>13</value>
</data>
<data name="label6.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label6.Location" type="System.Drawing.Point, System.Drawing">
<value>326, 141</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>27, 13</value>
</data>
<data name="label6.TabIndex" type="System.Int32, mscorlib">
<value>16</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>Trim</value>
</data>
<data name="&gt;&gt;label6.Name" xml:space="preserve">
<value>label6</value>
</data>
<data name="&gt;&gt;label6.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label6.ZOrder" xml:space="preserve">
<value>14</value>
</data>
<data name="TXT_tiltrange.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 157</value>
</data>
<data name="TXT_tiltrange.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 20</value>
</data>
<data name="TXT_tiltrange.TabIndex" type="System.Int32, mscorlib">
<value>6</value>
</data>
<data name="TXT_tiltrange.Text" xml:space="preserve">
<value>90</value>
</data>
<data name="&gt;&gt;TXT_tiltrange.Name" xml:space="preserve">
<value>TXT_tiltrange</value>
</data>
<data name="&gt;&gt;TXT_tiltrange.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TXT_tiltrange.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TXT_tiltrange.ZOrder" xml:space="preserve">
<value>15</value>
</data>
<data name="TRK_tilttrim.Location" type="System.Drawing.Point, System.Drawing">
<value>153, 157</value>
</data>
<data name="TRK_tilttrim.Size" type="System.Drawing.Size, System.Drawing">
<value>375, 45</value>
</data>
<data name="TRK_tilttrim.TabIndex" type="System.Int32, mscorlib">
<value>7</value>
</data>
<data name="&gt;&gt;TRK_tilttrim.Name" xml:space="preserve">
<value>TRK_tilttrim</value>
</data>
<data name="&gt;&gt;TRK_tilttrim.Type" xml:space="preserve">
<value>System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TRK_tilttrim.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TRK_tilttrim.ZOrder" xml:space="preserve">
<value>16</value>
</data>
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label2.Location" type="System.Drawing.Point, System.Drawing">
<value>12, 65</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>26, 13</value>
</data>
<data name="label2.TabIndex" type="System.Int32, mscorlib">
<value>18</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>Pan</value>
</data>
<data name="&gt;&gt;label2.Name" xml:space="preserve">
<value>label2</value>
</data>
<data name="&gt;&gt;label2.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label2.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
<value>12</value>
</data>
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label7.Location" type="System.Drawing.Point, System.Drawing">
<value>12, 141</value>
</data>
<data name="label7.Size" type="System.Drawing.Size, System.Drawing">
<value>21, 13</value>
</data>
<data name="label7.TabIndex" type="System.Int32, mscorlib">
<value>19</value>
</data>
<data name="label7.Text" xml:space="preserve">
<value>Tilt</value>
</data>
<data name="&gt;&gt;label7.Name" xml:space="preserve">
<value>label7</value>
</data>
<data name="&gt;&gt;label7.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label7.ZOrder" xml:space="preserve">
<value>11</value>
</data>
<data name="CHK_revpan.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_revpan.Location" type="System.Drawing.Point, System.Drawing">
<value>534, 83</value>
</data>
<data name="CHK_revpan.Size" type="System.Drawing.Size, System.Drawing">
<value>46, 17</value>
</data>
<data name="CHK_revpan.TabIndex" type="System.Int32, mscorlib">
<value>20</value>
</data>
<data name="CHK_revpan.Text" xml:space="preserve">
<value>Rev</value>
</data>
<data name="&gt;&gt;CHK_revpan.Name" xml:space="preserve">
<value>CHK_revpan</value>
</data>
<data name="&gt;&gt;CHK_revpan.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_revpan.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_revpan.ZOrder" xml:space="preserve">
<value>10</value>
</data>
<data name="CHK_revtilt.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_revtilt.Location" type="System.Drawing.Point, System.Drawing">
<value>534, 159</value>
</data>
<data name="CHK_revtilt.Size" type="System.Drawing.Size, System.Drawing">
<value>46, 17</value>
</data>
<data name="CHK_revtilt.TabIndex" type="System.Int32, mscorlib">
<value>21</value>
</data>
<data name="CHK_revtilt.Text" xml:space="preserve">
<value>Rev</value>
</data>
<data name="&gt;&gt;CHK_revtilt.Name" xml:space="preserve">
<value>CHK_revtilt</value>
</data>
<data name="&gt;&gt;CHK_revtilt.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_revtilt.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_revtilt.ZOrder" xml:space="preserve">
<value>9</value>
</data>
<data name="TXT_pwmrangepan.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 107</value>
</data>
<data name="TXT_pwmrangepan.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 20</value>
</data>
<data name="TXT_pwmrangepan.TabIndex" type="System.Int32, mscorlib">
<value>22</value>
</data>
<data name="TXT_pwmrangepan.Text" xml:space="preserve">
<value>1000</value>
</data>
<data name="&gt;&gt;TXT_pwmrangepan.Name" xml:space="preserve">
<value>TXT_pwmrangepan</value>
</data>
<data name="&gt;&gt;TXT_pwmrangepan.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TXT_pwmrangepan.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TXT_pwmrangepan.ZOrder" xml:space="preserve">
<value>8</value>
</data>
<data name="TXT_pwmrangetilt.Location" type="System.Drawing.Point, System.Drawing">
<value>83, 183</value>
</data>
<data name="TXT_pwmrangetilt.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 20</value>
</data>
<data name="TXT_pwmrangetilt.TabIndex" type="System.Int32, mscorlib">
<value>23</value>
</data>
<data name="TXT_pwmrangetilt.Text" xml:space="preserve">
<value>1000</value>
</data>
<data name="&gt;&gt;TXT_pwmrangetilt.Name" xml:space="preserve">
<value>TXT_pwmrangetilt</value>
</data>
<data name="&gt;&gt;TXT_pwmrangetilt.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TXT_pwmrangetilt.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TXT_pwmrangetilt.ZOrder" xml:space="preserve">
<value>7</value>
</data>
<data name="label8.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
<value>43, 110</value>
</data>
<data name="label8.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label8.TabIndex" type="System.Int32, mscorlib">
<value>24</value>
</data>
<data name="label8.Text" xml:space="preserve">
<value>PWM</value>
</data>
<data name="&gt;&gt;label8.Name" xml:space="preserve">
<value>label8</value>
</data>
<data name="&gt;&gt;label8.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label8.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="label9.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label9.Location" type="System.Drawing.Point, System.Drawing">
<value>43, 186</value>
</data>
<data name="label9.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label9.TabIndex" type="System.Int32, mscorlib">
<value>25</value>
</data>
<data name="label9.Text" xml:space="preserve">
<value>PWM</value>
</data>
<data name="&gt;&gt;label9.Name" xml:space="preserve">
<value>label9</value>
</data>
<data name="&gt;&gt;label9.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label9.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label9.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="label10.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label10.Location" type="System.Drawing.Point, System.Drawing">
<value>45, 160</value>
</data>
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label10.TabIndex" type="System.Int32, mscorlib">
<value>27</value>
</data>
<data name="label10.Text" xml:space="preserve">
<value>Angle</value>
</data>
<data name="&gt;&gt;label10.Name" xml:space="preserve">
<value>label10</value>
</data>
<data name="&gt;&gt;label10.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label10.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label10.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="label11.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label11.Location" type="System.Drawing.Point, System.Drawing">
<value>45, 84</value>
</data>
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label11.TabIndex" type="System.Int32, mscorlib">
<value>26</value>
</data>
<data name="label11.Text" xml:space="preserve">
<value>Angle</value>
</data>
<data name="&gt;&gt;label11.Name" xml:space="preserve">
<value>label11</value>
</data>
<data name="&gt;&gt;label11.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label11.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label11.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="label12.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label12.Font" type="System.Drawing.Font, System.Drawing">
<value>Microsoft Sans Serif, 8.25pt, style=Bold</value>
</data>
<data name="label12.Location" type="System.Drawing.Point, System.Drawing">
<value>94, 40</value>
</data>
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
<value>403, 13</value>
</data>
<data name="label12.TabIndex" type="System.Int32, mscorlib">
<value>28</value>
</data>
<data name="label12.Text" xml:space="preserve">
<value>Miss using this interface can cause servo damage, use with caution!!!</value>
</data>
<data name="&gt;&gt;label12.Name" xml:space="preserve">
<value>label12</value>
</data>
<data name="&gt;&gt;label12.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label12.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label12.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="BUT_connect.Location" type="System.Drawing.Point, System.Drawing">
<value>476, 9</value>
</data>
<data name="BUT_connect.Size" type="System.Drawing.Size, System.Drawing">
<value>75, 23</value>
</data>
<data name="BUT_connect.TabIndex" type="System.Int32, mscorlib">
<value>3</value>
</data>
<data name="BUT_connect.Text" xml:space="preserve">
<value>Connect</value>
</data>
<data name="&gt;&gt;BUT_connect.Name" xml:space="preserve">
<value>BUT_connect</value>
</data>
<data name="&gt;&gt;BUT_connect.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_connect.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_connect.ZOrder" xml:space="preserve">
<value>22</value>
</data>
<data name="LBL_pantrim.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="LBL_pantrim.Location" type="System.Drawing.Point, System.Drawing">
<value>326, 113</value>
</data>
<data name="LBL_pantrim.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="LBL_pantrim.TabIndex" type="System.Int32, mscorlib">
<value>29</value>
</data>
<data name="LBL_pantrim.Text" xml:space="preserve">
<value>Angle</value>
</data>
<data name="&gt;&gt;LBL_pantrim.Name" xml:space="preserve">
<value>LBL_pantrim</value>
</data>
<data name="&gt;&gt;LBL_pantrim.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;LBL_pantrim.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;LBL_pantrim.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="LBL_tilttrim.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="LBL_tilttrim.Location" type="System.Drawing.Point, System.Drawing">
<value>326, 190</value>
</data>
<data name="LBL_tilttrim.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="LBL_tilttrim.TabIndex" type="System.Int32, mscorlib">
<value>30</value>
</data>
<data name="LBL_tilttrim.Text" xml:space="preserve">
<value>Angle</value>
</data>
<data name="&gt;&gt;LBL_tilttrim.Name" xml:space="preserve">
<value>LBL_tilttrim</value>
</data>
<data name="&gt;&gt;LBL_tilttrim.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;LBL_tilttrim.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;LBL_tilttrim.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
<value>6, 13</value>
</data>
<data name="$this.Size" type="System.Drawing.Size, System.Drawing">
<value>587, 212</value>
</data>
<data name="&gt;&gt;$this.Name" xml:space="preserve">
<value>Tracker</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
</root>

View File

@ -0,0 +1,208 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>接口</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>范围</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>范围</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>旋转</value>
</data>
<data name="label7.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label7.Text" xml:space="preserve">
<value>倾斜</value>
</data>
<data name="CHK_revpan.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revpan.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revtilt.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revtilt.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label10.Text" xml:space="preserve">
<value>角度</value>
</data>
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label11.Text" xml:space="preserve">
<value>角度</value>
</data>
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
<value>275, 13</value>
</data>
<data name="label12.Text" xml:space="preserve">
<value>错误的接口可能导致舵机损坏。务必小心使用!!!</value>
</data>
<data name="BUT_connect.Text" xml:space="preserve">
<value>连接</value>
</data>
<data name="LBL_pantrim.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="LBL_pantrim.Text" xml:space="preserve">
<value>角度</value>
</data>
<data name="LBL_tilttrim.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="LBL_tilttrim.Text" xml:space="preserve">
<value>角度</value>
</data>
</root>

View File

@ -543,6 +543,12 @@
<EmbeddedResource Include="Antenna\Tracker.resx">
<DependentUpon>Tracker.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Antenna\Tracker.zh-Hans.resx">
<DependentUpon>Tracker.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Camera.zh-Hans.resx">
<DependentUpon>Camera.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Controls\BackstageView\BackstageView.resx">
<DependentUpon>BackstageView.cs</DependentUpon>
</EmbeddedResource>
@ -745,6 +751,9 @@
<EmbeddedResource Include="MavlinkLog.es-ES.resx">
<DependentUpon>MavlinkLog.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Radio\3DRradio.zh-Hans.resx">
<DependentUpon>3DRradio.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="RAW_Sensor.es-ES.resx">
<DependentUpon>RAW_Sensor.cs</DependentUpon>
</EmbeddedResource>

View File

@ -1,384 +1,384 @@
namespace ArdupilotMega
{
partial class Camera
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Windows Form Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Windows Form Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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;
}
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,208 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>航高 (米)</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>焦距</value>
</data>
<data name="label6.Location" type="System.Drawing.Point, System.Drawing">
<value>278, 19</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>76, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>水平视野 (米)</value>
</data>
<data name="label7.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label7.Text" xml:space="preserve">
<value>水平视角</value>
</data>
<data name="label8.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label8.Text" xml:space="preserve">
<value>垂直视角</value>
</data>
<data name="label10.Location" type="System.Drawing.Point, System.Drawing">
<value>278, 46</value>
</data>
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
<value>76, 13</value>
</data>
<data name="label10.Text" xml:space="preserve">
<value>垂直视野 (米)</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>像素宽度</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label14.Text" xml:space="preserve">
<value>像素高度</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>传感器高度</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>传感器宽度</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>前后重叠</value>
</data>
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label15.Text" xml:space="preserve">
<value>两侧重叠</value>
</data>
<data name="CHK_camdirection.Size" type="System.Drawing.Size, System.Drawing">
<value>98, 17</value>
</data>
<data name="CHK_camdirection.Text" xml:space="preserve">
<value>相机顶部朝前</value>
</data>
<data name="BUT_save.Text" xml:space="preserve">
<value>保存</value>
</data>
</root>

View File

@ -131,6 +131,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{}
@ -329,7 +364,8 @@ namespace ArdupilotMega
CIRCLE = 7,
POSITION = 8,
LAND = 9, // AUTO control
OF_LOITER = 10
OF_LOITER = 10,
APPROACH = 11
}
public enum ac2ch7modes

View File

@ -80,6 +80,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; }
@ -529,6 +531,9 @@ namespace ArdupilotMega
case (byte)(100 + Common.ac2modes.LAND):
mode = "Land";
break;
case (byte)(100 + Common.ac2modes.APPROACH):
mode = "APPROACH";
break;
case (byte)(100 + Common.ac2modes.POSITION):
mode = "Position";
break;

View File

@ -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();

View File

@ -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();

View File

@ -1,230 +1,230 @@
namespace ArdupilotMega.GCSViews.ConfigurationView
{
partial class ConfigBatteryMonitoring
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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;
}
}

View File

@ -1,496 +1,178 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="tabRadioIn.Text" xml:space="preserve">
<value>遥控输入</value>
</data>
<data name="tabModes.Text" xml:space="preserve">
<value>模式</value>
</data>
<data name="tabHardware.Text" xml:space="preserve">
<value>硬件</value>
</data>
<data name="tabBattery.Text" xml:space="preserve">
<value>电池</value>
</data>
<data name="tabHeli.Text" xml:space="preserve">
<value>AC2 直升机</value>
</data>
<data name="groupBoxElevons.Text" xml:space="preserve">
<value>上降副翼 (Elevon) 配置</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch2rev.Text" xml:space="preserve">
<value>Elevons CH2 逆转</value>
</data>
<data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
<value>91, 17</value>
</data>
<data name="CHK_elevonrev.Text" xml:space="preserve">
<value>Elevons 逆转</value>
</data>
<data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
<value>Elevons CH1 逆转</value>
</data>
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch3.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch4.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch2.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch1.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
<value>校准遥控</value>
</data>
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple6.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple5.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple4.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple3.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple2.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple1.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label14.Text" xml:space="preserve">
<value>当前 PWM:</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>当前模式:</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>飞行模式 6</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>飞行模式 5</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>飞行模式 4</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>飞行模式 3</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>飞行模式 2</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>飞行模式 1</value>
</data>
<data name="BUT_SaveModes.Text" xml:space="preserve">
<value>保存模式</value>
</data>
<data name="label27.Text" xml:space="preserve">
<value>十进制, 2° 3' W 就是 -2.3</value>
</data>
<data name="CHK_enableoptflow.Text" xml:space="preserve">
<value>启用光流</value>
</data>
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="linkLabelmagdec.Text" xml:space="preserve">
<value>磁偏角网站</value>
</data>
<data name="label100.Text" xml:space="preserve">
<value>磁偏角</value>
</data>
<data name="CHK_enableairspeed.Text" xml:space="preserve">
<value>启用空速计</value>
</data>
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>启用声纳</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>启用罗盘</value>
</data>
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label31.Text" xml:space="preserve">
<value>输入电压:</value>
</data>
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
<value>94, 13</value>
</data>
<data name="label32.Text" xml:space="preserve">
<value>测量的电池电压:</value>
</data>
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label33.Text" xml:space="preserve">
<value>电池电压:</value>
</data>
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label34.Text" xml:space="preserve">
<value>分 压 比:</value>
</data>
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
<value>63, 13</value>
</data>
<data name="label35.Text" xml:space="preserve">
<value>安培/伏特:</value>
</data>
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 18</value>
</data>
<data name="label47.Text" xml:space="preserve">
<value>传感器</value>
</data>
<data name="textBox3.Text" xml:space="preserve">
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label31.Text" xml:space="preserve">
<value>输入电压:</value>
</data>
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
<value>94, 13</value>
</data>
<data name="label32.Text" xml:space="preserve">
<value>测量的电池电压:</value>
</data>
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label33.Text" xml:space="preserve">
<value>电池电压:</value>
</data>
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label34.Text" xml:space="preserve">
<value>分 压 比:</value>
</data>
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
<value>63, 13</value>
</data>
<data name="label35.Text" xml:space="preserve">
<value>安培/伏特:</value>
</data>
<data name="groupBox4.Text" xml:space="preserve">
<value>校准</value>
</data>
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 18</value>
</data>
<data name="label47.Text" xml:space="preserve">
<value>传感器</value>
</data>
<data name="textBox3.Text" xml:space="preserve">
<value>电压传感器校准:
1. 测量APM输入电压输入到下方的文本框中
2. 测量电池电压,输入到下方的文本框中
3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
</data>
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label29.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 13</value>
</data>
<data name="label30.Text" xml:space="preserve">
<value>监控器</value>
</data>
<data name="label28.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 13</value>
</data>
<data name="label28.Text" xml:space="preserve">
<value>设置水平面的默认加速度计偏移</value>
</data>
<data name="label16.Size" type="System.Drawing.Size, System.Drawing">
<value>261, 13</value>
</data>
<data name="label16.Text" xml:space="preserve">
<value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
</data>
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
<value>93, 13</value>
</data>
<data name="label15.Text" xml:space="preserve">
<value>机架设置 (+ 或 x)</value>
</data>
<data name="BUT_levelac2.Text" xml:space="preserve">
<value>找平</value>
</data>
<data name="BUT_HS4save.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="BUT_swash_manual.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label46.Text" xml:space="preserve">
<value>感度</value>
</data>
<data name="label45.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label45.Text" xml:space="preserve">
<value>启用</value>
</data>
<data name="label44.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label44.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label43.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label43.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label42.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 13</value>
</data>
<data name="label42.Text" xml:space="preserve">
<value>方向舵</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>最大</value>
</data>
<data name="label40.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label40.Text" xml:space="preserve">
<value>最小</value>
</data>
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label41.Text" xml:space="preserve">
<value>最低</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>最高</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>0度</value>
</data>
<data name="label39.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label39.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label38.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label38.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label37.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label37.Text" xml:space="preserve">
<value>位置</value>
</data>
<data name="label36.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label36.Text" xml:space="preserve">
<value>舵机</value>
</data>
<data name="label26.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label26.Text" xml:space="preserve">
<value>最大俯仰</value>
</data>
<data name="label25.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label25.Text" xml:space="preserve">
<value>最大侧倾</value>
</data>
<data name="label23.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label23.Text" xml:space="preserve">
<value>舵机行程</value>
</data>
<data name="label22.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label22.Text" xml:space="preserve">
<value>斜盘水平微调</value>
</data>
<data name="label17.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label17.Text" xml:space="preserve">
<value>斜盘舵机位置</value>
</data>
<data name="tabReset.Text" xml:space="preserve">
<value>重置</value>
</data>
<data name="BUT_reset.Text" xml:space="preserve">
<value>重置 APM 为默认设置</value>
</data>
<data name="$this.Text" xml:space="preserve">
<value>APM设置</value>
</data>
3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
</data>
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label29.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 13</value>
</data>
<data name="label30.Text" xml:space="preserve">
<value>监控器</value>
</data>
</root>

View File

@ -1,318 +1,318 @@
namespace ArdupilotMega.GCSViews.ConfigurationView
{
partial class ConfigFlightModes
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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;
}
}

View File

@ -1,496 +1,208 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="tabRadioIn.Text" xml:space="preserve">
<value>遥控输入</value>
</data>
<data name="tabModes.Text" xml:space="preserve">
<value>模式</value>
</data>
<data name="tabHardware.Text" xml:space="preserve">
<value>硬件</value>
</data>
<data name="tabBattery.Text" xml:space="preserve">
<value>电池</value>
</data>
<data name="tabHeli.Text" xml:space="preserve">
<value>AC2 直升机</value>
</data>
<data name="groupBoxElevons.Text" xml:space="preserve">
<value>上降副翼 (Elevon) 配置</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch2rev.Text" xml:space="preserve">
<value>Elevons CH2 逆转</value>
</data>
<data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
<value>91, 17</value>
</data>
<data name="CHK_elevonrev.Text" xml:space="preserve">
<value>Elevons 逆转</value>
</data>
<data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
<value>Elevons CH1 逆转</value>
</data>
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch3.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch4.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch2.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch1.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
<value>校准遥控</value>
</data>
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple6.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple5.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple4.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple3.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple2.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple1.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label14.Text" xml:space="preserve">
<value>当前 PWM:</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>当前模式:</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>飞行模式 6</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>飞行模式 5</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>飞行模式 4</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>飞行模式 3</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>飞行模式 2</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>飞行模式 1</value>
</data>
<data name="BUT_SaveModes.Text" xml:space="preserve">
<value>保存模式</value>
</data>
<data name="label27.Text" xml:space="preserve">
<value>十进制, 2° 3' W 就是 -2.3</value>
</data>
<data name="CHK_enableoptflow.Text" xml:space="preserve">
<value>启用光流</value>
</data>
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="linkLabelmagdec.Text" xml:space="preserve">
<value>磁偏角网站</value>
</data>
<data name="label100.Text" xml:space="preserve">
<value>磁偏角</value>
</data>
<data name="CHK_enableairspeed.Text" xml:space="preserve">
<value>启用空速计</value>
</data>
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>启用声纳</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>启用罗盘</value>
</data>
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label31.Text" xml:space="preserve">
<value>输入电压:</value>
</data>
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
<value>94, 13</value>
</data>
<data name="label32.Text" xml:space="preserve">
<value>测量的电池电压:</value>
</data>
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label33.Text" xml:space="preserve">
<value>电池电压:</value>
</data>
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label34.Text" xml:space="preserve">
<value>分 压 比:</value>
</data>
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
<value>63, 13</value>
</data>
<data name="label35.Text" xml:space="preserve">
<value>安培/伏特:</value>
</data>
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 18</value>
</data>
<data name="label47.Text" xml:space="preserve">
<value>传感器</value>
</data>
<data name="textBox3.Text" xml:space="preserve">
<value>电压传感器校准:
1. 测量APM输入电压输入到下方的文本框中
2. 测量电池电压,输入到下方的文本框中
3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
</data>
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label29.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 13</value>
</data>
<data name="label30.Text" xml:space="preserve">
<value>监控器</value>
</data>
<data name="label28.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 13</value>
</data>
<data name="label28.Text" xml:space="preserve">
<value>设置水平面的默认加速度计偏移</value>
</data>
<data name="label16.Size" type="System.Drawing.Size, System.Drawing">
<value>261, 13</value>
</data>
<data name="label16.Text" xml:space="preserve">
<value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
</data>
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
<value>93, 13</value>
</data>
<data name="label15.Text" xml:space="preserve">
<value>机架设置 (+ 或 x)</value>
</data>
<data name="BUT_levelac2.Text" xml:space="preserve">
<value>找平</value>
</data>
<data name="BUT_HS4save.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="BUT_swash_manual.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label46.Text" xml:space="preserve">
<value>感度</value>
</data>
<data name="label45.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label45.Text" xml:space="preserve">
<value>启用</value>
</data>
<data name="label44.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label44.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label43.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label43.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label42.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 13</value>
</data>
<data name="label42.Text" xml:space="preserve">
<value>方向舵</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>最大</value>
</data>
<data name="label40.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label40.Text" xml:space="preserve">
<value>最小</value>
</data>
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label41.Text" xml:space="preserve">
<value>最低</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>最高</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>0度</value>
</data>
<data name="label39.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label39.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label38.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label38.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label37.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label37.Text" xml:space="preserve">
<value>位置</value>
</data>
<data name="label36.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label36.Text" xml:space="preserve">
<value>舵机</value>
</data>
<data name="label26.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label26.Text" xml:space="preserve">
<value>最大俯仰</value>
</data>
<data name="label25.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label25.Text" xml:space="preserve">
<value>最大侧倾</value>
</data>
<data name="label23.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label23.Text" xml:space="preserve">
<value>舵机行程</value>
</data>
<data name="label22.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label22.Text" xml:space="preserve">
<value>斜盘水平微调</value>
</data>
<data name="label17.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label17.Text" xml:space="preserve">
<value>斜盘舵机位置</value>
</data>
<data name="tabReset.Text" xml:space="preserve">
<value>重置</value>
</data>
<data name="BUT_reset.Text" xml:space="preserve">
<value>重置 APM 为默认设置</value>
</data>
<data name="$this.Text" xml:space="preserve">
<value>APM设置</value>
</data>
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple6.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple5.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple4.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple3.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple2.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple1.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label14.Text" xml:space="preserve">
<value>当前 PWM:</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>当前模式:</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>飞行模式 6</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>飞行模式 5</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>飞行模式 4</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>飞行模式 3</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>飞行模式 2</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>飞行模式 1</value>
</data>
<data name="BUT_SaveModes.Text" xml:space="preserve">
<value>保存模式</value>
</data>
</root>

View File

@ -1,212 +1,222 @@
namespace ArdupilotMega.GCSViews.ConfigurationView
{
partial class ConfigHardwareOptions
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
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;
}
}

View File

@ -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"); }
}
}
}

View File

@ -1,496 +1,151 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="tabRadioIn.Text" xml:space="preserve">
<value>遥控输入</value>
</data>
<data name="tabModes.Text" xml:space="preserve">
<value>模式</value>
</data>
<data name="tabHardware.Text" xml:space="preserve">
<value>硬件</value>
</data>
<data name="tabBattery.Text" xml:space="preserve">
<value>电池</value>
</data>
<data name="tabHeli.Text" xml:space="preserve">
<value>AC2 直升机</value>
</data>
<data name="groupBoxElevons.Text" xml:space="preserve">
<value>上降副翼 (Elevon) 配置</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch2rev.Text" xml:space="preserve">
<value>Elevons CH2 逆转</value>
</data>
<data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
<value>91, 17</value>
</data>
<data name="CHK_elevonrev.Text" xml:space="preserve">
<value>Elevons 逆转</value>
</data>
<data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
<value>Elevons CH1 逆转</value>
</data>
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch3.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch4.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch2.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch1.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
<value>校准遥控</value>
</data>
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple6.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple5.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple4.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple3.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple2.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple1.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label14.Text" xml:space="preserve">
<value>当前 PWM:</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>当前模式:</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>飞行模式 6</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>飞行模式 5</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>飞行模式 4</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>飞行模式 3</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>飞行模式 2</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>飞行模式 1</value>
</data>
<data name="BUT_SaveModes.Text" xml:space="preserve">
<value>保存模式</value>
</data>
<data name="label27.Text" xml:space="preserve">
<value>十进制, 2° 3' W 就是 -2.3</value>
</data>
<data name="CHK_enableoptflow.Text" xml:space="preserve">
<value>启用光流</value>
</data>
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="linkLabelmagdec.Text" xml:space="preserve">
<value>磁偏角网站</value>
</data>
<data name="label100.Text" xml:space="preserve">
<value>磁偏角</value>
</data>
<data name="CHK_enableairspeed.Text" xml:space="preserve">
<value>启用空速计</value>
</data>
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>启用声纳</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>启用罗盘</value>
</data>
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label31.Text" xml:space="preserve">
<value>输入电压:</value>
</data>
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
<value>94, 13</value>
</data>
<data name="label32.Text" xml:space="preserve">
<value>测量的电池电压:</value>
</data>
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label33.Text" xml:space="preserve">
<value>电池电压:</value>
</data>
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label34.Text" xml:space="preserve">
<value>分 压 比:</value>
</data>
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
<value>63, 13</value>
</data>
<data name="label35.Text" xml:space="preserve">
<value>安培/伏特:</value>
</data>
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 18</value>
</data>
<data name="label47.Text" xml:space="preserve">
<value>传感器</value>
</data>
<data name="textBox3.Text" xml:space="preserve">
<value>电压传感器校准:
1. 测量APM输入电压输入到下方的文本框中
2. 测量电池电压,输入到下方的文本框中
3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
</data>
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label29.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 13</value>
</data>
<data name="label30.Text" xml:space="preserve">
<value>监控器</value>
</data>
<data name="label28.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 13</value>
</data>
<data name="label28.Text" xml:space="preserve">
<value>设置水平面的默认加速度计偏移</value>
</data>
<data name="label16.Size" type="System.Drawing.Size, System.Drawing">
<value>261, 13</value>
</data>
<data name="label16.Text" xml:space="preserve">
<value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
</data>
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
<value>93, 13</value>
</data>
<data name="label15.Text" xml:space="preserve">
<value>机架设置 (+ 或 x)</value>
</data>
<data name="BUT_levelac2.Text" xml:space="preserve">
<value>找平</value>
</data>
<data name="BUT_HS4save.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="BUT_swash_manual.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label46.Text" xml:space="preserve">
<value>感度</value>
</data>
<data name="label45.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label45.Text" xml:space="preserve">
<value>启用</value>
</data>
<data name="label44.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label44.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label43.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label43.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label42.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 13</value>
</data>
<data name="label42.Text" xml:space="preserve">
<value>方向舵</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>最大</value>
</data>
<data name="label40.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label40.Text" xml:space="preserve">
<value>最小</value>
</data>
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label41.Text" xml:space="preserve">
<value>最低</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>最高</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>0度</value>
</data>
<data name="label39.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label39.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label38.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label38.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label37.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label37.Text" xml:space="preserve">
<value>位置</value>
</data>
<data name="label36.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label36.Text" xml:space="preserve">
<value>舵机</value>
</data>
<data name="label26.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label26.Text" xml:space="preserve">
<value>最大俯仰</value>
</data>
<data name="label25.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label25.Text" xml:space="preserve">
<value>最大侧倾</value>
</data>
<data name="label23.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label23.Text" xml:space="preserve">
<value>舵机行程</value>
</data>
<data name="label22.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label22.Text" xml:space="preserve">
<value>斜盘水平微调</value>
</data>
<data name="label17.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label17.Text" xml:space="preserve">
<value>斜盘舵机位置</value>
</data>
<data name="tabReset.Text" xml:space="preserve">
<value>重置</value>
</data>
<data name="BUT_reset.Text" xml:space="preserve">
<value>重置 APM 为默认设置</value>
</data>
<data name="$this.Text" xml:space="preserve">
<value>APM设置</value>
</data>
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="BUT_MagCalibrationLive.Text" xml:space="preserve">
<value>现场校准</value>
</data>
<data name="label27.Text" xml:space="preserve">
<value>十进制, 2° 3' W 就是 -2.3</value>
</data>
<data name="CHK_enableoptflow.Text" xml:space="preserve">
<value>启用光流</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="linkLabelmagdec.Text" xml:space="preserve">
<value>磁偏角网站</value>
</data>
<data name="label100.Text" xml:space="preserve">
<value>磁偏角</value>
</data>
<data name="CHK_enableairspeed.Text" xml:space="preserve">
<value>启用空速计</value>
</data>
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>启用声纳</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>启用罗盘</value>
</data>
<data name="BUT_MagCalibrationLog.Text" xml:space="preserve">
<value>日志校准</value>
</data>
</root>

View File

@ -28,6 +28,7 @@
/// </summary>
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);

View File

@ -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);

View File

@ -117,19 +117,286 @@
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="BUT_compare.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Right</value>
</data>
<data name="BUT_compare.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="BUT_compare.Location" type="System.Drawing.Point, System.Drawing">
<value>341, 119</value>
</data>
<data name="BUT_compare.Size" type="System.Drawing.Size, System.Drawing">
<value>103, 19</value>
</data>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="BUT_compare.TabIndex" type="System.Int32, mscorlib">
<value>72</value>
</data>
<data name="BUT_compare.Text" xml:space="preserve">
<value>Compare Params</value>
</data>
<data name="&gt;&gt;BUT_compare.Name" xml:space="preserve">
<value>BUT_compare</value>
</data>
<data name="&gt;&gt;BUT_compare.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_compare.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_compare.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="BUT_rerequestparams.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Right</value>
</data>
<data name="BUT_rerequestparams.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_rerequestparams.Location" type="System.Drawing.Point, System.Drawing">
<value>341, 94</value>
</data>
<data name="BUT_rerequestparams.Size" type="System.Drawing.Size, System.Drawing">
<value>103, 19</value>
</data>
<data name="BUT_rerequestparams.TabIndex" type="System.Int32, mscorlib">
<value>67</value>
</data>
<data name="BUT_rerequestparams.Text" xml:space="preserve">
<value>Refresh Params</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Name" xml:space="preserve">
<value>BUT_rerequestparams</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="BUT_writePIDS.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Right</value>
</data>
<data name="BUT_writePIDS.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_writePIDS.Location" type="System.Drawing.Point, System.Drawing">
<value>341, 69</value>
</data>
<data name="BUT_writePIDS.Size" type="System.Drawing.Size, System.Drawing">
<value>103, 19</value>
</data>
<data name="BUT_writePIDS.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="BUT_writePIDS.Text" xml:space="preserve">
<value>Write Params</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Name" xml:space="preserve">
<value>BUT_writePIDS</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="BUT_save.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Right</value>
</data>
<data name="BUT_save.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_save.Location" type="System.Drawing.Point, System.Drawing">
<value>341, 35</value>
</data>
<data name="BUT_save.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="BUT_save.Size" type="System.Drawing.Size, System.Drawing">
<value>104, 19</value>
</data>
<data name="BUT_save.TabIndex" type="System.Int32, mscorlib">
<value>70</value>
</data>
<data name="BUT_save.Text" xml:space="preserve">
<value>Save</value>
</data>
<data name="&gt;&gt;BUT_save.Name" xml:space="preserve">
<value>BUT_save</value>
</data>
<data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_save.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="BUT_load.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Right</value>
</data>
<data name="BUT_load.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_load.Location" type="System.Drawing.Point, System.Drawing">
<value>341, 7</value>
</data>
<data name="BUT_load.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="BUT_load.Size" type="System.Drawing.Size, System.Drawing">
<value>104, 19</value>
</data>
<data name="BUT_load.TabIndex" type="System.Int32, mscorlib">
<value>71</value>
</data>
<data name="BUT_load.Text" xml:space="preserve">
<value>Load</value>
</data>
<data name="&gt;&gt;BUT_load.Name" xml:space="preserve">
<value>BUT_load</value>
</data>
<data name="&gt;&gt;BUT_load.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_load.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_load.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="Params.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Bottom, Left, Right</value>
</data>
<metadata name="Command.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="Command.HeaderText" xml:space="preserve">
<value>Command</value>
</data>
<data name="Command.Width" type="System.Int32, mscorlib">
<value>150</value>
</data>
<metadata name="Value.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="Value.HeaderText" xml:space="preserve">
<value>Value</value>
</data>
<data name="Value.Width" type="System.Int32, mscorlib">
<value>80</value>
</data>
<metadata name="Default.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="Default.HeaderText" xml:space="preserve">
<value>Default</value>
</data>
<data name="Default.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="mavScale.HeaderText" xml:space="preserve">
<value>mavScale</value>
</data>
<data name="mavScale.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<metadata name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="RawValue.HeaderText" xml:space="preserve">
<value>RawValue</value>
</data>
<data name="RawValue.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="Params.Location" type="System.Drawing.Point, System.Drawing">
<value>14, 3</value>
</data>
<data name="Params.RowHeadersWidth" type="System.Int32, mscorlib">
<value>150</value>
</data>
<data name="Params.Size" type="System.Drawing.Size, System.Drawing">
<value>321, 302</value>
</data>
<data name="Params.TabIndex" type="System.Int32, mscorlib">
<value>68</value>
</data>
<data name="&gt;&gt;Params.Name" xml:space="preserve">
<value>Params</value>
</data>
<data name="&gt;&gt;Params.Type" xml:space="preserve">
<value>System.Windows.Forms.DataGridView, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Params.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;Params.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
</metadata>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
<value>6, 13</value>
</data>
<data name="$this.Size" type="System.Drawing.Size, System.Drawing">
<value>460, 305</value>
</data>
<data name="&gt;&gt;Command.Name" xml:space="preserve">
<value>Command</value>
</data>
<data name="&gt;&gt;Command.Type" xml:space="preserve">
<value>System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Value.Name" xml:space="preserve">
<value>Value</value>
</data>
<data name="&gt;&gt;Value.Type" xml:space="preserve">
<value>System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Default.Name" xml:space="preserve">
<value>Default</value>
</data>
<data name="&gt;&gt;Default.Type" xml:space="preserve">
<value>System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;mavScale.Name" xml:space="preserve">
<value>mavScale</value>
</data>
<data name="&gt;&gt;mavScale.Type" xml:space="preserve">
<value>System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;RawValue.Name" xml:space="preserve">
<value>RawValue</value>
</data>
<data name="&gt;&gt;RawValue.Type" xml:space="preserve">
<value>System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;toolTip1.Name" xml:space="preserve">
<value>toolTip1</value>
</data>
<data name="&gt;&gt;toolTip1.Type" xml:space="preserve">
<value>System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;$this.Name" xml:space="preserve">
<value>ConfigRawParams</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
</root>

View File

@ -1,496 +1,244 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="tabRadioIn.Text" xml:space="preserve">
<value>遥控输入</value>
</data>
<data name="tabModes.Text" xml:space="preserve">
<value>模式</value>
</data>
<data name="tabHardware.Text" xml:space="preserve">
<value>硬件</value>
</data>
<data name="tabBattery.Text" xml:space="preserve">
<value>电池</value>
</data>
<data name="tabHeli.Text" xml:space="preserve">
<value>AC2 直升机</value>
</data>
<data name="groupBoxElevons.Text" xml:space="preserve">
<value>上降副翼 (Elevon) 配置</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch2rev.Text" xml:space="preserve">
<value>Elevons CH2 逆转</value>
</data>
<data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
<value>91, 17</value>
</data>
<data name="CHK_elevonrev.Text" xml:space="preserve">
<value>Elevons 逆转</value>
</data>
<data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
<value>115, 17</value>
</data>
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
<value>Elevons CH1 逆转</value>
</data>
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch3.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch4.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch2.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
<value>50, 17</value>
</data>
<data name="CHK_revch1.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
<value>校准遥控</value>
</data>
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple6.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple5.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple4.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple3.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple2.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
<value>74, 17</value>
</data>
<data name="CB_simple1.Text" xml:space="preserve">
<value>简单模式</value>
</data>
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label14.Text" xml:space="preserve">
<value>当前 PWM:</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>当前模式:</value>
</data>
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label6.Text" xml:space="preserve">
<value>飞行模式 6</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>飞行模式 5</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>飞行模式 4</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>飞行模式 3</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>飞行模式 2</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>飞行模式 1</value>
</data>
<data name="BUT_SaveModes.Text" xml:space="preserve">
<value>保存模式</value>
</data>
<data name="label27.Text" xml:space="preserve">
<value>十进制, 2° 3' W 就是 -2.3</value>
</data>
<data name="CHK_enableoptflow.Text" xml:space="preserve">
<value>启用光流</value>
</data>
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
<value>67, 13</value>
</data>
<data name="linkLabelmagdec.Text" xml:space="preserve">
<value>磁偏角网站</value>
</data>
<data name="label100.Text" xml:space="preserve">
<value>磁偏角</value>
</data>
<data name="CHK_enableairspeed.Text" xml:space="preserve">
<value>启用空速计</value>
</data>
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>启用声纳</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>启用罗盘</value>
</data>
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label31.Text" xml:space="preserve">
<value>输入电压:</value>
</data>
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
<value>94, 13</value>
</data>
<data name="label32.Text" xml:space="preserve">
<value>测量的电池电压:</value>
</data>
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
<value>58, 13</value>
</data>
<data name="label33.Text" xml:space="preserve">
<value>电池电压:</value>
</data>
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 13</value>
</data>
<data name="label34.Text" xml:space="preserve">
<value>分 压 比:</value>
</data>
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
<value>63, 13</value>
</data>
<data name="label35.Text" xml:space="preserve">
<value>安培/伏特:</value>
</data>
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 18</value>
</data>
<data name="label47.Text" xml:space="preserve">
<value>传感器</value>
</data>
<data name="textBox3.Text" xml:space="preserve">
<value>电压传感器校准:
1. 测量APM输入电压输入到下方的文本框中
2. 测量电池电压,输入到下方的文本框中
3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
</data>
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label29.Text" xml:space="preserve">
<value>容量</value>
</data>
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
<value>48, 13</value>
</data>
<data name="label30.Text" xml:space="preserve">
<value>监控器</value>
</data>
<data name="label28.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 13</value>
</data>
<data name="label28.Text" xml:space="preserve">
<value>设置水平面的默认加速度计偏移</value>
</data>
<data name="label16.Size" type="System.Drawing.Size, System.Drawing">
<value>261, 13</value>
</data>
<data name="label16.Text" xml:space="preserve">
<value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
</data>
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
<value>93, 13</value>
</data>
<data name="label15.Text" xml:space="preserve">
<value>机架设置 (+ 或 x)</value>
</data>
<data name="BUT_levelac2.Text" xml:space="preserve">
<value>找平</value>
</data>
<data name="BUT_HS4save.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="BUT_swash_manual.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label46.Text" xml:space="preserve">
<value>感度</value>
</data>
<data name="label45.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label45.Text" xml:space="preserve">
<value>启用</value>
</data>
<data name="label44.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label44.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label43.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label43.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label42.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 13</value>
</data>
<data name="label42.Text" xml:space="preserve">
<value>方向舵</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>最大</value>
</data>
<data name="label40.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label40.Text" xml:space="preserve">
<value>最小</value>
</data>
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label41.Text" xml:space="preserve">
<value>最低</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>最高</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>0度</value>
</data>
<data name="label39.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label39.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label38.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label38.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label37.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label37.Text" xml:space="preserve">
<value>位置</value>
</data>
<data name="label36.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label36.Text" xml:space="preserve">
<value>舵机</value>
</data>
<data name="label26.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label26.Text" xml:space="preserve">
<value>最大俯仰</value>
</data>
<data name="label25.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label25.Text" xml:space="preserve">
<value>最大侧倾</value>
</data>
<data name="label23.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label23.Text" xml:space="preserve">
<value>舵机行程</value>
</data>
<data name="label22.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label22.Text" xml:space="preserve">
<value>斜盘水平微调</value>
</data>
<data name="label17.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label17.Text" xml:space="preserve">
<value>斜盘舵机位置</value>
</data>
<data name="tabReset.Text" xml:space="preserve">
<value>重置</value>
</data>
<data name="BUT_reset.Text" xml:space="preserve">
<value>重置 APM 为默认设置</value>
</data>
<data name="$this.Text" xml:space="preserve">
<value>APM设置</value>
</data>
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<data name="groupBox5.Text" xml:space="preserve">
<value>斜盘类型</value>
</data>
<data name="BUT_swash_manual.Text" xml:space="preserve">
<value>手动</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label41.Text" xml:space="preserve">
<value>最低</value>
</data>
<data name="groupBox3.Text" xml:space="preserve">
<value>陀螺仪</value>
</data>
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label46.Text" xml:space="preserve">
<value>感度</value>
</data>
<data name="label45.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label45.Text" xml:space="preserve">
<value>启用</value>
</data>
<data name="BUT_HS4save.Text" xml:space="preserve">
<value>手动</value>
</data>
<data name="label21.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label21.Text" xml:space="preserve">
<value>最高</value>
</data>
<data name="BUT_0collective.Text" xml:space="preserve">
<value>0度</value>
</data>
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label24.Text" xml:space="preserve">
<value>最大</value>
</data>
<data name="label40.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label40.Text" xml:space="preserve">
<value>最小</value>
</data>
<data name="label39.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label39.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label38.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label38.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label37.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label37.Text" xml:space="preserve">
<value>位置</value>
</data>
<data name="label36.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label36.Text" xml:space="preserve">
<value>舵机</value>
</data>
<data name="label26.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label26.Text" xml:space="preserve">
<value>最大俯仰</value>
</data>
<data name="label25.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label25.Text" xml:space="preserve">
<value>最大侧倾</value>
</data>
<data name="label23.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label23.Text" xml:space="preserve">
<value>舵机行程</value>
</data>
<data name="label22.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label22.Text" xml:space="preserve">
<value>斜盘水平微调</value>
</data>
<data name="label17.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value>
</data>
<data name="label17.Text" xml:space="preserve">
<value>斜盘舵机位置</value>
</data>
<data name="label44.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label44.Text" xml:space="preserve">
<value>微调</value>
</data>
<data name="label43.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label43.Text" xml:space="preserve">
<value>逆转</value>
</data>
<data name="label42.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 13</value>
</data>
<data name="label42.Text" xml:space="preserve">
<value>方向舵</value>
</data>
</root>

View File

@ -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;
}
}

View File

@ -208,7 +208,7 @@
<value>hud1</value>
</data>
<data name="&gt;&gt;hud1.Type" xml:space="preserve">
<value>hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>hud.HUD, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;hud1.Parent" xml:space="preserve">
<value>SubMainLeft.Panel1</value>
@ -247,7 +247,7 @@
<value>BUT_script</value>
</data>
<data name="&gt;&gt;BUT_script.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_script.Parent" xml:space="preserve">
<value>tabActions</value>
@ -280,7 +280,7 @@
<value>BUT_joystick</value>
</data>
<data name="&gt;&gt;BUT_joystick.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_joystick.Parent" xml:space="preserve">
<value>tabActions</value>
@ -310,7 +310,7 @@
<value>BUT_quickmanual</value>
</data>
<data name="&gt;&gt;BUT_quickmanual.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_quickmanual.Parent" xml:space="preserve">
<value>tabActions</value>
@ -340,7 +340,7 @@
<value>BUT_quickrtl</value>
</data>
<data name="&gt;&gt;BUT_quickrtl.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_quickrtl.Parent" xml:space="preserve">
<value>tabActions</value>
@ -370,7 +370,7 @@
<value>BUT_quickauto</value>
</data>
<data name="&gt;&gt;BUT_quickauto.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_quickauto.Parent" xml:space="preserve">
<value>tabActions</value>
@ -424,7 +424,7 @@
<value>BUT_setwp</value>
</data>
<data name="&gt;&gt;BUT_setwp.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_setwp.Parent" xml:space="preserve">
<value>tabActions</value>
@ -475,7 +475,7 @@
<value>BUT_setmode</value>
</data>
<data name="&gt;&gt;BUT_setmode.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_setmode.Parent" xml:space="preserve">
<value>tabActions</value>
@ -505,7 +505,7 @@
<value>BUT_clear_track</value>
</data>
<data name="&gt;&gt;BUT_clear_track.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_clear_track.Parent" xml:space="preserve">
<value>tabActions</value>
@ -556,7 +556,7 @@
<value>BUT_Homealt</value>
</data>
<data name="&gt;&gt;BUT_Homealt.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_Homealt.Parent" xml:space="preserve">
<value>tabActions</value>
@ -586,7 +586,7 @@
<value>BUT_RAWSensor</value>
</data>
<data name="&gt;&gt;BUT_RAWSensor.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_RAWSensor.Parent" xml:space="preserve">
<value>tabActions</value>
@ -616,7 +616,7 @@
<value>BUTrestartmission</value>
</data>
<data name="&gt;&gt;BUTrestartmission.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUTrestartmission.Parent" xml:space="preserve">
<value>tabActions</value>
@ -646,7 +646,7 @@
<value>BUTactiondo</value>
</data>
<data name="&gt;&gt;BUTactiondo.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUTactiondo.Parent" xml:space="preserve">
<value>tabActions</value>
@ -700,7 +700,7 @@
<value>Gvspeed</value>
</data>
<data name="&gt;&gt;Gvspeed.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gvspeed.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -730,7 +730,7 @@
<value>Gheading</value>
</data>
<data name="&gt;&gt;Gheading.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gheading.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -760,7 +760,7 @@
<value>Galt</value>
</data>
<data name="&gt;&gt;Galt.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Galt.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -793,7 +793,7 @@
<value>Gspeed</value>
</data>
<data name="&gt;&gt;Gspeed.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gspeed.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -874,7 +874,7 @@
<value>lbl_logpercent</value>
</data>
<data name="&gt;&gt;lbl_logpercent.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_logpercent.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -925,7 +925,7 @@
<value>BUT_log2kml</value>
</data>
<data name="&gt;&gt;BUT_log2kml.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_log2kml.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -976,7 +976,7 @@
<value>BUT_playlog</value>
</data>
<data name="&gt;&gt;BUT_playlog.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_playlog.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -1003,7 +1003,7 @@
<value>BUT_loadtelem</value>
</data>
<data name="&gt;&gt;BUT_loadtelem.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_loadtelem.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -1167,6 +1167,72 @@
<data name="&gt;&gt;splitContainer1.Panel1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_hdop.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="lbl_hdop.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_hdop.Location" type="System.Drawing.Point, System.Drawing">
<value>-1, 390</value>
</data>
<data name="lbl_hdop.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 12</value>
</data>
<data name="lbl_hdop.TabIndex" type="System.Int32, mscorlib">
<value>70</value>
</data>
<data name="lbl_hdop.Text" xml:space="preserve">
<value>hdop: 0</value>
</data>
<data name="lbl_hdop.ToolTip" xml:space="preserve">
<value>gps hdop</value>
</data>
<data name="&gt;&gt;lbl_hdop.Name" xml:space="preserve">
<value>lbl_hdop</value>
</data>
<data name="&gt;&gt;lbl_hdop.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_hdop.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_hdop.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_sats.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="lbl_sats.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_sats.Location" type="System.Drawing.Point, System.Drawing">
<value>-1, 408</value>
</data>
<data name="lbl_sats.Size" type="System.Drawing.Size, System.Drawing">
<value>40, 12</value>
</data>
<data name="lbl_sats.TabIndex" type="System.Int32, mscorlib">
<value>71</value>
</data>
<data name="lbl_sats.Text" xml:space="preserve">
<value>Sats: 0</value>
</data>
<data name="lbl_sats.ToolTip" xml:space="preserve">
<value>Satalite Count</value>
</data>
<data name="&gt;&gt;lbl_sats.Name" xml:space="preserve">
<value>lbl_sats</value>
</data>
<data name="&gt;&gt;lbl_sats.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_sats.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_sats.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="lbl_winddir.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
@ -1189,13 +1255,13 @@
<value>lbl_winddir</value>
</data>
<data name="&gt;&gt;lbl_winddir.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_winddir.ZOrder" xml:space="preserve">
<value>0</value>
<value>2</value>
</data>
<data name="lbl_windvel.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1219,13 +1285,13 @@
<value>lbl_windvel</value>
</data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_windvel.ZOrder" xml:space="preserve">
<value>1</value>
<value>3</value>
</data>
<data name="gMapControl1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
@ -1391,13 +1457,13 @@
<value>gMapControl1</value>
</data>
<data name="&gt;&gt;gMapControl1.Type" xml:space="preserve">
<value>ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;gMapControl1.ZOrder" xml:space="preserve">
<value>2</value>
<value>4</value>
</data>
<data name="&gt;&gt;splitContainer1.Panel2.Name" xml:space="preserve">
<value>splitContainer1.Panel2</value>
@ -1454,7 +1520,7 @@
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
@ -1511,7 +1577,7 @@
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
@ -1541,7 +1607,7 @@
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
@ -1571,7 +1637,7 @@
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
@ -1772,7 +1838,7 @@
<value>label6</value>
</data>
<data name="&gt;&gt;label6.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;label6.Parent" xml:space="preserve">
<value>$this</value>
@ -1850,6 +1916,6 @@
<value>FlightData</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
</data>
</root>

View File

@ -2,14 +2,14 @@
<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
<Product Id="*" Name="APM Planner" Language="1033" Version="1.1.64" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<Product Id="*" Name="APM Planner" Language="1033" Version="1.1.68" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<UpgradeVersion OnlyDetect="yes" Minimum="1.1.64" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
<UpgradeVersion OnlyDetect="no" Maximum="1.1.64" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
<UpgradeVersion OnlyDetect="yes" Minimum="1.1.68" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
<UpgradeVersion OnlyDetect="no" Maximum="1.1.68" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
</Upgrade>
<InstallExecuteSequence>
@ -31,224 +31,227 @@
<Permission User="Everyone" GenericAll="yes" />
</CreateFolder>
</Component>
<Component Id="_comp1" Guid="dba8d621-643a-42b5-a947-bf317799d98f">
<File Id="_2" Source="..\bin\release\AeroSimRCAPMHil.zip" />
<File Id="_3" Source="..\bin\release\alglibnet2.dll" />
<File Id="_4" Source="..\bin\release\ArduCopter-sitl.exe" />
<File Id="_5" Source="..\bin\release\arducopter-xplane.zip" />
<File Id="_6" Source="..\bin\release\ArduCopter.exe" />
<File Id="_7" Source="..\bin\release\ArduinoCPP.exe" />
<File Id="_8" Source="..\bin\release\ArduinoCPP.exe.config" />
<File Id="_9" Source="..\bin\release\ArduinoCPP.pdb" />
<File Id="_10" Source="..\bin\release\ArdupilotMegaPlanner.exe" />
<File Id="_11" Source="..\bin\release\ArdupilotMegaPlanner.exe.config" />
<File Id="_12" Source="..\bin\release\ArdupilotMegaPlanner.pdb" />
<File Id="_13" Source="..\bin\release\ArduPlane-sitl.exe" />
<File Id="_14" Source="..\bin\release\ArduPlane.exe" />
<File Id="_15" Source="..\bin\release\block_plane_0.dae" />
<File Id="_16" Source="..\bin\release\BSE.Windows.Forms.dll" />
<File Id="_17" Source="..\bin\release\Core.dll" />
<File Id="_18" Source="..\bin\release\cygwin1.dll" />
<File Id="_19" Source="..\bin\release\dataflashlog.xml" />
<File Id="_20" Source="..\bin\release\DirectShowLib-2005.dll" />
<File Id="_21" Source="..\bin\release\eeprom.bin" />
<File Id="_22" Source="..\bin\release\GMap.NET.Core.dll" />
<File Id="_23" Source="..\bin\release\GMap.NET.WindowsForms.dll" />
<File Id="_24" Source="..\bin\release\hud.html" />
<File Id="_25" Source="..\bin\release\ICSharpCode.SharpZipLib.dll" />
<File Id="_26" Source="..\bin\release\Ionic.Zip.Reduced.dll" />
<File Id="_27" Source="..\bin\release\IronPython.dll" />
<File Id="_28" Source="..\bin\release\IronPython.Modules.dll" />
<File Id="_29" Source="..\bin\release\JSBSim.exe" />
<File Id="_30" Source="..\bin\release\KMLib.dll" />
<File Id="_31" Source="..\bin\release\log4net.dll" />
<File Id="_32" Source="..\bin\release\mavcmd.xml" />
<File Id="_33" Source="..\bin\release\MAVLink.xml" />
<File Id="_34" Source="..\bin\release\MetaDataExtractor.dll" />
<File Id="_35" Source="..\bin\release\Microsoft.DirectX.DirectInput.dll" />
<File Id="_36" Source="..\bin\release\Microsoft.DirectX.dll" />
<File Id="_37" Source="..\bin\release\Microsoft.Dynamic.dll" />
<File Id="_38" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
<File Id="_39" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
<File Id="_40" Source="..\bin\release\Microsoft.Scripting.dll" />
<File Id="_41" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
<File Id="_42" Source="..\bin\release\netDxf.dll" />
<File Id="_43" Source="..\bin\release\OpenTK.dll" />
<File Id="_44" Source="..\bin\release\OpenTK.GLControl.dll" />
<File Id="_45" Source="..\bin\release\quadhil.xml" />
<File Id="_46" Source="..\bin\release\serialsent.raw" />
<File Id="_47" Source="..\bin\release\SharpKml.dll" />
<File Id="_48" Source="..\bin\release\System.Data.SQLite.dll" />
<File Id="_49" Source="..\bin\release\System.Speech.dll" />
<File Id="_50" Source="..\bin\release\Updater.exe" />
<File Id="_51" Source="..\bin\release\Updater.exe.config" />
<File Id="_52" Source="..\bin\release\Updater.pdb" />
<File Id="_53" Source="..\bin\release\version.exe" />
<File Id="_54" Source="..\bin\release\version.txt" />
<File Id="_55" Source="..\bin\release\ZedGraph.dll" />
<Component Id="_comp1" Guid="5644ef2a-b056-468e-8dc6-7baa930a46e2">
<File Id="_2" Source="..\bin\release\aerosim3.91.txt" />
<File Id="_3" Source="..\bin\release\AeroSimRCAPMHil.zip" />
<File Id="_4" Source="..\bin\release\alglibnet2.dll" />
<File Id="_5" Source="..\bin\release\ArduCopter-sitl.exe" />
<File Id="_6" Source="..\bin\release\arducopter-xplane.zip" />
<File Id="_7" Source="..\bin\release\ArduCopter.exe" />
<File Id="_8" Source="..\bin\release\ArduCopterConfig.xml" />
<File Id="_9" Source="..\bin\release\ArduinoCPP.exe" />
<File Id="_10" Source="..\bin\release\ArduinoCPP.exe.config" />
<File Id="_11" Source="..\bin\release\ArduinoCPP.pdb" />
<File Id="_12" Source="..\bin\release\ArdupilotMegaPlanner.exe" />
<File Id="_13" Source="..\bin\release\ArdupilotMegaPlanner.exe.config" />
<File Id="_14" Source="..\bin\release\ArdupilotMegaPlanner.pdb" />
<File Id="_15" Source="..\bin\release\ArduPlane-sitl.exe" />
<File Id="_16" Source="..\bin\release\ArduPlane.exe" />
<File Id="_17" Source="..\bin\release\block_plane_0.dae" />
<File Id="_18" Source="..\bin\release\BSE.Windows.Forms.dll" />
<File Id="_19" Source="..\bin\release\Core.dll" />
<File Id="_20" Source="..\bin\release\cygwin1.dll" />
<File Id="_21" Source="..\bin\release\dataflashlog.xml" />
<File Id="_22" Source="..\bin\release\DirectShowLib-2005.dll" />
<File Id="_23" Source="..\bin\release\eeprom.bin" />
<File Id="_24" Source="..\bin\release\GMap.NET.Core.dll" />
<File Id="_25" Source="..\bin\release\GMap.NET.WindowsForms.dll" />
<File Id="_26" Source="..\bin\release\hud.html" />
<File Id="_27" Source="..\bin\release\ICSharpCode.SharpZipLib.dll" />
<File Id="_28" Source="..\bin\release\Ionic.Zip.Reduced.dll" />
<File Id="_29" Source="..\bin\release\IronPython.dll" />
<File Id="_30" Source="..\bin\release\IronPython.Modules.dll" />
<File Id="_31" Source="..\bin\release\JSBSim.exe" />
<File Id="_32" Source="..\bin\release\KMLib.dll" />
<File Id="_33" Source="..\bin\release\log4net.dll" />
<File Id="_34" Source="..\bin\release\mavcmd.xml" />
<File Id="_35" Source="..\bin\release\MAVLink.xml" />
<File Id="_36" Source="..\bin\release\MetaDataExtractor.dll" />
<File Id="_37" Source="..\bin\release\Microsoft.DirectX.DirectInput.dll" />
<File Id="_38" Source="..\bin\release\Microsoft.DirectX.dll" />
<File Id="_39" Source="..\bin\release\Microsoft.Dynamic.dll" />
<File Id="_40" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
<File Id="_41" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
<File Id="_42" Source="..\bin\release\Microsoft.Scripting.dll" />
<File Id="_43" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
<File Id="_44" Source="..\bin\release\netDxf.dll" />
<File Id="_45" Source="..\bin\release\OpenTK.dll" />
<File Id="_46" Source="..\bin\release\OpenTK.GLControl.dll" />
<File Id="_47" Source="..\bin\release\quadhil.xml" />
<File Id="_48" Source="..\bin\release\serialsent.raw" />
<File Id="_49" Source="..\bin\release\SharpKml.dll" />
<File Id="_50" Source="..\bin\release\System.Data.SQLite.dll" />
<File Id="_51" Source="..\bin\release\System.Speech.dll" />
<File Id="_52" Source="..\bin\release\Updater.exe" />
<File Id="_53" Source="..\bin\release\Updater.exe.config" />
<File Id="_54" Source="..\bin\release\Updater.pdb" />
<File Id="_55" Source="..\bin\release\version.exe" />
<File Id="_56" Source="..\bin\release\version.txt" />
<File Id="_57" Source="..\bin\release\ZedGraph.dll" />
</Component>
<Directory Id="aircraft55" Name="aircraft">
<Component Id="_comp56" Guid="45b138a8-2f48-4508-9edc-e6688532247a">
<File Id="_57" Source="..\bin\release\aircraft\placeholder.txt" />
<Directory Id="aircraft57" Name="aircraft">
<Component Id="_comp58" Guid="7212c708-1909-4002-ba49-4f1081e32162">
<File Id="_59" Source="..\bin\release\aircraft\placeholder.txt" />
</Component>
<Directory Id="arducopter57" Name="arducopter">
<Component Id="_comp58" Guid="f084a180-18c9-41f6-8070-ae26bf831d1e">
<File Id="_59" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
<File Id="_60" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
<File Id="_61" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
<File Id="_62" Source="..\bin\release\aircraft\arducopter\initfile.xml" />
<File Id="_63" Source="..\bin\release\aircraft\arducopter\plus_quad2-set.xml" />
<File Id="_64" Source="..\bin\release\aircraft\arducopter\plus_quad2.xml" />
<File Id="_65" Source="..\bin\release\aircraft\arducopter\quad.nas" />
<File Id="_66" Source="..\bin\release\aircraft\arducopter\README" />
<Directory Id="arducopter59" Name="arducopter">
<Component Id="_comp60" Guid="5f433433-26df-44a9-b9c9-89aa3397030d">
<File Id="_61" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
<File Id="_62" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
<File Id="_63" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
<File Id="_64" Source="..\bin\release\aircraft\arducopter\initfile.xml" />
<File Id="_65" Source="..\bin\release\aircraft\arducopter\plus_quad2-set.xml" />
<File Id="_66" Source="..\bin\release\aircraft\arducopter\plus_quad2.xml" />
<File Id="_67" Source="..\bin\release\aircraft\arducopter\quad.nas" />
<File Id="_68" Source="..\bin\release\aircraft\arducopter\README" />
</Component>
<Directory Id="data66" Name="data">
<Component Id="_comp67" Guid="5dee70d9-d900-4409-bf27-2430cc6220d4">
<File Id="_68" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
<File Id="_69" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
<File Id="_70" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
<Directory Id="data68" Name="data">
<Component Id="_comp69" Guid="26f173bd-765b-43ba-8d28-2617728dfb2c">
<File Id="_70" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
<File Id="_71" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
<File Id="_72" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
</Component>
</Directory>
<Directory Id="Engines70" Name="Engines">
<Component Id="_comp71" Guid="bac95eb2-9cf0-452b-8c29-a4ab162de973">
<File Id="_72" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
<File Id="_73" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
<Directory Id="Engines72" Name="Engines">
<Component Id="_comp73" Guid="a0806084-173b-4ff2-969e-4ce5903d0d5f">
<File Id="_74" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
<File Id="_75" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
</Component>
</Directory>
<Directory Id="Models73" Name="Models">
<Component Id="_comp74" Guid="14cf59a2-751c-4329-83f2-094a85d80f21">
<File Id="_75" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
<File Id="_76" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
<File Id="_77" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
<File Id="_78" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.ac" />
<File Id="_79" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.xml" />
<File Id="_80" Source="..\bin\release\aircraft\arducopter\Models\quad.3ds" />
<File Id="_81" Source="..\bin\release\aircraft\arducopter\Models\shareware_output.3ds" />
<File Id="_82" Source="..\bin\release\aircraft\arducopter\Models\Untitled.ac" />
<File Id="_83" Source="..\bin\release\aircraft\arducopter\Models\Y6_test.ac" />
<Directory Id="Models75" Name="Models">
<Component Id="_comp76" Guid="1d1b8579-fe0d-49a5-b3b5-028fc65f3151">
<File Id="_77" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
<File Id="_78" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
<File Id="_79" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
<File Id="_80" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.ac" />
<File Id="_81" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.xml" />
<File Id="_82" Source="..\bin\release\aircraft\arducopter\Models\quad.3ds" />
<File Id="_83" Source="..\bin\release\aircraft\arducopter\Models\shareware_output.3ds" />
<File Id="_84" Source="..\bin\release\aircraft\arducopter\Models\Untitled.ac" />
<File Id="_85" Source="..\bin\release\aircraft\arducopter\Models\Y6_test.ac" />
</Component>
</Directory>
</Directory>
<Directory Id="Rascal83" Name="Rascal">
<Component Id="_comp84" Guid="957d112f-a39e-4619-a8a1-e66281fe43b9">
<File Id="_85" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
<File Id="_86" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
<File Id="_87" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
<File Id="_88" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim-set.xml" />
<File Id="_89" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim.xml" />
<File Id="_90" Source="..\bin\release\aircraft\Rascal\Rascal110-splash.rgb" />
<File Id="_91" Source="..\bin\release\aircraft\Rascal\README.Rascal" />
<File Id="_92" Source="..\bin\release\aircraft\Rascal\reset_CMAC.xml" />
<File Id="_93" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
<Directory Id="Rascal85" Name="Rascal">
<Component Id="_comp86" Guid="5dfbf7cf-8aa2-4837-88f0-c036f532d722">
<File Id="_87" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
<File Id="_88" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
<File Id="_89" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
<File Id="_90" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim-set.xml" />
<File Id="_91" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim.xml" />
<File Id="_92" Source="..\bin\release\aircraft\Rascal\Rascal110-splash.rgb" />
<File Id="_93" Source="..\bin\release\aircraft\Rascal\README.Rascal" />
<File Id="_94" Source="..\bin\release\aircraft\Rascal\reset_CMAC.xml" />
<File Id="_95" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
</Component>
<Directory Id="Dialogs93" Name="Dialogs">
<Component Id="_comp94" Guid="96a657ee-49de-494b-85d6-277b72a81d51">
<File Id="_95" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml" />
<File Id="_96" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml.new" />
<Directory Id="Dialogs95" Name="Dialogs">
<Component Id="_comp96" Guid="b5c4167d-062e-43c6-b97f-18bfbfaa8f31">
<File Id="_97" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml" />
<File Id="_98" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml.new" />
</Component>
</Directory>
<Directory Id="Engines96" Name="Engines">
<Component Id="_comp97" Guid="f1772147-fde4-4591-a0a7-bd5fa600c67e">
<File Id="_98" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
<File Id="_99" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml.new" />
<File Id="_100" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
<File Id="_101" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml.new" />
<Directory Id="Engines98" Name="Engines">
<Component Id="_comp99" Guid="76fcc1e7-b39d-4335-8af2-6c13643c8725">
<File Id="_100" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
<File Id="_101" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml.new" />
<File Id="_102" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
<File Id="_103" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml.new" />
</Component>
</Directory>
<Directory Id="Models101" Name="Models">
<Component Id="_comp102" Guid="b4f42a2c-ef80-4505-a614-1b6a2923feac">
<File Id="_103" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
<File Id="_104" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb.new" />
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
<File Id="_106" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac.new" />
<File Id="_107" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
<File Id="_108" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml.new" />
<File Id="_109" Source="..\bin\release\aircraft\Rascal\Models\smoke.png" />
<File Id="_110" Source="..\bin\release\aircraft\Rascal\Models\smoke.png.new" />
<File Id="_111" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml" />
<File Id="_112" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml.new" />
<File Id="_113" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac" />
<File Id="_114" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac.new" />
<File Id="_115" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml" />
<File Id="_116" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml.new" />
<Directory Id="Models103" Name="Models">
<Component Id="_comp104" Guid="c7c50e85-8e0a-4e79-b62f-b5b200315146">
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
<File Id="_106" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb.new" />
<File Id="_107" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
<File Id="_108" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac.new" />
<File Id="_109" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
<File Id="_110" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml.new" />
<File Id="_111" Source="..\bin\release\aircraft\Rascal\Models\smoke.png" />
<File Id="_112" Source="..\bin\release\aircraft\Rascal\Models\smoke.png.new" />
<File Id="_113" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml" />
<File Id="_114" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml.new" />
<File Id="_115" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac" />
<File Id="_116" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac.new" />
<File Id="_117" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml" />
<File Id="_118" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml.new" />
</Component>
</Directory>
<Directory Id="Systems116" Name="Systems">
<Component Id="_comp117" Guid="59ed6ff3-352f-4846-b737-f5a37ae497ed">
<File Id="_118" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
<File Id="_119" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml.new" />
<File Id="_120" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
<File Id="_121" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas.new" />
<File Id="_122" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
<File Id="_123" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml.new" />
<File Id="_124" Source="..\bin\release\aircraft\Rascal\Systems\main.nas" />
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\main.nas.new" />
<File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\ugear.nas" />
<Directory Id="Systems118" Name="Systems">
<Component Id="_comp119" Guid="0ecaf32f-1460-4a1a-a17b-74d3a0995b93">
<File Id="_120" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
<File Id="_121" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml.new" />
<File Id="_122" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
<File Id="_123" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas.new" />
<File Id="_124" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml.new" />
<File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\main.nas" />
<File Id="_127" Source="..\bin\release\aircraft\Rascal\Systems\main.nas.new" />
<File Id="_128" Source="..\bin\release\aircraft\Rascal\Systems\ugear.nas" />
</Component>
</Directory>
</Directory>
</Directory>
<Directory Id="Driver126" Name="Driver">
<Component Id="_comp127" Guid="d9776466-be68-424f-b076-ef3fb4766362">
<File Id="_128" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
<File Id="_129" Source="..\bin\release\Driver\Arduino MEGA 2560.inf.new" />
<Directory Id="Driver128" Name="Driver">
<Component Id="_comp129" Guid="515e59db-299e-4863-a730-ffd0ef02483b">
<File Id="_130" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
<File Id="_131" Source="..\bin\release\Driver\Arduino MEGA 2560.inf.new" />
</Component>
</Directory>
<Directory Id="es_ES129" Name="es-ES">
<Component Id="_comp130" Guid="1fb42ff8-9e61-49b3-a3c3-b3ecbfaf2d5f">
<File Id="_131" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="es_ES131" Name="es-ES">
<Component Id="_comp132" Guid="04d19c2c-1174-462d-855e-454f99b4dd33">
<File Id="_133" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
<Directory Id="fr131" Name="fr">
<Component Id="_comp132" Guid="aa277d0f-e449-4838-95a4-b8caba929e73">
<File Id="_133" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="fr133" Name="fr">
<Component Id="_comp134" Guid="c7e73622-81d5-4c92-903e-b71c8d69f7d2">
<File Id="_135" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
<Directory Id="it_IT133" Name="it-IT">
<Component Id="_comp134" Guid="32fba21d-c610-4d07-8740-60a5956ed784">
<File Id="_135" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="it_IT135" Name="it-IT">
<Component Id="_comp136" Guid="64d73ea4-50e4-4379-8915-50d314fc680c">
<File Id="_137" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
<Directory Id="jsbsim135" Name="jsbsim">
<Component Id="_comp136" Guid="d6eb33b4-51c0-4e8e-bcbd-b719ebade3f4">
<File Id="_137" Source="..\bin\release\jsbsim\fgout.xml" />
<File Id="_138" Source="..\bin\release\jsbsim\rascal_test.xml" />
<Directory Id="jsbsim137" Name="jsbsim">
<Component Id="_comp138" Guid="6584d317-3e83-4525-a2d8-48361fd6cced">
<File Id="_139" Source="..\bin\release\jsbsim\fgout.xml" />
<File Id="_140" Source="..\bin\release\jsbsim\rascal_test.xml" />
</Component>
</Directory>
<Directory Id="m3u138" Name="m3u">
<Component Id="_comp139" Guid="629b2aa0-faf6-4bba-81bc-a624c7b9b27b">
<File Id="_140" Source="..\bin\release\m3u\both.m3u" />
<File Id="_141" Source="..\bin\release\m3u\hud.m3u" />
<File Id="_142" Source="..\bin\release\m3u\map.m3u" />
<File Id="_143" Source="..\bin\release\m3u\networklink.kml" />
<Directory Id="m3u140" Name="m3u">
<Component Id="_comp141" Guid="e067cb13-59c1-44c2-b632-1c73d3da5dda">
<File Id="_142" Source="..\bin\release\m3u\both.m3u" />
<File Id="_143" Source="..\bin\release\m3u\GeoRefnetworklink.kml" />
<File Id="_144" Source="..\bin\release\m3u\hud.m3u" />
<File Id="_145" Source="..\bin\release\m3u\map.m3u" />
<File Id="_146" Source="..\bin\release\m3u\networklink.kml" />
</Component>
</Directory>
<Directory Id="pl143" Name="pl">
<Component Id="_comp144" Guid="552d60e0-5755-49b4-bca3-73ff0a8f345a">
<File Id="_145" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="pl146" Name="pl">
<Component Id="_comp147" Guid="c9dc4142-0fe8-4804-9cc1-97b669c6bb70">
<File Id="_148" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
<Directory Id="Resources145" Name="Resources">
<Component Id="_comp146" Guid="d0b46c4b-4222-441b-8c57-6dea9513559e">
<File Id="_147" Source="..\bin\release\Resources\MAVCmd.txt" />
<File Id="_148" Source="..\bin\release\Resources\MAVCmd.txt.new" />
<File Id="_149" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
<File Id="_150" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf.new" />
<Directory Id="Resources148" Name="Resources">
<Component Id="_comp149" Guid="ed3e0985-9010-4930-b36e-9be84fcbe408">
<File Id="_150" Source="..\bin\release\Resources\MAVCmd.txt" />
<File Id="_151" Source="..\bin\release\Resources\MAVCmd.txt.new" />
<File Id="_152" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
<File Id="_153" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf.new" />
</Component>
</Directory>
<Directory Id="ru_RU150" Name="ru-RU">
<Component Id="_comp151" Guid="964ca3d0-1802-4a4b-ba4b-2e6c1b1ab626">
<File Id="_152" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="ru_RU153" Name="ru-RU">
<Component Id="_comp154" Guid="2e0e6d6d-370a-4c2c-9331-e941060675bc">
<File Id="_155" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
<Directory Id="zh_Hans152" Name="zh-Hans">
<Component Id="_comp153" Guid="363b03dc-9b08-428c-80c9-711f08487df4">
<File Id="_154" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="zh_Hans155" Name="zh-Hans">
<Component Id="_comp156" Guid="381a4296-5113-4d10-880a-bd6bb6dbfe20">
<File Id="_157" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
<Directory Id="zh_TW154" Name="zh-TW">
<Component Id="_comp155" Guid="728fc93e-de0e-4229-94a7-672d48bfb8c2">
<File Id="_156" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
<Directory Id="zh_TW157" Name="zh-TW">
<Component Id="_comp158" Guid="c49d6f3f-8616-483e-9cf7-e6685b9fc785">
<File Id="_159" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
</Component>
</Directory>
@ -290,27 +293,27 @@
<ComponentRef Id="InstallDirPermissions" />
<ComponentRef Id="_comp1" />
<ComponentRef Id="_comp56" />
<ComponentRef Id="_comp58" />
<ComponentRef Id="_comp67" />
<ComponentRef Id="_comp71" />
<ComponentRef Id="_comp74" />
<ComponentRef Id="_comp84" />
<ComponentRef Id="_comp94" />
<ComponentRef Id="_comp97" />
<ComponentRef Id="_comp102" />
<ComponentRef Id="_comp117" />
<ComponentRef Id="_comp127" />
<ComponentRef Id="_comp130" />
<ComponentRef Id="_comp60" />
<ComponentRef Id="_comp69" />
<ComponentRef Id="_comp73" />
<ComponentRef Id="_comp76" />
<ComponentRef Id="_comp86" />
<ComponentRef Id="_comp96" />
<ComponentRef Id="_comp99" />
<ComponentRef Id="_comp104" />
<ComponentRef Id="_comp119" />
<ComponentRef Id="_comp129" />
<ComponentRef Id="_comp132" />
<ComponentRef Id="_comp134" />
<ComponentRef Id="_comp136" />
<ComponentRef Id="_comp139" />
<ComponentRef Id="_comp144" />
<ComponentRef Id="_comp146" />
<ComponentRef Id="_comp151" />
<ComponentRef Id="_comp153" />
<ComponentRef Id="_comp155" />
<ComponentRef Id="_comp138" />
<ComponentRef Id="_comp141" />
<ComponentRef Id="_comp147" />
<ComponentRef Id="_comp149" />
<ComponentRef Id="_comp154" />
<ComponentRef Id="_comp156" />
<ComponentRef Id="_comp158" />
<ComponentRef Id="ApplicationShortcut" />
@ -331,7 +334,7 @@
<Property Id="WIXUI_EXITDIALOGOPTIONALCHECKBOXTEXT" Value="Launch APM Planner" />
<!-- Step 3: Include the custom action -->
<Property Id="WixShellExecTarget" Value="[#_10]" />
<Property Id="WixShellExecTarget" Value="[#_12]" />
<CustomAction Id="LaunchApplication"
BinaryKey="WixCA"
DllEntry="WixShellExec"

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.1.*")]
[assembly: AssemblyFileVersion("1.1.67")]
[assembly: AssemblyFileVersion("1.1.70")]
[assembly: NeutralResourcesLanguageAttribute("")]

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,178 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>49, 13</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>波 特 率</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>47, 13</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>格  式</value>
</data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>47, 13</value>
</data>
<data name="label3.Text" xml:space="preserve">
<value>空  速</value>
</data>
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
<value>42, 13</value>
</data>
<data name="label4.Text" xml:space="preserve">
<value>网络ID</value>
</data>
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
<value>55, 13</value>
</data>
<data name="label5.Text" xml:space="preserve">
<value>发射功率</value>
</data>
<data name="label9.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label9.Text" xml:space="preserve">
<value>本地</value>
</data>
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label10.Text" xml:space="preserve">
<value>远程</value>
</data>
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
<value>47, 13</value>
</data>
<data name="label11.Text" xml:space="preserve">
<value>版  本</value>
</data>
<data name="BUT_savesettings.Text" xml:space="preserve">
<value>保存设置</value>
</data>
<data name="BUT_getcurrent.Text" xml:space="preserve">
<value>加载设置</value>
</data>
<data name="BUT_upload.Text" xml:space="preserve">
<value>上传固件 (本地)</value>
</data>
</root>

View File

@ -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);
}

View File

@ -1 +1 @@
1.1.4488.39145
1.1.4492.34709

View File

@ -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<string[]> 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 = "<table><tr><td><img src=\"" + Path.GetFileName(file).ToLower() + "\" width=500 /></td></tr></table>"
Text = "<table><tr><td><img src=\"" + Path.GetFileName(filename).ToLower() + "\" width=500 /></td></tr></table>"
},
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);
}
}
}
}
}

View File

@ -5,3 +5,6 @@ list below
----------------
Test Developer ...
Chris Anderson
Phil Cole after following the instructions explicitly.

View File

@ -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()

1555
cmake/Platform/Arduino.cmake Normal file

File diff suppressed because it is too large Load Diff

View File

@ -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)

View File

@ -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()

View File

@ -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}")

View File

@ -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 <LibraryName.h>" 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()

View File

@ -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()

View File

@ -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)

View File

@ -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

View File

@ -82,6 +82,8 @@ public:
// attitude
virtual Matrix3f get_dcm_matrix(void) = 0;
static const struct AP_Param::GroupInfo var_info[];
protected:
// pointer to compass object, if enabled
Compass * _compass;

View File

@ -23,6 +23,12 @@
// from the GPS and wait for the ground speed to get above GPS_SPEED_MIN
#define GPS_SPEED_RESET 100
// table of user settable parameters
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
AP_GROUPINFO("YAW_P", 0, AP_AHRS_DCM, _kp_yaw),
AP_GROUPEND
};
// run a full DCM update round
void
AP_AHRS_DCM::update(void)
@ -453,7 +459,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
// allow the yaw reference source to affect all 3 components
// of _omega_yaw_P as we need to be able to correctly hold a
// heading when roll and pitch are non-zero
_omega_yaw_P = error * _kp_yaw;
_omega_yaw_P = error * _kp_yaw.get();
// add yaw correction to integrator correction vector, but
// only for the z gyro. We rely on the accelerometers for x

View File

@ -17,7 +17,7 @@ public:
AP_AHRS_DCM(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps)
{
_kp_roll_pitch = 0.13;
_kp_yaw = 0.4;
_kp_yaw.set(0.4);
_dcm_matrix(Vector3f(1, 0, 0),
Vector3f(0, 1, 0),
Vector3f(0, 0, 1));
@ -42,10 +42,12 @@ public:
float get_error_rp(void);
float get_error_yaw(void);
// settable parameters
AP_Float _kp_yaw;
private:
float _kp_roll_pitch;
float _ki_roll_pitch;
float _kp_yaw;
float _ki_yaw;
bool _have_initial_yaw;

View File

@ -32,6 +32,9 @@ public:
float get_error_rp(void) { return 0; }
float get_error_yaw(void) { return 0; }
// settable parameters
AP_Float _kp_yaw;
private:
Vector3f _omega;
};